fast_vgicp.hpp 2.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #ifndef FAST_GICP_FAST_VGICP_HPP
  2. #define FAST_GICP_FAST_VGICP_HPP
  3. #include <unordered_map>
  4. #include <Eigen/Core>
  5. #include <Eigen/Geometry>
  6. #include <pcl/point_types.h>
  7. #include <pcl/point_cloud.h>
  8. #include <pcl/search/kdtree.h>
  9. #include <pcl/registration/registration.h>
  10. #include <fast_gicp/gicp/gicp_settings.hpp>
  11. #include <fast_gicp/gicp/fast_gicp.hpp>
  12. #include <fast_gicp/gicp/fast_vgicp_voxel.hpp>
  13. namespace fast_gicp {
  14. /**
  15. * @brief Fast Voxelized GICP algorithm boosted with OpenMP
  16. */
  17. template<typename PointSource, typename PointTarget>
  18. class FastVGICP : public FastGICP<PointSource, PointTarget> {
  19. public:
  20. using Scalar = float;
  21. using Matrix4 = typename pcl::Registration<PointSource, PointTarget, Scalar>::Matrix4;
  22. using PointCloudSource = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudSource;
  23. using PointCloudSourcePtr = typename PointCloudSource::Ptr;
  24. using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
  25. using PointCloudTarget = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudTarget;
  26. using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
  27. using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
  28. protected:
  29. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  30. using pcl::Registration<PointSource, PointTarget, Scalar>::target_;
  31. using FastGICP<PointSource, PointTarget>::num_threads_;
  32. using FastGICP<PointSource, PointTarget>::source_kdtree_;
  33. using FastGICP<PointSource, PointTarget>::target_kdtree_;
  34. using FastGICP<PointSource, PointTarget>::source_covs_;
  35. using FastGICP<PointSource, PointTarget>::target_covs_;
  36. public:
  37. FastVGICP();
  38. virtual ~FastVGICP() override;
  39. void setResolution(double resolution);
  40. void setVoxelAccumulationMode(VoxelAccumulationMode mode);
  41. void setNeighborSearchMethod(NeighborSearchMethod method);
  42. virtual void swapSourceAndTarget() override;
  43. virtual void setInputTarget(const PointCloudTargetConstPtr& cloud) override;
  44. protected:
  45. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  46. virtual void update_correspondences(const Eigen::Isometry3d& trans) override;
  47. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H = nullptr, Eigen::Matrix<double, 6, 1>* b = nullptr) override;
  48. virtual double compute_error(const Eigen::Isometry3d& trans) override;
  49. protected:
  50. double voxel_resolution_;
  51. NeighborSearchMethod search_method_;
  52. VoxelAccumulationMode voxel_mode_;
  53. std::unique_ptr<GaussianVoxelMap<PointTarget>> voxelmap_;
  54. std::vector<std::pair<int, GaussianVoxel::Ptr>> voxel_correspondences_;
  55. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> voxel_mahalanobis_;
  56. };
  57. } // namespace fast_gicp
  58. #endif