lsq_registration.hpp 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778
  1. #ifndef FAST_GICP_LSQ_REGISTRATION_HPP
  2. #define FAST_GICP_LSQ_REGISTRATION_HPP
  3. #include <Eigen/Core>
  4. #include <Eigen/Geometry>
  5. #include <pcl/point_types.h>
  6. #include <pcl/point_cloud.h>
  7. #include <pcl/registration/registration.h>
  8. namespace fast_gicp {
  9. enum class LSQ_OPTIMIZER_TYPE { GaussNewton, LevenbergMarquardt };
  10. template<typename PointSource, typename PointTarget>
  11. class LsqRegistration : public pcl::Registration<PointSource, PointTarget, float> {
  12. public:
  13. using Scalar = float;
  14. using Matrix4 = typename pcl::Registration<PointSource, PointTarget, Scalar>::Matrix4;
  15. using PointCloudSource = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudSource;
  16. using PointCloudSourcePtr = typename PointCloudSource::Ptr;
  17. using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;
  18. using PointCloudTarget = typename pcl::Registration<PointSource, PointTarget, Scalar>::PointCloudTarget;
  19. using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
  20. using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;
  21. protected:
  22. using pcl::Registration<PointSource, PointTarget, Scalar>::input_;
  23. using pcl::Registration<PointSource, PointTarget, Scalar>::nr_iterations_;
  24. using pcl::Registration<PointSource, PointTarget, Scalar>::max_iterations_;
  25. using pcl::Registration<PointSource, PointTarget, Scalar>::final_transformation_;
  26. using pcl::Registration<PointSource, PointTarget, Scalar>::transformation_epsilon_;
  27. using pcl::Registration<PointSource, PointTarget, Scalar>::converged_;
  28. public:
  29. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  30. LsqRegistration();
  31. virtual ~LsqRegistration();
  32. void setRotationEpsilon(double eps);
  33. void setInitialLambdaFactor(double init_lambda_factor);
  34. void setDebugPrint(bool lm_debug_print);
  35. const Eigen::Matrix<double, 6, 6>& getFinalHessian() const;
  36. virtual void swapSourceAndTarget() {}
  37. virtual void clearSource() {}
  38. virtual void clearTarget() {}
  39. protected:
  40. virtual void computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
  41. bool is_converged(const Eigen::Isometry3d& delta) const;
  42. virtual double linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H = nullptr, Eigen::Matrix<double, 6, 1>* b = nullptr) = 0;
  43. virtual double compute_error(const Eigen::Isometry3d& trans) = 0;
  44. bool step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta);
  45. bool step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta);
  46. bool step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta);
  47. protected:
  48. double rotation_epsilon_;
  49. LSQ_OPTIMIZER_TYPE lsq_optimizer_type_;
  50. int lm_max_iterations_;
  51. double lm_init_lambda_factor_;
  52. double lm_lambda_;
  53. bool lm_debug_print_;
  54. Eigen::Matrix<double, 6, 6> final_hessian_;
  55. };
  56. } // namespace fast_gicp
  57. #endif