fast_gicp_st.hpp 2.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  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/gicp/fast_gicp.hpp>
  10. #include <fast_gicp/gicp/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. protected:
  24. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  25. using pcl::Registration<PointSource, PointTarget, Scalar>::target_;
  26. using FastGICP<PointSource, PointTarget>::target_kdtree_;
  27. using FastGICP<PointSource, PointTarget>::correspondences_;
  28. using FastGICP<PointSource, PointTarget>::sq_distances_;
  29. using FastGICP<PointSource, PointTarget>::source_covs_;
  30. using FastGICP<PointSource, PointTarget>::target_covs_;
  31. using FastGICP<PointSource, PointTarget>::mahalanobis_;
  32. public:
  33. FastGICPSingleThread();
  34. virtual ~FastGICPSingleThread() override;
  35. protected:
  36. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  37. private:
  38. virtual void update_correspondences(const Eigen::Isometry3d& trans) override;
  39. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H = nullptr, Eigen::Matrix<double, 6, 1>* b = nullptr) override;
  40. virtual double compute_error(const Eigen::Isometry3d& trans) override;
  41. private:
  42. std::vector<float> second_sq_distances_;
  43. std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f>> anchors_;
  44. };
  45. } // namespace fast_gicp
  46. #endif