lsq_registration_impl.hpp 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169
  1. #include <fast_gicp/gicp/lsq_registration.hpp>
  2. #include <boost/format.hpp>
  3. #include <fast_gicp/so3/so3.hpp>
  4. namespace fast_gicp {
  5. template <typename PointTarget, typename PointSource>
  6. LsqRegistration<PointTarget, PointSource>::LsqRegistration() {
  7. this->reg_name_ = "LsqRegistration";
  8. max_iterations_ = 64;
  9. rotation_epsilon_ = 2e-3;
  10. transformation_epsilon_ = 5e-4;
  11. lsq_optimizer_type_ = LSQ_OPTIMIZER_TYPE::LevenbergMarquardt;
  12. lm_debug_print_ = false;
  13. lm_max_iterations_ = 10;
  14. lm_init_lambda_factor_ = 1e-9;
  15. lm_lambda_ = -1.0;
  16. final_hessian_.setIdentity();
  17. }
  18. template <typename PointTarget, typename PointSource>
  19. LsqRegistration<PointTarget, PointSource>::~LsqRegistration() {}
  20. template <typename PointTarget, typename PointSource>
  21. void LsqRegistration<PointTarget, PointSource>::setRotationEpsilon(double eps) {
  22. rotation_epsilon_ = eps;
  23. }
  24. template <typename PointTarget, typename PointSource>
  25. void LsqRegistration<PointTarget, PointSource>::setInitialLambdaFactor(double init_lambda_factor) {
  26. lm_init_lambda_factor_ = init_lambda_factor;
  27. }
  28. template <typename PointTarget, typename PointSource>
  29. void LsqRegistration<PointTarget, PointSource>::setDebugPrint(bool lm_debug_print) {
  30. lm_debug_print_ = lm_debug_print;
  31. }
  32. template <typename PointTarget, typename PointSource>
  33. const Eigen::Matrix<double, 6, 6>& LsqRegistration<PointTarget, PointSource>::getFinalHessian() const {
  34. return final_hessian_;
  35. }
  36. template <typename PointTarget, typename PointSource>
  37. void LsqRegistration<PointTarget, PointSource>::computeTransformation(PointCloudSource& output, const Matrix4& guess) {
  38. Eigen::Isometry3d x0 = Eigen::Isometry3d(guess.template cast<double>());
  39. lm_lambda_ = -1.0;
  40. converged_ = false;
  41. if (lm_debug_print_) {
  42. std::cout << "********************************************" << std::endl;
  43. std::cout << "***************** optimize *****************" << std::endl;
  44. std::cout << "********************************************" << std::endl;
  45. }
  46. for (int i = 0; i < max_iterations_ && !converged_; i++) {
  47. nr_iterations_ = i;
  48. Eigen::Isometry3d delta;
  49. if (!step_optimize(x0, delta)) {
  50. std::cerr << "lm not converged!!" << std::endl;
  51. break;
  52. }
  53. converged_ = is_converged(delta);
  54. }
  55. final_transformation_ = x0.cast<float>().matrix();
  56. pcl::transformPointCloud(*input_, output, final_transformation_);
  57. }
  58. template <typename PointTarget, typename PointSource>
  59. bool LsqRegistration<PointTarget, PointSource>::is_converged(const Eigen::Isometry3d& delta) const {
  60. double accum = 0.0;
  61. Eigen::Matrix3d R = delta.linear() - Eigen::Matrix3d::Identity();
  62. Eigen::Vector3d t = delta.translation();
  63. Eigen::Matrix3d r_delta = 1.0 / rotation_epsilon_ * R.array().abs();
  64. Eigen::Vector3d t_delta = 1.0 / transformation_epsilon_ * t.array().abs();
  65. return std::max(r_delta.maxCoeff(), t_delta.maxCoeff()) < 1;
  66. }
  67. template <typename PointTarget, typename PointSource>
  68. bool LsqRegistration<PointTarget, PointSource>::step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  69. switch (lsq_optimizer_type_) {
  70. case LSQ_OPTIMIZER_TYPE::LevenbergMarquardt:
  71. return step_lm(x0, delta);
  72. case LSQ_OPTIMIZER_TYPE::GaussNewton:
  73. return step_gn(x0, delta);
  74. }
  75. return step_lm(x0, delta);
  76. }
  77. template <typename PointTarget, typename PointSource>
  78. bool LsqRegistration<PointTarget, PointSource>::step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  79. Eigen::Matrix<double, 6, 6> H;
  80. Eigen::Matrix<double, 6, 1> b;
  81. double y0 = linearize(x0, &H, &b);
  82. Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H);
  83. Eigen::Matrix<double, 6, 1> d = solver.solve(-b);
  84. delta.setIdentity();
  85. delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
  86. delta.translation() = d.tail<3>();
  87. x0 = delta * x0;
  88. final_hessian_ = H;
  89. return true;
  90. }
  91. template <typename PointTarget, typename PointSource>
  92. bool LsqRegistration<PointTarget, PointSource>::step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  93. Eigen::Matrix<double, 6, 6> H;
  94. Eigen::Matrix<double, 6, 1> b;
  95. double y0 = linearize(x0, &H, &b);
  96. if (lm_lambda_ < 0.0) {
  97. lm_lambda_ = lm_init_lambda_factor_ * H.diagonal().array().abs().maxCoeff();
  98. }
  99. double nu = 2.0;
  100. for (int i = 0; i < lm_max_iterations_; i++) {
  101. Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H + lm_lambda_ * Eigen::Matrix<double, 6, 6>::Identity());
  102. Eigen::Matrix<double, 6, 1> d = solver.solve(-b);
  103. delta.setIdentity();
  104. delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
  105. delta.translation() = d.tail<3>();
  106. Eigen::Isometry3d xi = delta * x0;
  107. double yi = compute_error(xi);
  108. double rho = (y0 - yi) / (d.dot(lm_lambda_ * d - b));
  109. if (lm_debug_print_) {
  110. if (i == 0) {
  111. std::cout << boost::format("--- LM optimization ---\n%5s %15s %15s %15s %15s %15s %5s\n") % "i" % "y0" % "yi" % "rho" % "lambda" % "|delta|" % "dec";
  112. }
  113. char dec = rho > 0.0 ? 'x' : ' ';
  114. std::cout << boost::format("%5d %15g %15g %15g %15g %15g %5c") % i % y0 % yi % rho % lm_lambda_ % d.norm() % dec << std::endl;
  115. }
  116. if (rho < 0) {
  117. if (is_converged(delta)) {
  118. return true;
  119. }
  120. lm_lambda_ = nu * lm_lambda_;
  121. nu = 2 * nu;
  122. continue;
  123. }
  124. x0 = xi;
  125. lm_lambda_ = lm_lambda_ * std::max(1.0 / 3.0, 1 - std::pow(2 * rho - 1, 3));
  126. final_hessian_ = H;
  127. return true;
  128. }
  129. return false;
  130. }
  131. } // namespace fast_gicp