fast_vgicp.hpp 3.1 KB

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