Skip to content

Commit

Permalink
Enable and fix warnings (#100)
Browse files Browse the repository at this point in the history
* Enable and fix warnings

This enables warning flags for MSVC/gcc/clang and fixes the warnings
reported.

Co-authored-by: Ignacio Vizzo <ignaciovizzo@gmail.com>

* Replace lambda by range loop

---------

Co-authored-by: Ignacio Vizzo <ignaciovizzo@gmail.com>
  • Loading branch information
ahans and nachovizzo committed Mar 29, 2023
1 parent f1e8a84 commit 447bb7a
Show file tree
Hide file tree
Showing 11 changed files with 44 additions and 24 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/cpp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,13 @@ jobs:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: [ubuntu-22.04, ubuntu-20.04, windows-2019, macos-11]
os: [ubuntu-22.04, ubuntu-20.04, windows-2022, macos-11]
steps:
- uses: actions/checkout@v3
- name: Setup cmake
uses: jwlawson/actions-setup-cmake@v1.13
with:
cmake-version: "3.22.x"
cmake-version: "3.24.x"
- name: Configure CMake
run: cmake -B ${{github.workspace}}/build -DCMAKE_BUILD_TYPE=${{env.BUILD_TYPE}} ${{github.workspace}}/cpp/kiss_icp
- name: Build
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/pypi.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ jobs:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: [ubuntu-22.04, windows-2019, macos-11]
os: [ubuntu-22.04, windows-2022, macos-11]

steps:
- uses: actions/checkout@v3
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/python.yml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ jobs:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: [ubuntu-22.04, ubuntu-20.04, windows-2019, macos-11]
os: [ubuntu-22.04, ubuntu-20.04, windows-2022, macos-11]

steps:
- uses: actions/checkout@v3
Expand Down
2 changes: 1 addition & 1 deletion cpp/kiss_icp/3rdparty/tbb/tbb.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ ExternalProject_Get_Property(external_tbb INSTALL_DIR)
set(TBB_ROOT ${INSTALL_DIR} CACHE INTERNAL "TBB_ROOT Install directory")
add_library(TBBHelper INTERFACE)
add_dependencies(TBBHelper external_tbb)
target_include_directories(TBBHelper INTERFACE ${INSTALL_DIR}/include)
target_include_directories(TBBHelper SYSTEM INTERFACE ${INSTALL_DIR}/include)
target_link_directories(TBBHelper INTERFACE ${INSTALL_DIR}/lib)
target_link_libraries(TBBHelper INTERFACE tbb Threads::Threads)
add_library(TBB::tbb ALIAS TBBHelper)
2 changes: 1 addition & 1 deletion cpp/kiss_icp/3rdparty/tsl_robin/tsl_robin.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ if(NOT tessil_POPULATED)
FetchContent_Populate(tessil)
add_library(robin_map INTERFACE)
add_library(tsl::robin_map ALIAS robin_map)
target_include_directories(robin_map INTERFACE "$<BUILD_INTERFACE:${tessil_SOURCE_DIR}/include>")
target_include_directories(robin_map SYSTEM INTERFACE "$<BUILD_INTERFACE:${tessil_SOURCE_DIR}/include>")
list(APPEND headers "${tessil_SOURCE_DIR}/include/tsl/robin_growth_policy.h"
"${tessil_SOURCE_DIR}/include/tsl/robin_hash.h" "${tessil_SOURCE_DIR}/include/tsl/robin_map.h"
"${tessil_SOURCE_DIR}/include/tsl/robin_set.h")
Expand Down
26 changes: 23 additions & 3 deletions cpp/kiss_icp/cmake/CompilerOptions.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,29 @@
# SOFTWARE.
function(set_global_target_properties target)
target_compile_features(${target} PUBLIC cxx_std_17)
target_compile_options(${target} PRIVATE $<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-fcolor-diagnostics>)
target_compile_options(${target} PRIVATE $<$<COMPILE_LANG_AND_ID:CXX,GNU>:-fdiagnostics-color=always>)

target_compile_options(
${target}
PRIVATE # MSVC
$<$<COMPILE_LANG_AND_ID:CXX,MSVC>:/W4>
$<$<COMPILE_LANG_AND_ID:CXX,MSVC>:/WX>
# Clang/AppleClang
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-fcolor-diagnostics>
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-Werror>
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-Wall>
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-Wextra>
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-Wconversion>
$<$<COMPILE_LANG_AND_ID:CXX,Clang,AppleClang>:-Wno-sign-conversion>
# GNU
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-fdiagnostics-color=always>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Werror>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wall>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wextra>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-pedantic>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wcast-align>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wcast-qual>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wconversion>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Wdisabled-optimization>
$<$<COMPILE_LANG_AND_ID:CXX,GNU>:-Woverloaded-virtual>)
set(INCLUDE_DIRS ${PROJECT_SOURCE_DIR})
get_filename_component(INCLUDE_DIRS ${INCLUDE_DIRS} PATH)
target_include_directories(${target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}
Expand Down
3 changes: 2 additions & 1 deletion cpp/kiss_icp/core/Preprocessing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ std::vector<Eigen::Vector3d> VoxelDownsample(const std::vector<Eigen::Vector3d>
}
std::vector<Eigen::Vector3d> frame_dowsampled;
frame_dowsampled.reserve(grid.size());
for (const auto &[_, point] : grid) {
for (const auto &[voxel, point] : grid) {
(void)voxel;
frame_dowsampled.emplace_back(point);
}
return frame_dowsampled;
Expand Down
6 changes: 3 additions & 3 deletions cpp/kiss_icp/core/Registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,10 +83,10 @@ Sophus::SE3d AlignClouds(const std::vector<Eigen::Vector3d> &source,
auto Weight = [&](double residual2) { return square(th) / square(th + residual2); };
auto &[JTJ_private, JTr_private] = J;
for (auto i = r.begin(); i < r.end(); ++i) {
const auto &[J_r, r] = compute_jacobian_and_residual(i);
const double w = Weight(r.squaredNorm());
const auto &[J_r, residual] = compute_jacobian_and_residual(i);
const double w = Weight(residual.squaredNorm());
JTJ_private.noalias() += J_r.transpose() * w * J_r;
JTr_private.noalias() += J_r.transpose() * w * r;
JTr_private.noalias() += J_r.transpose() * w * residual;
}
return J;
},
Expand Down
6 changes: 4 additions & 2 deletions cpp/kiss_icp/core/VoxelHashMap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,8 +138,10 @@ std::vector<Eigen::Vector3d> VoxelHashMap::Pointcloud() const {
std::vector<Eigen::Vector3d> points;
points.reserve(max_points_per_voxel_ * map_.size());
for (const auto &[voxel, voxel_block] : map_) {
std::for_each(voxel_block.points.cbegin(), voxel_block.points.cend(),
[&](const auto &point) { points.emplace_back(point); });
(void)voxel;
for (const auto &point : voxel_block.points) {
points.push_back(point);
}
}
return points;
}
Expand Down
8 changes: 4 additions & 4 deletions cpp/kiss_icp/metrics/Metrics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,8 @@ std::tuple<float, float> SeqError(const std::vector<Eigen::Matrix4d> &poses_gt,
r_err += it.r_err;
}

double avg_trans_error = avg_trans_error = 100.0 * (t_err / float(err.size()));
double avg_rot_error = avg_rot_error = 100.0 * (r_err / float(err.size())) / 3.14 * 180.0;
double avg_trans_error = 100.0 * (t_err / static_cast<double>(err.size()));
double avg_rot_error = 100.0 * (r_err / static_cast<double>(err.size())) / 3.14 * 180.0;

return std::make_tuple(avg_trans_error, avg_rot_error);
}
Expand Down Expand Up @@ -185,8 +185,8 @@ std::tuple<float, float> AbsoluteTrajectoryError(const std::vector<Eigen::Matrix
ATE_trans += delta_t.squaredNorm();
}
// Get the RMSE
ATE_rot /= num_poses;
ATE_trans /= num_poses;
ATE_rot /= static_cast<double>(num_poses);
ATE_trans /= static_cast<double>(num_poses);
return std::make_tuple(std::sqrt(ATE_rot), std::sqrt(ATE_trans));
}
} // namespace kiss_icp::metrics
7 changes: 2 additions & 5 deletions cpp/kiss_icp/pipeline/KissICP.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,7 @@ class KissICP {
local_map_(config.voxel_size, config.max_range, config.max_points_per_voxel),
adaptive_threshold_(config.initial_threshold, config.min_motion_th, config.max_range) {}

KissICP()
: local_map_(config_.voxel_size, config_.max_range, config_.max_points_per_voxel),
adaptive_threshold_(config_.initial_threshold, config_.min_motion_th, config_.max_range) {
}
KissICP() : KissICP(KISSConfig{}) {}

public:
Vector3dVectorTuple RegisterFrame(const std::vector<Eigen::Vector3d> &frame);
Expand All @@ -80,8 +77,8 @@ class KissICP {
// KISS-ICP pipeline modules
std::vector<Sophus::SE3d> poses_;
KISSConfig config_;
AdaptiveThreshold adaptive_threshold_;
VoxelHashMap local_map_;
AdaptiveThreshold adaptive_threshold_;
};

} // namespace kiss_icp::pipeline

0 comments on commit 447bb7a

Please sign in to comment.