fast_gicp.hpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103
  1. #ifndef FAST_GICP_FAST_GICP_HPP
  2. #define FAST_GICP_FAST_GICP_HPP
  3. #include <Eigen/Core>
  4. #include <Eigen/Geometry>
  5. #include <pcl/point_types.h>
  6. #include <pcl/point_cloud.h>
  7. #include <pcl/search/search.h>
  8. #include <pcl/registration/registration.h>
  9. #include "lsq_registration.hpp"
  10. #include "gicp_settings.hpp"
  11. namespace fast_gicp {
  12. /**
  13. * @brief Fast GICP algorithm optimized for multi threading with OpenMP
  14. */
  15. template<typename PointSource, typename PointTarget, typename SearchMethodSource = pcl::search::KdTree<PointSource>, typename SearchMethodTarget = pcl::search::KdTree<PointTarget>>
  16. class FastGICP : public LsqRegistration<PointSource, PointTarget> {
  17. public:
  18. using Scalar = float;
  19. using Matrix4 = typename pcl::Registration<PointSource, PointTarget, Scalar>::Matrix4;
  20. using PointCloudSource = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudSource;
  21. using PointCloudSourcePtr = typename PointCloudSource::Ptr;
  22. using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
  23. using PointCloudTarget = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudTarget;
  24. using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
  25. using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
  26. #if PCL_VERSION >= PCL_VERSION_CALC(1, 10, 0)
  27. using Ptr = pcl::shared_ptr<FastGICP<PointSource, PointTarget>>;
  28. using ConstPtr = pcl::shared_ptr<const FastGICP<PointSource, PointTarget>>;
  29. #else
  30. using Ptr = boost::shared_ptr<FastGICP<PointSource, PointTarget>>;
  31. using ConstPtr = boost::shared_ptr<const FastGICP<PointSource, PointTarget>>;
  32. #endif
  33. protected:
  34. using pcl::Registration<PointSource, PointTarget, Scalar>::reg_name_;
  35. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  36. using pcl::Registration<PointSource, PointTarget, Scalar>::target_;
  37. using pcl::Registration<PointSource, PointTarget, Scalar>::corr_dist_threshold_;
  38. public:
  39. FastGICP();
  40. virtual ~FastGICP() override;
  41. void setNumThreads(int n);
  42. void setCorrespondenceRandomness(int k);
  43. void setRegularizationMethod(RegularizationMethod method);
  44. virtual void swapSourceAndTarget() override;
  45. virtual void clearSource() override;
  46. virtual void clearTarget() override;
  47. virtual void setInputSource(const PointCloudSourceConstPtr& cloud) override;
  48. virtual void setSourceCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs);
  49. virtual void setInputTarget(const PointCloudTargetConstPtr& cloud) override;
  50. virtual void setTargetCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs);
  51. const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& getSourceCovariances() const {
  52. return source_covs_;
  53. }
  54. const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& getTargetCovariances() const {
  55. return target_covs_;
  56. }
  57. protected:
  58. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  59. virtual void update_correspondences(const Eigen::Isometry3d& trans);
  60. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H, Eigen::Matrix<double, 6, 1>* b) override;
  61. virtual double compute_error(const Eigen::Isometry3d& trans) override;
  62. template<typename PointT>
  63. bool calculate_covariances(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, pcl::search::Search<PointT>& kdtree, std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covariances);
  64. protected:
  65. int num_threads_;
  66. int k_correspondences_;
  67. RegularizationMethod regularization_method_;
  68. std::shared_ptr<SearchMethodSource> search_source_;
  69. std::shared_ptr<SearchMethodTarget> search_target_;
  70. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> source_covs_;
  71. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> target_covs_;
  72. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> mahalanobis_;
  73. std::vector<int> correspondences_;
  74. std::vector<float> sq_distances_;
  75. };
  76. } // namespace fast_gicp
  77. #endif