cmake options

This commit is contained in:
k.koide 2024-03-28 20:27:14 +09:00
parent a7fc74a944
commit 61cc0e6051
18 changed files with 156 additions and 98 deletions

View File

@ -5,11 +5,22 @@ set(CMAKE_CXX_STANDARD 20)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake")
if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES)
set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Choose the type of build." FORCE)
set(CMAKE_BUILD_TYPE "Release" CACHE STRING "Choose the type of build." FORCE)
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release" "MinSizeRel" "RelWithDebInfo")
endif()
# Eigen is the sole mandatory dependency
find_package(Eigen3 REQUIRED)
find_package(OpenMP)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
option(BUILD_TESTS "Build test" OFF)
option(BUILD_BENCHMARKS "Build benchmarks" OFF)
option(BUILD_WITH_TBB "Build with TBB" ON)
option(BUILD_WITH_PCL "Build with PCL (required for benchmark and test only)" OFF)
option(BUILD_WITH_FAST_GICP "Build with fast_gicp (required for benchmark and test only)" OFF)
option(BUILD_WITH_IRIDESCENCE "Build with Iridescence (required for benchmark)" OFF)
option(BUILD_WITH_MARCH_NATIVE "Build with -march=native" OFF)
if(BUILD_WITH_MARCH_NATIVE)
@ -18,106 +29,101 @@ if(BUILD_WITH_MARCH_NATIVE)
set(CMAKE_CXX_FLAGS "-march=native ${CMAKE_CXX_FLAGS}")
endif()
find_package(fmt REQUIRED)
find_package(PCL REQUIRED)
find_package(TBB REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(Iridescence REQUIRED)
set(FAST_GICP_INCLUDE_DIR /home/koide/workspace/fast_gicp/include)
find_package(OpenMP)
if (OPENMP_FOUND)
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
endif()
###########
## Build ##
###########
# add_executable(small_gicp_test
# src/small_gicp_test.cpp
# )
# target_include_directories(small_gicp_test PUBLIC
# include
# ${PCL_INCLUDE_DIRS}
# ${TBB_INCLUDE_DIRS}
# ${EIGEN3_INCLUDE_DIR}
# ${Iridescence_INCLUDE_DIRS}
# )
# target_link_libraries(small_gicp_test
# ${PCL_LIBRARIES}
# ${TBB_LIBRARIES}
# ${Iridescence_LIBRARIES}
# )
# Helper library
add_library(small_gicp SHARED
src/small_gicp/registration/registration.cpp
src/small_gicp/registration/registration_helper.cpp
)
target_include_directories(small_gicp PUBLIC
include
${PCL_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
)
target_link_libraries(small_gicp
${PCL_LIBRARIES}
${TBB_LIBRARIES}
)
install(DIRECTORY include/ DESTINATION include)
install(TARGETS small_gicp DESTINATION lib)
###############
## Benchmark ##
###############
if(BUILD_BENCHMARKS)
find_package(fmt REQUIRED)
if (BUILD_WITH_TBB)
find_package(TBB REQUIRED)
add_compile_definitions(BUILD_WITH_TBB)
endif()
if (BUILD_WITH_PCL)
find_package(PCL REQUIRED)
add_compile_definitions(BUILD_WITH_PCL)
endif()
if (BUILD_WITH_IRIDESCENCE)
find_package(Iridescence REQUIRED)
add_compile_definitions(BUILD_WITH_IRIDESCENCE)
endif()
if (BUILD_WITH_FAST_GICP)
set(FAST_GICP_INCLUDE_DIR /home/koide/workspace/fast_gicp/include)
add_compile_definitions(BUILD_WITH_FAST_GICP)
endif()
add_executable(odometry_benchmark
src/small_gicp/util/benchmark_odom.cpp
src/odometry_benchmark_pcl.cpp
src/odometry_benchmark_fast_gicp.cpp
src/odometry_benchmark_fast_vgicp.cpp
src/odometry_benchmark_small_gicp.cpp
src/odometry_benchmark_small_gicp_omp.cpp
src/odometry_benchmark_small_vgicp_omp.cpp
src/odometry_benchmark_small_gicp_tbb.cpp
src/odometry_benchmark_small_vgicp_tbb.cpp
src/odometry_benchmark_small_vgicp_model_tbb.cpp
src/odometry_benchmark_small_gicp_tbb_flow.cpp
src/odometry_benchmark.cpp
)
target_include_directories(odometry_benchmark PUBLIC
include
${PCL_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${Iridescence_INCLUDE_DIRS}
${FAST_GICP_INCLUDE_DIR}
)
target_link_libraries(odometry_benchmark
fmt::fmt
${PCL_LIBRARIES}
${TBB_LIBRARIES}
${Iridescence_LIBRARIES}
)
# Odometry benchmark
add_executable(odometry_benchmark
src/small_gicp/util/benchmark_odom.cpp
src/odometry_benchmark_pcl.cpp
src/odometry_benchmark_fast_gicp.cpp
src/odometry_benchmark_fast_vgicp.cpp
src/odometry_benchmark_small_gicp.cpp
src/odometry_benchmark_small_gicp_omp.cpp
src/odometry_benchmark_small_vgicp_omp.cpp
src/odometry_benchmark_small_gicp_tbb.cpp
src/odometry_benchmark_small_vgicp_tbb.cpp
src/odometry_benchmark_small_vgicp_model_tbb.cpp
src/odometry_benchmark_small_gicp_tbb_flow.cpp
src/odometry_benchmark.cpp
)
target_include_directories(odometry_benchmark PUBLIC
include
${PCL_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${Iridescence_INCLUDE_DIRS}
${FAST_GICP_INCLUDE_DIR}
)
target_link_libraries(odometry_benchmark
fmt::fmt
${PCL_LIBRARIES}
${TBB_LIBRARIES}
${Iridescence_LIBRARIES}
)
add_executable(downsampling_benchmark
src/downsampling_benchmark.cpp
)
target_include_directories(downsampling_benchmark PUBLIC
include
${PCL_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
)
target_link_libraries(downsampling_benchmark
fmt::fmt
${PCL_LIBRARIES}
${TBB_LIBRARIES}
)
if(BUILD_WITH_PCL)
# Downsampling benchmark
add_executable(downsampling_benchmark
src/downsampling_benchmark.cpp
)
target_include_directories(downsampling_benchmark PUBLIC
include
${PCL_INCLUDE_DIRS}
${TBB_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
)
target_link_libraries(downsampling_benchmark
fmt::fmt
${PCL_LIBRARIES}
${TBB_LIBRARIES}
)
endif()
endif()
##########
## Test ##
##########
option(BUILD_TESTS "Build test" ON)
if(BUILD_TESTS)
find_package(PCL REQUIRED)
find_package(TBB REQUIRED)
include(FetchContent)
FetchContent_Declare(googletest URL https://github.com/google/googletest/archive/03597a01ee50ed33e9dfd640b249b4be3799d395.zip)
FetchContent_MakeAvailable(googletest)

View File

@ -52,6 +52,7 @@
#define NANOFLANN_OMP_HPP_
#include <atomic>
#include <iostream>
#include <small_gicp/ann/nanoflann.hpp>
namespace nanoflann {

View File

@ -8,7 +8,9 @@
#include <small_gicp/util/downsampling.hpp>
#include <small_gicp/benchmark/benchmark.hpp>
#ifdef BUILD_WITH_IRIDESCENCE
#include <guik/viewer/async_light_viewer.hpp>
#endif
namespace small_gicp {
@ -56,6 +58,7 @@ public:
const Eigen::Isometry3d T = estimate(downsampled);
traj.emplace_back(T);
#ifdef BUILD_WITH_IRIDESCENCE
if (params.visualize) {
auto async_viewer = guik::async_viewer();
z_range[0] = std::min<double>(z_range[0], T.translation().z() - 5.0f);
@ -65,6 +68,7 @@ public:
async_viewer->update_points(guik::anon(), voxelgrid_sampling(*downsampled, 1.0)->points, guik::Rainbow(T));
async_viewer->lookat(T.translation().cast<float>());
}
#endif
points[i].reset();

View File

@ -4,6 +4,12 @@
namespace small_gicp {
#ifdef _OPENMP
inline int omp_get_thread_num() {
return 0;
}
#endif
/// @brief Parallel reduction with OpenMP backend
struct ParallelReductionOMP {
ParallelReductionOMP() : num_threads(8) {}

View File

@ -7,7 +7,9 @@
#include <small_gicp/util/downsampling.hpp>
#include <small_gicp/util/downsampling_omp.hpp>
#ifdef BUILD_WITH_TBB
#include <small_gicp/util/downsampling_tbb.hpp>
#endif
#include <small_gicp/points/point_cloud.hpp>
#include <small_gicp/points/pcl_point.hpp>
#include <small_gicp/points/pcl_point_traits.hpp>
@ -75,7 +77,9 @@ int main(int argc, char** argv) {
std::cout << "max_num_frames=" << max_num_frames << std::endl;
std::cout << "num_threads=" << num_threads << std::endl;
#ifdef BUILD_WITH_TBB
tbb::global_control control(tbb::global_control::max_allowed_parallelism, num_threads);
#endif
KittiDataset kitti(dataset_path, max_num_frames);
std::cout << "num_frames=" << kitti.points.size() << std::endl;
@ -91,8 +95,10 @@ int main(int argc, char** argv) {
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
std::cout << fmt::format("{:25}: ", "small_voxelgrid") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
#ifdef BUILD_WITH_TBB
std::cout << fmt::format("{:25}: ", "small_voxelgrid_tbb") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points_pcl, 0.5, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });
@ -105,8 +111,10 @@ int main(int argc, char** argv) {
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
std::cout << fmt::format("{:25}: ", "small_voxelgrid") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
#ifdef BUILD_WITH_TBB
std::cout << fmt::format("{:25}: ", "small_voxelgrid_tbb") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points_pcl, leaf_size, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });
}

View File

@ -3,10 +3,6 @@
#include <small_gicp/benchmark/benchmark.hpp>
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <small_gicp/ann/kdtree.hpp>
#include <small_gicp/ann/kdtree_omp.hpp>
#include <small_gicp/ann/kdtree_tbb.hpp>
int main(int argc, char** argv) {
using namespace small_gicp;

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_FAST_GICP
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <pcl/point_types.h>
@ -59,4 +61,6 @@ private:
static auto fast_gicp_registry = register_odometry("fast_gicp", [](const OdometryEstimationParams& params) { return std::make_shared<FastGICPOdometryEstimation>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_FAST_GICP
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <pcl/point_types.h>
@ -62,4 +64,6 @@ private:
static auto fast_vgicp_registry = register_odometry("fast_vgicp", [](const OdometryEstimationParams& params) { return std::make_shared<FastVGICPOdometryEstimation>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_PCL
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <pcl/point_types.h>
@ -56,4 +58,6 @@ private:
static auto pcl_odom_registry = register_odometry("pcl", [](const OdometryEstimationParams& params) { return std::make_shared<PCLOnlineOdometryEstimation>(params); });
}
} // namespace small_gicp
#endif

View File

@ -54,7 +54,7 @@ private:
Eigen::Isometry3d T;
};
static auto small_gicp_tbb_registry =
static auto small_gicp_registry =
register_odometry("small_gicp", [](const OdometryEstimationParams& params) { return std::make_shared<SmallGICPOnlineOdometryEstimation>(params); });
} // namespace small_gicp

View File

@ -58,4 +58,4 @@ private:
static auto small_gicp_omp_registry =
register_odometry("small_gicp_omp", [](const OdometryEstimationParams& params) { return std::make_shared<SmallGICPOnlineOdometryEstimationOMP>(params); });
} // namespace small_gicp
} // namespace small_gicp

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_TBB
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <tbb/tbb.h>
@ -63,4 +65,6 @@ private:
static auto small_gicp_tbb_registry =
register_odometry("small_gicp_tbb", [](const OdometryEstimationParams& params) { return std::make_shared<SmallGICPOnlineOdometryEstimationTBB>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_TBB
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <tbb/tbb.h>
@ -30,7 +32,11 @@ public:
control(tbb::global_control::max_allowed_parallelism, params.num_threads),
throughput(0.0) {}
~SmallGICPFlowEstimationTBB() { guik::async_destroy(); }
~SmallGICPFlowEstimationTBB() {
#ifdef BUILD_WITH_IRIDESCENCE
guik::async_destroy();
#endif
}
std::vector<Eigen::Isometry3d> estimate(std::vector<PointCloud::Ptr>& points) override {
std::vector<Eigen::Isometry3d> traj;
@ -84,6 +90,7 @@ public:
report();
}
#ifdef BUILD_WITH_IRIDESCENCE
if (params.visualize) {
static Eigen::Vector2f z_range(0.0f, 0.0f);
z_range[0] = std::min<double>(z_range[0], T.translation().z() - 5.0f);
@ -94,6 +101,7 @@ public:
async_viewer->update_points(guik::anon(), input->points->points, guik::Rainbow(T));
async_viewer->update_points("points", input->points->points, guik::FlatOrange(T).set_point_scale(2.0f));
}
#endif
});
tbb::flow::make_edge(input_node, preprocess_node);
@ -135,4 +143,6 @@ private:
static auto small_gicp_tbb_flow_registry =
register_odometry("small_gicp_tbb_flow", [](const OdometryEstimationParams& params) { return std::make_shared<SmallGICPFlowEstimationTBB>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_TBB
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <tbb/tbb.h>
@ -57,4 +59,6 @@ private:
static auto small_gicp_model_tbb_registry =
register_odometry("small_vgicp_model_tbb", [](const OdometryEstimationParams& params) { return std::make_shared<SmallVGICPModelOnlineOdometryEstimationTBB>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -62,4 +62,4 @@ private:
static auto small_vgicp_omp_registry =
register_odometry("small_vgicp_omp", [](const OdometryEstimationParams& params) { return std::make_shared<SmallVGICPOnlineOdometryEstimationOMP>(params); });
} // namespace small_gicp
} // namespace small_gicp

View File

@ -1,3 +1,5 @@
#ifdef BUILD_WITH_TBB
#include <small_gicp/benchmark/benchmark_odom.hpp>
#include <tbb/tbb.h>
@ -66,4 +68,6 @@ private:
static auto small_gicp_tbb_registry =
register_odometry("small_vgicp_tbb", [](const OdometryEstimationParams& params) { return std::make_shared<SmallVGICPOnlineOdometryEstimationTBB>(params); });
} // namespace small_gicp
} // namespace small_gicp
#endif

View File

@ -1,7 +1,7 @@
#include <small_gicp/registration/registration_helper.hpp>
#include <small_gicp/ann/kdtree.hpp>
#include <small_gicp/ann/kdtree_tbb.hpp>
#include <small_gicp/ann/kdtree_omp.hpp>
#include <small_gicp/ann/gaussian_voxelmap.hpp>
#include <small_gicp/util/downsampling.hpp>
#include <small_gicp/util/downsampling_omp.hpp>

View File

@ -1,4 +1,3 @@
#include <fmt/format.h>
#include <gtest/gtest.h>
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
@ -180,7 +179,11 @@ INSTANTIATE_TEST_SUITE_P(
RegistrationTest,
RegistrationTest,
testing::Combine(testing::Values("ICP", "PLANE_ICP", "GICP", "VGICP"), testing::Values("SERIAL", "TBB", "OMP")),
[](const auto& info) { return fmt::format("{}_{}", std::get<0>(info.param), std::get<1>(info.param)); });
[](const auto& info) {
std::stringstream sst;
sst << std::get<0>(info.param) << "_" << std::get<1>(info.param);
return sst.str();
});
TEST_P(RegistrationTest, EmptyTest) {
const std::string factor = std::get<0>(GetParam());