diff --git a/CMakeLists.txt b/CMakeLists.txt index ba0f536..70b7a04 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,17 +6,11 @@ option(BUILD_apps "Build application programs" ON) option(BUILD_test "Build test programs" OFF) option(BUILD_PYTHON_BINDINGS "Build python bindings" OFF) -if(${CMAKE_SYSTEM_PROCESSOR} STREQUAL "aarch64") -else() - add_definitions(-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2) - set(CMAKE_C_FLAGS "-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2") - set(CMAKE_CXX_FLAGS "-msse -msse2 -msse3 -msse4 -msse4.1 -msse4.2") -endif() - set(CMAKE_BUILD_TYPE "Release") find_package(PCL REQUIRED) find_package(Eigen3 REQUIRED) +add_definitions(${PCL_DEFINITIONS}) if(DEFINED ENV{ROS_VERSION}) set(ROS_VERSION $ENV{ROS_VERSION}) @@ -150,7 +144,7 @@ if(BUILD_VGICP_CUDA) ) add_dependencies(fast_gicp fast_vgicp_cuda) if(catkin_FOUND) - install(TARGETS fast_vgicp_cuda + install(TARGETS fast_vgicp_cuda LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) endif() endif() @@ -171,7 +165,7 @@ if(catkin_FOUND) ################################### install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) - + install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.hpp") diff --git a/README.md b/README.md index b90de2f..ae7d990 100644 --- a/README.md +++ b/README.md @@ -23,6 +23,12 @@ This package is a collection of GICP-based fast point cloud registration algorit We have tested this package on Ubuntu 18.04/20.04 and CUDA 11.1. +On macOS when using `brew`, you might have to set up your depenencies like this + +``` +cmake .. "-DCMAKE_PREFIX_PATH=$(brew --prefix libomp)[;other-custom-prefixes]" -DQt5_DIR=$(brew --prefix qt@5)lib/cmake/Qt5 +``` + ### CUDA To enable the CUDA-powered implementations, set ```BUILD_VGICP_CUDA``` cmake option to ```ON```. diff --git a/include/fast_gicp/gicp/fast_gicp.hpp b/include/fast_gicp/gicp/fast_gicp.hpp index e1cd117..3e6b4c1 100755 --- a/include/fast_gicp/gicp/fast_gicp.hpp +++ b/include/fast_gicp/gicp/fast_gicp.hpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include #include @@ -16,7 +16,7 @@ namespace fast_gicp { /** * @brief Fast GICP algorithm optimized for multi threading with OpenMP */ -template +template, typename SearchMethodTarget = pcl::search::KdTree> class FastGICP : public LsqRegistration { public: using Scalar = float; @@ -79,7 +79,7 @@ class FastGICP : public LsqRegistration { virtual double compute_error(const Eigen::Isometry3d& trans) override; template - bool calculate_covariances(const typename pcl::PointCloud::ConstPtr& cloud, pcl::search::KdTree& kdtree, std::vector>& covariances); + bool calculate_covariances(const typename pcl::PointCloud::ConstPtr& cloud, pcl::search::Search& kdtree, std::vector>& covariances); protected: int num_threads_; @@ -87,8 +87,8 @@ class FastGICP : public LsqRegistration { RegularizationMethod regularization_method_; - std::shared_ptr> source_kdtree_; - std::shared_ptr> target_kdtree_; + std::shared_ptr search_source_; + std::shared_ptr search_target_; std::vector> source_covs_; std::vector> target_covs_; @@ -100,4 +100,4 @@ class FastGICP : public LsqRegistration { }; } // namespace fast_gicp -#endif \ No newline at end of file +#endif diff --git a/include/fast_gicp/gicp/fast_gicp_st.hpp b/include/fast_gicp/gicp/fast_gicp_st.hpp index d04ea2d..b7bd03b 100644 --- a/include/fast_gicp/gicp/fast_gicp_st.hpp +++ b/include/fast_gicp/gicp/fast_gicp_st.hpp @@ -38,7 +38,7 @@ class FastGICPSingleThread : public FastGICP { using pcl::Registration::input_; using pcl::Registration::target_; - using FastGICP::target_kdtree_; + using FastGICP::search_target_; using FastGICP::correspondences_; using FastGICP::sq_distances_; using FastGICP::source_covs_; diff --git a/include/fast_gicp/gicp/fast_vgicp.hpp b/include/fast_gicp/gicp/fast_vgicp.hpp index f57870a..7fa76ba 100644 --- a/include/fast_gicp/gicp/fast_vgicp.hpp +++ b/include/fast_gicp/gicp/fast_vgicp.hpp @@ -47,8 +47,8 @@ class FastVGICP : public FastGICP { using pcl::Registration::target_; using FastGICP::num_threads_; - using FastGICP::source_kdtree_; - using FastGICP::target_kdtree_; + using FastGICP::search_source_; + using FastGICP::search_target_; using FastGICP::source_covs_; using FastGICP::target_covs_; diff --git a/include/fast_gicp/gicp/impl/fast_gicp_impl.hpp b/include/fast_gicp/gicp/impl/fast_gicp_impl.hpp index 0ef6cb3..218de13 100644 --- a/include/fast_gicp/gicp/impl/fast_gicp_impl.hpp +++ b/include/fast_gicp/gicp/impl/fast_gicp_impl.hpp @@ -5,8 +5,8 @@ namespace fast_gicp { -template -FastGICP::FastGICP() { +template +FastGICP::FastGICP() { #ifdef _OPENMP num_threads_ = omp_get_max_threads(); #else @@ -18,15 +18,15 @@ FastGICP::FastGICP() { corr_dist_threshold_ = std::numeric_limits::max(); regularization_method_ = RegularizationMethod::PLANE; - source_kdtree_.reset(new pcl::search::KdTree); - target_kdtree_.reset(new pcl::search::KdTree); + search_source_.reset(new SearchMethodSource); + search_target_.reset(new SearchMethodTarget); } -template -FastGICP::~FastGICP() {} +template +FastGICP::~FastGICP() {} -template -void FastGICP::setNumThreads(int n) { +template +void FastGICP::setNumThreads(int n) { num_threads_ = n; #ifdef _OPENMP @@ -36,86 +36,86 @@ void FastGICP::setNumThreads(int n) { #endif } -template -void FastGICP::setCorrespondenceRandomness(int k) { +template +void FastGICP::setCorrespondenceRandomness(int k) { k_correspondences_ = k; } -template -void FastGICP::setRegularizationMethod(RegularizationMethod method) { +template +void FastGICP::setRegularizationMethod(RegularizationMethod method) { regularization_method_ = method; } -template -void FastGICP::swapSourceAndTarget() { +template +void FastGICP::swapSourceAndTarget() { input_.swap(target_); - source_kdtree_.swap(target_kdtree_); + search_source_.swap(search_target_); source_covs_.swap(target_covs_); correspondences_.clear(); sq_distances_.clear(); } -template -void FastGICP::clearSource() { +template +void FastGICP::clearSource() { input_.reset(); source_covs_.clear(); } -template -void FastGICP::clearTarget() { +template +void FastGICP::clearTarget() { target_.reset(); target_covs_.clear(); } -template -void FastGICP::setInputSource(const PointCloudSourceConstPtr& cloud) { +template +void FastGICP::setInputSource(const PointCloudSourceConstPtr& cloud) { if (input_ == cloud) { return; } pcl::Registration::setInputSource(cloud); - source_kdtree_->setInputCloud(cloud); + search_source_->setInputCloud(cloud); source_covs_.clear(); } -template -void FastGICP::setInputTarget(const PointCloudTargetConstPtr& cloud) { +template +void FastGICP::setInputTarget(const PointCloudTargetConstPtr& cloud) { if (target_ == cloud) { return; } pcl::Registration::setInputTarget(cloud); - target_kdtree_->setInputCloud(cloud); + search_target_->setInputCloud(cloud); target_covs_.clear(); } -template -void FastGICP::setSourceCovariances(const std::vector>& covs) { +template +void FastGICP::setSourceCovariances(const std::vector>& covs) { source_covs_ = covs; } -template -void FastGICP::setTargetCovariances(const std::vector>& covs) { +template +void FastGICP::setTargetCovariances(const std::vector>& covs) { target_covs_ = covs; } -template -void FastGICP::computeTransformation(PointCloudSource& output, const Matrix4& guess) { +template +void FastGICP::computeTransformation(PointCloudSource& output, const Matrix4& guess) { if (output.points.data() == input_->points.data() || output.points.data() == target_->points.data()) { throw std::invalid_argument("FastGICP: destination cloud cannot be identical to source or target"); } if (source_covs_.size() != input_->size()) { - calculate_covariances(input_, *source_kdtree_, source_covs_); + calculate_covariances(input_, *search_source_, source_covs_); } if (target_covs_.size() != target_->size()) { - calculate_covariances(target_, *target_kdtree_, target_covs_); + calculate_covariances(target_, *search_target_, target_covs_); } LsqRegistration::computeTransformation(output, guess); } -template -void FastGICP::update_correspondences(const Eigen::Isometry3d& trans) { +template +void FastGICP::update_correspondences(const Eigen::Isometry3d& trans) { assert(source_covs_.size() == input_->size()); assert(target_covs_.size() == target_->size()); @@ -133,7 +133,7 @@ void FastGICP::update_correspondences(const Eigen::Iso PointTarget pt; pt.getVector4fMap() = trans_f * input_->at(i).getVector4fMap(); - target_kdtree_->nearestKSearch(pt, 1, k_indices, k_sq_dists); + search_target_->nearestKSearch(pt, 1, k_indices, k_sq_dists); sq_distances_[i] = k_sq_dists[0]; correspondences_[i] = k_sq_dists[0] < corr_dist_threshold_ * corr_dist_threshold_ ? k_indices[0] : -1; @@ -154,8 +154,8 @@ void FastGICP::update_correspondences(const Eigen::Iso } } -template -double FastGICP::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H, Eigen::Matrix* b) { +template +double FastGICP::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix* H, Eigen::Matrix* b) { update_correspondences(trans); double sum_errors = 0.0; @@ -213,8 +213,8 @@ double FastGICP::linearize(const Eigen::Isometry3d& tr return sum_errors; } -template -double FastGICP::compute_error(const Eigen::Isometry3d& trans) { +template +double FastGICP::compute_error(const Eigen::Isometry3d& trans) { double sum_errors = 0.0; #pragma omp parallel for num_threads(num_threads_) reduction(+ : sum_errors) schedule(guided, 8) @@ -239,11 +239,11 @@ double FastGICP::compute_error(const Eigen::Isometry3d return sum_errors; } -template +template template -bool FastGICP::calculate_covariances( +bool FastGICP::calculate_covariances( const typename pcl::PointCloud::ConstPtr& cloud, - pcl::search::KdTree& kdtree, + pcl::search::Search& kdtree, std::vector>& covariances) { if (kdtree.getInputCloud() != cloud) { kdtree.setInputCloud(cloud); diff --git a/include/fast_gicp/gicp/impl/fast_gicp_st_impl.hpp b/include/fast_gicp/gicp/impl/fast_gicp_st_impl.hpp index 35d3443..9ec058b 100644 --- a/include/fast_gicp/gicp/impl/fast_gicp_st_impl.hpp +++ b/include/fast_gicp/gicp/impl/fast_gicp_st_impl.hpp @@ -53,7 +53,7 @@ void FastGICPSingleThread::update_correspondences(cons } } - target_kdtree_->nearestKSearch(pt, 2, k_indices, k_sq_dists); + search_target_->nearestKSearch(pt, 2, k_indices, k_sq_dists); correspondences_[i] = k_sq_dists[0] < this->corr_dist_threshold_ * this->corr_dist_threshold_ ? k_indices[0] : -1; sq_distances_[i] = k_sq_dists[0]; diff --git a/include/fast_gicp/gicp/impl/fast_vgicp_impl.hpp b/include/fast_gicp/gicp/impl/fast_vgicp_impl.hpp index 5879411..92e51e4 100644 --- a/include/fast_gicp/gicp/impl/fast_vgicp_impl.hpp +++ b/include/fast_gicp/gicp/impl/fast_vgicp_impl.hpp @@ -45,7 +45,7 @@ void FastVGICP::setVoxelAccumulationMode(VoxelAccumula template void FastVGICP::swapSourceAndTarget() { input_.swap(target_); - source_kdtree_.swap(target_kdtree_); + search_source_.swap(search_target_); source_covs_.swap(target_covs_); voxelmap_.reset(); voxel_correspondences_.clear();