fast_gicp_st.hpp 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768
  1. #ifndef FAST_GICP_FAST_GICP_ST_HPP
  2. #define FAST_GICP_FAST_GICP_ST_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.hpp"
  10. #include "gicp_settings.hpp"
  11. namespace fast_gicp {
  12. /**
  13. * @brief Fast GICP algorithm optimized for single threading
  14. */
  15. template<typename PointSource, typename PointTarget>
  16. class FastGICPSingleThread : public FastGICP<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. #if PCL_VERSION >= PCL_VERSION_CALC(1, 10, 0)
  24. using Ptr = pcl::shared_ptr<FastGICPSingleThread<PointSource, PointTarget>>;
  25. using ConstPtr = pcl::shared_ptr<const FastGICPSingleThread<PointSource, PointTarget>>;
  26. #else
  27. using Ptr = boost::shared_ptr<FastGICPSingleThread<PointSource, PointTarget>>;
  28. using ConstPtr = boost::shared_ptr<const FastGICPSingleThread<PointSource, PointTarget>>;
  29. #endif
  30. protected:
  31. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  32. using pcl::Registration<PointSource, PointTarget, Scalar>::target_;
  33. using FastGICP<PointSource, PointTarget>::search_target_;
  34. using FastGICP<PointSource, PointTarget>::correspondences_;
  35. using FastGICP<PointSource, PointTarget>::sq_distances_;
  36. using FastGICP<PointSource, PointTarget>::source_covs_;
  37. using FastGICP<PointSource, PointTarget>::target_covs_;
  38. using FastGICP<PointSource, PointTarget>::mahalanobis_;
  39. public:
  40. FastGICPSingleThread();
  41. virtual ~FastGICPSingleThread() override;
  42. protected:
  43. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  44. private:
  45. virtual void update_correspondences(const Eigen::Isometry3d& trans) override;
  46. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H = nullptr, Eigen::Matrix<double, 6, 1>* b = nullptr) override;
  47. virtual double compute_error(const Eigen::Isometry3d& trans) override;
  48. private:
  49. std::vector<float> second_sq_distances_;
  50. std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f>> anchors_;
  51. };
  52. } // namespace fast_gicp
  53. #endif