diff --git a/CMakeLists.txt b/CMakeLists.txt index ea03974..d1ce393 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -122,6 +122,7 @@ if(BUILD_BENCHMARKS) src/benchmark/odometry_benchmark_fast_gicp.cpp src/benchmark/odometry_benchmark_fast_vgicp.cpp src/benchmark/odometry_benchmark_small_gicp.cpp + src/benchmark/odometry_benchmark_small_gicp_pcl.cpp src/benchmark/odometry_benchmark_small_gicp_omp.cpp src/benchmark/odometry_benchmark_small_vgicp_omp.cpp src/benchmark/odometry_benchmark_small_gicp_tbb.cpp diff --git a/include/small_gicp/pcl/pcl_registration_impl.hpp b/include/small_gicp/pcl/pcl_registration_impl.hpp index 54898ce..3d7d4e3 100644 --- a/include/small_gicp/pcl/pcl_registration_impl.hpp +++ b/include/small_gicp/pcl/pcl_registration_impl.hpp @@ -116,6 +116,8 @@ void RegistrationPCL::computeTransformation(PointCloud } Registration registration; + registration.criteria.rotation_eps = rotation_epsilon_; + registration.criteria.translation_eps = transformation_epsilon_; registration.reduction.num_threads = num_threads_; registration.rejector.max_dist_sq = corr_dist_threshold_ * corr_dist_threshold_; registration.optimizer.verbose = verbose_; diff --git a/src/benchmark/odometry_benchmark_small_gicp_pcl.cpp b/src/benchmark/odometry_benchmark_small_gicp_pcl.cpp new file mode 100644 index 0000000..8fee6a9 --- /dev/null +++ b/src/benchmark/odometry_benchmark_small_gicp_pcl.cpp @@ -0,0 +1,65 @@ +#ifdef BUILD_WITH_PCL + +#include + +#include +#include + +#include +#include + +namespace small_gicp { + +class SmallGICPPCLOdometryEstimation : public OnlineOdometryEstimation { +public: + SmallGICPPCLOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) { + gicp.setCorrespondenceRandomness(params.num_neighbors); + gicp.setMaxCorrespondenceDistance(params.max_correspondence_distance); + gicp.setNumThreads(params.num_threads); + } + + Eigen::Isometry3d estimate(const PointCloud::Ptr& points) override { + auto points_pcl = pcl::make_shared>(); + points_pcl->resize(points->size()); + for (size_t i = 0; i < points->size(); i++) { + points_pcl->at(i).getVector4fMap() = points->point(i).template cast(); + } + + Stopwatch sw; + sw.start(); + + if (!gicp.getInputTarget()) { + gicp.setInputTarget(points_pcl); + return T; + } + + gicp.setInputSource(points_pcl); + pcl::PointCloud aligned; + gicp.align(aligned); + + sw.stop(); + reg_times.push(sw.msec()); + + T = T * Eigen::Isometry3d(gicp.getFinalTransformation().cast()); + gicp.swapSourceAndTarget(); + + return T; + } + + void report() override { // + std::cout << "registration_time_stats=" << reg_times.str() << " [msec/scan] total_throughput=" << total_times.str() << " [msec/scan]" << std::endl; + } + +private: + Summarizer reg_times; + + small_gicp::RegistrationPCL gicp; + Eigen::Isometry3d T; +}; + +static auto small_gicp_pcl_registry = + register_odometry("small_gicp_pcl", [](const OdometryEstimationParams& params) { return std::make_shared(params); }); + +} // namespace small_gicp + +#endif \ No newline at end of file