lsq_registration_impl.hpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. /***********************************************************************
  10. * BSD 3-Clause License
  11. *
  12. * Copyright (c) 2020, SMRT-AIST
  13. * All rights reserved.
  14. *
  15. * Redistribution and use in source and binary forms, with or without
  16. * modification, are permitted provided that the following conditions are met:
  17. *
  18. * 1. Redistributions of source code must retain the above copyright notice, this
  19. * list of conditions and the following disclaimer.
  20. *
  21. * 2. Redistributions in binary form must reproduce the above copyright notice,
  22. * this list of conditions and the following disclaimer in the documentation
  23. * and/or other materials provided with the distribution.
  24. *
  25. * 3. Neither the name of the copyright holder nor the names of its
  26. * contributors may be used to endorse or promote products derived from
  27. * this software without specific prior written permission.
  28. *
  29. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
  30. * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
  31. * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  32. * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
  33. * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
  34. * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
  35. * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  36. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
  37. * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
  38. * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  39. *************************************************************************/
  40. #include <boost/format.hpp>
  41. #include <nano_gicp/lsq_registration.hpp>
  42. #include <nano_gicp/gicp/so3.hpp>
  43. namespace nano_gicp {
  44. template <typename PointTarget, typename PointSource>
  45. LsqRegistration<PointTarget, PointSource>::LsqRegistration() {
  46. this->reg_name_ = "LsqRegistration";
  47. max_iterations_ = 64;
  48. rotation_epsilon_ = 2e-3;
  49. transformation_epsilon_ = 5e-4;
  50. lsq_optimizer_type_ = LSQ_OPTIMIZER_TYPE::LevenbergMarquardt;
  51. lm_debug_print_ = false;
  52. lm_max_iterations_ = 10;
  53. lm_init_lambda_factor_ = 1e-9;
  54. lm_lambda_ = -1.0;
  55. final_hessian_.setIdentity();
  56. }
  57. template <typename PointTarget, typename PointSource>
  58. LsqRegistration<PointTarget, PointSource>::~LsqRegistration() {}
  59. template <typename PointTarget, typename PointSource>
  60. void LsqRegistration<PointTarget, PointSource>::setRotationEpsilon(double eps) {
  61. rotation_epsilon_ = eps;
  62. }
  63. template <typename PointTarget, typename PointSource>
  64. void LsqRegistration<PointTarget, PointSource>::setInitialLambdaFactor(double init_lambda_factor) {
  65. lm_init_lambda_factor_ = init_lambda_factor;
  66. }
  67. template <typename PointTarget, typename PointSource>
  68. void LsqRegistration<PointTarget, PointSource>::setDebugPrint(bool lm_debug_print) {
  69. lm_debug_print_ = lm_debug_print;
  70. }
  71. template <typename PointTarget, typename PointSource>
  72. const Eigen::Matrix<double, 6, 6>& LsqRegistration<PointTarget, PointSource>::getFinalHessian() const {
  73. return final_hessian_;
  74. }
  75. template <typename PointTarget, typename PointSource>
  76. void LsqRegistration<PointTarget, PointSource>::computeTransformation(PointCloudSource& output, const Matrix4& guess) {
  77. Eigen::Isometry3d x0 = Eigen::Isometry3d(guess.template cast<double>());
  78. lm_lambda_ = -1.0;
  79. converged_ = false;
  80. if (lm_debug_print_) {
  81. std::cout << "********************************************" << std::endl;
  82. std::cout << "***************** optimize *****************" << std::endl;
  83. std::cout << "********************************************" << std::endl;
  84. }
  85. for (int i = 0; i < max_iterations_ && !converged_; i++) {
  86. nr_iterations_ = i;
  87. Eigen::Isometry3d delta;
  88. if (!step_optimize(x0, delta)) {
  89. std::cerr << "lm not converged!!" << std::endl;
  90. break;
  91. }
  92. converged_ = is_converged(delta);
  93. }
  94. final_transformation_ = x0.cast<float>().matrix();
  95. pcl::transformPointCloud(*input_, output, final_transformation_);
  96. }
  97. template <typename PointTarget, typename PointSource>
  98. bool LsqRegistration<PointTarget, PointSource>::is_converged(const Eigen::Isometry3d& delta) const {
  99. double accum = 0.0;
  100. Eigen::Matrix3d R = delta.linear() - Eigen::Matrix3d::Identity();
  101. Eigen::Vector3d t = delta.translation();
  102. Eigen::Matrix3d r_delta = 1.0 / rotation_epsilon_ * R.array().abs();
  103. Eigen::Vector3d t_delta = 1.0 / transformation_epsilon_ * t.array().abs();
  104. return std::max(r_delta.maxCoeff(), t_delta.maxCoeff()) < 1;
  105. }
  106. template <typename PointTarget, typename PointSource>
  107. bool LsqRegistration<PointTarget, PointSource>::step_optimize(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  108. switch (lsq_optimizer_type_) {
  109. case LSQ_OPTIMIZER_TYPE::LevenbergMarquardt:
  110. return step_lm(x0, delta);
  111. case LSQ_OPTIMIZER_TYPE::GaussNewton:
  112. return step_gn(x0, delta);
  113. }
  114. return step_lm(x0, delta);
  115. }
  116. template <typename PointTarget, typename PointSource>
  117. bool LsqRegistration<PointTarget, PointSource>::step_gn(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  118. Eigen::Matrix<double, 6, 6> H;
  119. Eigen::Matrix<double, 6, 1> b;
  120. double y0 = linearize(x0, &H, &b);
  121. Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H);
  122. Eigen::Matrix<double, 6, 1> d = solver.solve(-b);
  123. delta.setIdentity();
  124. delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
  125. delta.translation() = d.tail<3>();
  126. x0 = delta * x0;
  127. final_hessian_ = H;
  128. return true;
  129. }
  130. template <typename PointTarget, typename PointSource>
  131. bool LsqRegistration<PointTarget, PointSource>::step_lm(Eigen::Isometry3d& x0, Eigen::Isometry3d& delta) {
  132. Eigen::Matrix<double, 6, 6> H;
  133. Eigen::Matrix<double, 6, 1> b;
  134. double y0 = linearize(x0, &H, &b);
  135. if (lm_lambda_ < 0.0) {
  136. lm_lambda_ = lm_init_lambda_factor_ * H.diagonal().array().abs().maxCoeff();
  137. }
  138. double nu = 2.0;
  139. for (int i = 0; i < lm_max_iterations_; i++) {
  140. Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H + lm_lambda_ * Eigen::Matrix<double, 6, 6>::Identity());
  141. Eigen::Matrix<double, 6, 1> d = solver.solve(-b);
  142. delta.setIdentity();
  143. delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
  144. delta.translation() = d.tail<3>();
  145. Eigen::Isometry3d xi = delta * x0;
  146. double yi = compute_error(xi);
  147. double rho = (y0 - yi) / (d.dot(lm_lambda_ * d - b));
  148. if (lm_debug_print_) {
  149. if (i == 0) {
  150. std::cout << boost::format("--- LM optimization ---\n%5s %15s %15s %15s %15s %15s %5s\n") % "i" % "y0" % "yi" % "rho" % "lambda" % "|delta|" % "dec";
  151. }
  152. char dec = rho > 0.0 ? 'x' : ' ';
  153. std::cout << boost::format("%5d %15g %15g %15g %15g %15g %5c") % i % y0 % yi % rho % lm_lambda_ % d.norm() % dec << std::endl;
  154. }
  155. if (rho < 0) {
  156. if (is_converged(delta)) {
  157. return true;
  158. }
  159. lm_lambda_ = nu * lm_lambda_;
  160. nu = 2 * nu;
  161. continue;
  162. }
  163. x0 = xi;
  164. lm_lambda_ = lm_lambda_ * std::max(1.0 / 3.0, 1 - std::pow(2 * rho - 1, 3));
  165. final_hessian_ = H;
  166. return true;
  167. }
  168. return false;
  169. }
  170. } // namespace nano_gicp