fast_gicp.hpp 3.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  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/kdtree.h>
  8. #include <pcl/registration/registration.h>
  9. #include <fast_gicp/gicp/lsq_registration.hpp>
  10. #include <fast_gicp/gicp/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>
  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. protected:
  27. using pcl::Registration<PointSource, PointTarget, Scalar>::reg_name_;
  28. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  29. using pcl::Registration<PointSource, PointTarget, Scalar>::target_;
  30. using pcl::Registration<PointSource, PointTarget, Scalar>::corr_dist_threshold_;
  31. public:
  32. FastGICP();
  33. virtual ~FastGICP() override;
  34. void setNumThreads(int n);
  35. void setCorrespondenceRandomness(int k);
  36. void setRegularizationMethod(RegularizationMethod method);
  37. virtual void swapSourceAndTarget() override;
  38. virtual void clearSource() override;
  39. virtual void clearTarget() override;
  40. virtual void setInputSource(const PointCloudSourceConstPtr& cloud) override;
  41. virtual void setSourceCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs);
  42. virtual void setInputTarget(const PointCloudTargetConstPtr& cloud) override;
  43. virtual void setTargetCovariances(const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covs);
  44. const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& getSourceCovariances() const {
  45. return source_covs_;
  46. }
  47. const std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& getTargetCovariances() const {
  48. return target_covs_;
  49. }
  50. protected:
  51. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  52. virtual void update_correspondences(const Eigen::Isometry3d& trans);
  53. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H, Eigen::Matrix<double, 6, 1>* b) override;
  54. virtual double compute_error(const Eigen::Isometry3d& trans) override;
  55. template<typename PointT>
  56. bool calculate_covariances(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, pcl::search::KdTree<PointT>& kdtree, std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>& covariances);
  57. protected:
  58. int num_threads_;
  59. int k_correspondences_;
  60. RegularizationMethod regularization_method_;
  61. std::shared_ptr<pcl::search::KdTree<PointSource>> source_kdtree_;
  62. std::shared_ptr<pcl::search::KdTree<PointTarget>> target_kdtree_;
  63. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> source_covs_;
  64. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> target_covs_;
  65. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> mahalanobis_;
  66. std::vector<int> correspondences_;
  67. std::vector<float> sq_distances_;
  68. };
  69. } // namespace fast_gicp
  70. #endif