ndt_omp_impl.hpp 39 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955
  1. #include "ndt_omp.h"
  2. /*
  3. * Software License Agreement (BSD License)
  4. *
  5. * Point Cloud Library (PCL) - www.pointclouds.org
  6. * Copyright (c) 2010-2011, Willow Garage, Inc.
  7. * Copyright (c) 2012-, Open Perception, Inc.
  8. *
  9. * All rights reserved.
  10. *
  11. * Redistribution and use in source and binary forms, with or without
  12. * modification, are permitted provided that the following conditions
  13. * are met:
  14. *
  15. * * Redistributions of source code must retain the above copyright
  16. * notice, this list of conditions and the following disclaimer.
  17. * * Redistributions in binary form must reproduce the above
  18. * copyright notice, this list of conditions and the following
  19. * disclaimer in the documentation and/or other materials provided
  20. * with the distribution.
  21. * * Neither the name of the copyright holder(s) nor the names of its
  22. * contributors may be used to endorse or promote products derived
  23. * from this software without specific prior written permission.
  24. *
  25. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  26. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  27. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  28. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  29. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  30. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  31. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  32. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  33. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  34. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  35. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  36. * POSSIBILITY OF SUCH DAMAGE.
  37. *
  38. * $Id$
  39. *
  40. */
  41. #ifndef PCL_REGISTRATION_NDT_OMP_IMPL_H_
  42. #define PCL_REGISTRATION_NDT_OMP_IMPL_H_
  43. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  44. template<typename PointSource, typename PointTarget>
  45. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::NormalDistributionsTransform ()
  46. : target_cells_ ()
  47. , resolution_ (1.0f)
  48. , step_size_ (0.1)
  49. , outlier_ratio_ (0.55)
  50. , gauss_d1_ ()
  51. , gauss_d2_ ()
  52. , gauss_d3_ ()
  53. , trans_probability_ ()
  54. , j_ang_a_ (), j_ang_b_ (), j_ang_c_ (), j_ang_d_ (), j_ang_e_ (), j_ang_f_ (), j_ang_g_ (), j_ang_h_ ()
  55. , h_ang_a2_ (), h_ang_a3_ (), h_ang_b2_ (), h_ang_b3_ (), h_ang_c2_ (), h_ang_c3_ (), h_ang_d1_ (), h_ang_d2_ ()
  56. , h_ang_d3_ (), h_ang_e1_ (), h_ang_e2_ (), h_ang_e3_ (), h_ang_f1_ (), h_ang_f2_ (), h_ang_f3_ ()
  57. {
  58. reg_name_ = "NormalDistributionsTransform";
  59. double gauss_c1, gauss_c2;
  60. // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009]
  61. gauss_c1 = 10.0 * (1 - outlier_ratio_);
  62. gauss_c2 = outlier_ratio_ / pow (resolution_, 3);
  63. gauss_d3_ = -log (gauss_c2);
  64. gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3_;
  65. gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3_) / gauss_d1_);
  66. transformation_epsilon_ = 0.1;
  67. max_iterations_ = 35;
  68. search_method = DIRECT7;
  69. num_threads_ = omp_get_max_threads();
  70. }
  71. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  72. template<typename PointSource, typename PointTarget> void
  73. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
  74. {
  75. nr_iterations_ = 0;
  76. converged_ = false;
  77. double gauss_c1, gauss_c2;
  78. // Initializes the guassian fitting parameters (eq. 6.8) [Magnusson 2009]
  79. gauss_c1 = 10 * (1 - outlier_ratio_);
  80. gauss_c2 = outlier_ratio_ / pow (resolution_, 3);
  81. gauss_d3_ = -log (gauss_c2);
  82. gauss_d1_ = -log ( gauss_c1 + gauss_c2 ) - gauss_d3_;
  83. gauss_d2_ = -2 * log ((-log ( gauss_c1 * exp ( -0.5 ) + gauss_c2 ) - gauss_d3_) / gauss_d1_);
  84. if (guess != Eigen::Matrix4f::Identity ())
  85. {
  86. // Initialise final transformation to the guessed one
  87. final_transformation_ = guess;
  88. // Apply guessed transformation prior to search for neighbours
  89. transformPointCloud (output, output, guess);
  90. }
  91. Eigen::Transform<float, 3, Eigen::Affine, Eigen::ColMajor> eig_transformation;
  92. eig_transformation.matrix () = final_transformation_;
  93. // Convert initial guess matrix to 6 element transformation vector
  94. Eigen::Matrix<double, 6, 1> p, delta_p, score_gradient;
  95. Eigen::Vector3f init_translation = eig_transformation.translation ();
  96. Eigen::Vector3f init_rotation = eig_transformation.rotation ().eulerAngles (0, 1, 2);
  97. p << init_translation (0), init_translation (1), init_translation (2),
  98. init_rotation (0), init_rotation (1), init_rotation (2);
  99. Eigen::Matrix<double, 6, 6> hessian;
  100. double score = 0;
  101. double delta_p_norm;
  102. // Calculate derivates of initial transform vector, subsequent derivative calculations are done in the step length determination.
  103. score = computeDerivatives (score_gradient, hessian, output, p);
  104. while (!converged_)
  105. {
  106. // Store previous transformation
  107. previous_transformation_ = transformation_;
  108. // Solve for decent direction using newton method, line 23 in Algorithm 2 [Magnusson 2009]
  109. Eigen::JacobiSVD<Eigen::Matrix<double, 6, 6> > sv (hessian, Eigen::ComputeFullU | Eigen::ComputeFullV);
  110. // Negative for maximization as opposed to minimization
  111. delta_p = sv.solve (-score_gradient);
  112. //Calculate step length with guarnteed sufficient decrease [More, Thuente 1994]
  113. delta_p_norm = delta_p.norm ();
  114. if (delta_p_norm == 0 || delta_p_norm != delta_p_norm)
  115. {
  116. trans_probability_ = score / static_cast<double> (input_->points.size ());
  117. converged_ = delta_p_norm == delta_p_norm;
  118. return;
  119. }
  120. delta_p.normalize ();
  121. delta_p_norm = computeStepLengthMT (p, delta_p, delta_p_norm, step_size_, transformation_epsilon_ / 2, score, score_gradient, hessian, output);
  122. delta_p *= delta_p_norm;
  123. transformation_ = (Eigen::Translation<float, 3> (static_cast<float> (delta_p (0)), static_cast<float> (delta_p (1)), static_cast<float> (delta_p (2))) *
  124. Eigen::AngleAxis<float> (static_cast<float> (delta_p (3)), Eigen::Vector3f::UnitX ()) *
  125. Eigen::AngleAxis<float> (static_cast<float> (delta_p (4)), Eigen::Vector3f::UnitY ()) *
  126. Eigen::AngleAxis<float> (static_cast<float> (delta_p (5)), Eigen::Vector3f::UnitZ ())).matrix ();
  127. p = p + delta_p;
  128. // Update Visualizer (untested)
  129. if (update_visualizer_ != 0)
  130. update_visualizer_ (output, std::vector<int>(), *target_, std::vector<int>() );
  131. if (nr_iterations_ > max_iterations_ ||
  132. (nr_iterations_ && (std::fabs (delta_p_norm) < transformation_epsilon_)))
  133. {
  134. converged_ = true;
  135. }
  136. nr_iterations_++;
  137. }
  138. // Store transformation probability. The realtive differences within each scan registration are accurate
  139. // but the normalization constants need to be modified for it to be globally accurate
  140. trans_probability_ = score / static_cast<double> (input_->points.size ());
  141. }
  142. #ifndef _OPENMP
  143. int omp_get_max_threads() { return 1; }
  144. int omp_get_thread_num() { return 0; }
  145. #endif
  146. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  147. template<typename PointSource, typename PointTarget> double
  148. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeDerivatives(Eigen::Matrix<double, 6, 1> &score_gradient,
  149. Eigen::Matrix<double, 6, 6> &hessian,
  150. PointCloudSource &trans_cloud,
  151. Eigen::Matrix<double, 6, 1> &p,
  152. bool compute_hessian)
  153. {
  154. score_gradient.setZero();
  155. hessian.setZero();
  156. double score = 0;
  157. std::vector<double> scores(num_threads_);
  158. std::vector<Eigen::Matrix<double, 6, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 1>>> score_gradients(num_threads_);
  159. std::vector<Eigen::Matrix<double, 6, 6>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 6>>> hessians(num_threads_);
  160. for (int i = 0; i < num_threads_; i++) {
  161. scores[i] = 0;
  162. score_gradients[i].setZero();
  163. hessians[i].setZero();
  164. }
  165. // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009]
  166. computeAngleDerivatives(p);
  167. std::vector<std::vector<TargetGridLeafConstPtr>> neighborhoods(num_threads_);
  168. std::vector<std::vector<float>> distancess(num_threads_);
  169. // Update gradient and hessian for each point, line 17 in Algorithm 2 [Magnusson 2009]
  170. #pragma omp parallel for num_threads(num_threads_) schedule(guided, 8)
  171. for (int idx = 0; idx < input_->points.size(); idx++)
  172. {
  173. int thread_n = omp_get_thread_num();
  174. // Original Point and Transformed Point
  175. PointSource x_pt, x_trans_pt;
  176. // Original Point and Transformed Point (for math)
  177. Eigen::Vector3d x, x_trans;
  178. // Occupied Voxel
  179. TargetGridLeafConstPtr cell;
  180. // Inverse Covariance of Occupied Voxel
  181. Eigen::Matrix3d c_inv;
  182. // Initialize Point Gradient and Hessian
  183. Eigen::Matrix<float, 4, 6> point_gradient_;
  184. Eigen::Matrix<float, 24, 6> point_hessian_;
  185. point_gradient_.setZero();
  186. point_gradient_.block<3, 3>(0, 0).setIdentity();
  187. point_hessian_.setZero();
  188. x_trans_pt = trans_cloud.points[idx];
  189. auto& neighborhood = neighborhoods[thread_n];
  190. auto& distances = distancess[thread_n];
  191. // Find nieghbors (Radius search has been experimentally faster than direct neighbor checking.
  192. switch (search_method) {
  193. case KDTREE:
  194. target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
  195. break;
  196. case DIRECT26:
  197. target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);
  198. break;
  199. default:
  200. case DIRECT7:
  201. target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood);
  202. break;
  203. case DIRECT1:
  204. target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood);
  205. break;
  206. }
  207. double score_pt = 0;
  208. Eigen::Matrix<double, 6, 1> score_gradient_pt = Eigen::Matrix<double, 6, 1>::Zero();
  209. Eigen::Matrix<double, 6, 6> hessian_pt = Eigen::Matrix<double, 6, 6>::Zero();
  210. for (typename std::vector<TargetGridLeafConstPtr>::iterator neighborhood_it = neighborhood.begin(); neighborhood_it != neighborhood.end(); neighborhood_it++)
  211. {
  212. cell = *neighborhood_it;
  213. x_pt = input_->points[idx];
  214. x = Eigen::Vector3d(x_pt.x, x_pt.y, x_pt.z);
  215. x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z);
  216. // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
  217. x_trans -= cell->getMean();
  218. // Uses precomputed covariance for speed.
  219. c_inv = cell->getInverseCov();
  220. // Compute derivative of transform function w.r.t. transform vector, J_E and H_E in Equations 6.18 and 6.20 [Magnusson 2009]
  221. computePointDerivatives(x, point_gradient_, point_hessian_);
  222. // Update score, gradient and hessian, lines 19-21 in Algorithm 2, according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009]
  223. score_pt += updateDerivatives(score_gradient_pt, hessian_pt, point_gradient_, point_hessian_, x_trans, c_inv, compute_hessian);
  224. }
  225. scores[thread_n] += score_pt;
  226. score_gradients[thread_n].noalias() += score_gradient_pt;
  227. hessians[thread_n].noalias() += hessian_pt;
  228. }
  229. for (int i = 0; i < num_threads_; i++) {
  230. score += scores[i];
  231. score_gradient += score_gradients[i];
  232. hessian += hessians[i];
  233. }
  234. return (score);
  235. }
  236. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  237. template<typename PointSource, typename PointTarget> void
  238. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeAngleDerivatives(Eigen::Matrix<double, 6, 1> &p, bool compute_hessian)
  239. {
  240. // Simplified math for near 0 angles
  241. double cx, cy, cz, sx, sy, sz;
  242. if (fabs(p(3)) < 10e-5)
  243. {
  244. //p(3) = 0;
  245. cx = 1.0;
  246. sx = 0.0;
  247. }
  248. else
  249. {
  250. cx = cos(p(3));
  251. sx = sin(p(3));
  252. }
  253. if (fabs(p(4)) < 10e-5)
  254. {
  255. //p(4) = 0;
  256. cy = 1.0;
  257. sy = 0.0;
  258. }
  259. else
  260. {
  261. cy = cos(p(4));
  262. sy = sin(p(4));
  263. }
  264. if (fabs(p(5)) < 10e-5)
  265. {
  266. //p(5) = 0;
  267. cz = 1.0;
  268. sz = 0.0;
  269. }
  270. else
  271. {
  272. cz = cos(p(5));
  273. sz = sin(p(5));
  274. }
  275. // Precomputed angular gradiant components. Letters correspond to Equation 6.19 [Magnusson 2009]
  276. j_ang_a_ << (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy);
  277. j_ang_b_ << (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy);
  278. j_ang_c_ << (-sy * cz), sy * sz, cy;
  279. j_ang_d_ << sx * cy * cz, (-sx * cy * sz), sx * sy;
  280. j_ang_e_ << (-cx * cy * cz), cx * cy * sz, (-cx * sy);
  281. j_ang_f_ << (-cy * sz), (-cy * cz), 0;
  282. j_ang_g_ << (cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0;
  283. j_ang_h_ << (sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0;
  284. j_ang.setZero();
  285. j_ang.row(0).noalias() = Eigen::Vector4f((-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy), 0.0f);
  286. j_ang.row(1).noalias() = Eigen::Vector4f((cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy), 0.0f);
  287. j_ang.row(2).noalias() = Eigen::Vector4f((-sy * cz), sy * sz, cy, 0.0f);
  288. j_ang.row(3).noalias() = Eigen::Vector4f(sx * cy * cz, (-sx * cy * sz), sx * sy, 0.0f);
  289. j_ang.row(4).noalias() = Eigen::Vector4f((-cx * cy * cz), cx * cy * sz, (-cx * sy), 0.0f);
  290. j_ang.row(5).noalias() = Eigen::Vector4f((-cy * sz), (-cy * cz), 0, 0.0f);
  291. j_ang.row(6).noalias() = Eigen::Vector4f((cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0, 0.0f);
  292. j_ang.row(7).noalias() = Eigen::Vector4f((sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0, 0.0f);
  293. if (compute_hessian)
  294. {
  295. // Precomputed angular hessian components. Letters correspond to Equation 6.21 and numbers correspond to row index [Magnusson 2009]
  296. h_ang_a2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy;
  297. h_ang_a3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy);
  298. h_ang_b2_ << (cx * cy * cz), (-cx * cy * sz), (cx * sy);
  299. h_ang_b3_ << (sx * cy * cz), (-sx * cy * sz), (sx * sy);
  300. h_ang_c2_ << (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0;
  301. h_ang_c3_ << (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0;
  302. h_ang_d1_ << (-cy * cz), (cy * sz), (sy);
  303. h_ang_d2_ << (-sx * sy * cz), (sx * sy * sz), (sx * cy);
  304. h_ang_d3_ << (cx * sy * cz), (-cx * sy * sz), (-cx * cy);
  305. h_ang_e1_ << (sy * sz), (sy * cz), 0;
  306. h_ang_e2_ << (-sx * cy * sz), (-sx * cy * cz), 0;
  307. h_ang_e3_ << (cx * cy * sz), (cx * cy * cz), 0;
  308. h_ang_f1_ << (-cy * cz), (cy * sz), 0;
  309. h_ang_f2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0;
  310. h_ang_f3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0;
  311. h_ang.setZero();
  312. h_ang.row(0).noalias() = Eigen::Vector4f((-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy, 0.0f); // a2
  313. h_ang.row(1).noalias() = Eigen::Vector4f((-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy), 0.0f); // a3
  314. h_ang.row(2).noalias() = Eigen::Vector4f((cx * cy * cz), (-cx * cy * sz), (cx * sy), 0.0f); // b2
  315. h_ang.row(3).noalias() = Eigen::Vector4f((sx * cy * cz), (-sx * cy * sz), (sx * sy), 0.0f); // b3
  316. h_ang.row(4).noalias() = Eigen::Vector4f((-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0, 0.0f); // c2
  317. h_ang.row(5).noalias() = Eigen::Vector4f((cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0, 0.0f); // c3
  318. h_ang.row(6).noalias() = Eigen::Vector4f((-cy * cz), (cy * sz), (sy), 0.0f); // d1
  319. h_ang.row(7).noalias() = Eigen::Vector4f((-sx * sy * cz), (sx * sy * sz), (sx * cy), 0.0f); // d2
  320. h_ang.row(8).noalias() = Eigen::Vector4f((cx * sy * cz), (-cx * sy * sz), (-cx * cy), 0.0f); // d3
  321. h_ang.row(9).noalias() = Eigen::Vector4f((sy * sz), (sy * cz), 0, 0.0f); // e1
  322. h_ang.row(10).noalias() = Eigen::Vector4f ((-sx * cy * sz), (-sx * cy * cz), 0, 0.0f); // e2
  323. h_ang.row(11).noalias() = Eigen::Vector4f ((cx * cy * sz), (cx * cy * cz), 0, 0.0f); // e3
  324. h_ang.row(12).noalias() = Eigen::Vector4f ((-cy * cz), (cy * sz), 0, 0.0f); // f1
  325. h_ang.row(13).noalias() = Eigen::Vector4f ((-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0, 0.0f); // f2
  326. h_ang.row(14).noalias() = Eigen::Vector4f ((-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0, 0.0f); // f3
  327. }
  328. }
  329. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  330. template<typename PointSource, typename PointTarget> void
  331. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix<float, 4, 6>& point_gradient_, Eigen::Matrix<float, 24, 6>& point_hessian_, bool compute_hessian) const
  332. {
  333. Eigen::Vector4f x4(x[0], x[1], x[2], 0.0f);
  334. // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  335. // Derivative w.r.t. ith element of transform vector corresponds to column i, Equation 6.18 and 6.19 [Magnusson 2009]
  336. Eigen::Matrix<float, 8, 1> x_j_ang = j_ang * x4;
  337. point_gradient_(1, 3) = x_j_ang[0];
  338. point_gradient_(2, 3) = x_j_ang[1];
  339. point_gradient_(0, 4) = x_j_ang[2];
  340. point_gradient_(1, 4) = x_j_ang[3];
  341. point_gradient_(2, 4) = x_j_ang[4];
  342. point_gradient_(0, 5) = x_j_ang[5];
  343. point_gradient_(1, 5) = x_j_ang[6];
  344. point_gradient_(2, 5) = x_j_ang[7];
  345. if (compute_hessian)
  346. {
  347. Eigen::Matrix<float, 16, 1> x_h_ang = h_ang * x4;
  348. // Vectors from Equation 6.21 [Magnusson 2009]
  349. Eigen::Vector4f a (0, x_h_ang[0], x_h_ang[1], 0.0f);
  350. Eigen::Vector4f b (0, x_h_ang[2], x_h_ang[3], 0.0f);
  351. Eigen::Vector4f c (0, x_h_ang[4], x_h_ang[5], 0.0f);
  352. Eigen::Vector4f d (x_h_ang[6], x_h_ang[7], x_h_ang[8], 0.0f);
  353. Eigen::Vector4f e (x_h_ang[9], x_h_ang[10], x_h_ang[11], 0.0f);
  354. Eigen::Vector4f f (x_h_ang[12], x_h_ang[13], x_h_ang[14], 0.0f);
  355. // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  356. // Derivative w.r.t. ith and jth elements of transform vector corresponds to the 3x1 block matrix starting at (3i,j), Equation 6.20 and 6.21 [Magnusson 2009]
  357. point_hessian_.block<4, 1>((9/3)*4, 3) = a;
  358. point_hessian_.block<4, 1>((12/3)*4, 3) = b;
  359. point_hessian_.block<4, 1>((15/3)*4, 3) = c;
  360. point_hessian_.block<4, 1>((9/3)*4, 4) = b;
  361. point_hessian_.block<4, 1>((12/3)*4, 4) = d;
  362. point_hessian_.block<4, 1>((15/3)*4, 4) = e;
  363. point_hessian_.block<4, 1>((9/3)*4, 5) = c;
  364. point_hessian_.block<4, 1>((12/3)*4, 5) = e;
  365. point_hessian_.block<4, 1>((15/3)*4, 5) = f;
  366. }
  367. }
  368. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  369. template<typename PointSource, typename PointTarget> void
  370. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computePointDerivatives(Eigen::Vector3d &x, Eigen::Matrix<double, 3, 6>& point_gradient_, Eigen::Matrix<double, 18, 6>& point_hessian_, bool compute_hessian) const
  371. {
  372. // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  373. // Derivative w.r.t. ith element of transform vector corresponds to column i, Equation 6.18 and 6.19 [Magnusson 2009]
  374. point_gradient_(1, 3) = x.dot(j_ang_a_);
  375. point_gradient_(2, 3) = x.dot(j_ang_b_);
  376. point_gradient_(0, 4) = x.dot(j_ang_c_);
  377. point_gradient_(1, 4) = x.dot(j_ang_d_);
  378. point_gradient_(2, 4) = x.dot(j_ang_e_);
  379. point_gradient_(0, 5) = x.dot(j_ang_f_);
  380. point_gradient_(1, 5) = x.dot(j_ang_g_);
  381. point_gradient_(2, 5) = x.dot(j_ang_h_);
  382. if (compute_hessian)
  383. {
  384. // Vectors from Equation 6.21 [Magnusson 2009]
  385. Eigen::Vector3d a, b, c, d, e, f;
  386. a << 0, x.dot(h_ang_a2_), x.dot(h_ang_a3_);
  387. b << 0, x.dot(h_ang_b2_), x.dot(h_ang_b3_);
  388. c << 0, x.dot(h_ang_c2_), x.dot(h_ang_c3_);
  389. d << x.dot(h_ang_d1_), x.dot(h_ang_d2_), x.dot(h_ang_d3_);
  390. e << x.dot(h_ang_e1_), x.dot(h_ang_e2_), x.dot(h_ang_e3_);
  391. f << x.dot(h_ang_f1_), x.dot(h_ang_f2_), x.dot(h_ang_f3_);
  392. // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  393. // Derivative w.r.t. ith and jth elements of transform vector corresponds to the 3x1 block matrix starting at (3i,j), Equation 6.20 and 6.21 [Magnusson 2009]
  394. point_hessian_.block<3, 1>(9, 3) = a;
  395. point_hessian_.block<3, 1>(12, 3) = b;
  396. point_hessian_.block<3, 1>(15, 3) = c;
  397. point_hessian_.block<3, 1>(9, 4) = b;
  398. point_hessian_.block<3, 1>(12, 4) = d;
  399. point_hessian_.block<3, 1>(15, 4) = e;
  400. point_hessian_.block<3, 1>(9, 5) = c;
  401. point_hessian_.block<3, 1>(12, 5) = e;
  402. point_hessian_.block<3, 1>(15, 5) = f;
  403. }
  404. }
  405. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  406. template<typename PointSource, typename PointTarget> double
  407. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateDerivatives(Eigen::Matrix<double, 6, 1> &score_gradient,
  408. Eigen::Matrix<double, 6, 6> &hessian,
  409. const Eigen::Matrix<float, 4, 6> &point_gradient4,
  410. const Eigen::Matrix<float, 24, 6> &point_hessian_,
  411. const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv,
  412. bool compute_hessian) const
  413. {
  414. Eigen::Matrix<float, 1, 4> x_trans4( x_trans[0], x_trans[1], x_trans[2], 0.0f );
  415. Eigen::Matrix4f c_inv4 = Eigen::Matrix4f::Zero();
  416. c_inv4.topLeftCorner(3, 3) = c_inv.cast<float>();
  417. float gauss_d2 = gauss_d2_;
  418. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  419. float e_x_cov_x = exp(-gauss_d2 * x_trans4.dot(x_trans4 * c_inv4) * 0.5f);
  420. // Calculate probability of transtormed points existance, Equation 6.9 [Magnusson 2009]
  421. float score_inc = -gauss_d1_ * e_x_cov_x;
  422. e_x_cov_x = gauss_d2 * e_x_cov_x;
  423. // Error checking for invalid values.
  424. if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x)
  425. return (0);
  426. // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  427. e_x_cov_x *= gauss_d1_;
  428. Eigen::Matrix<float, 4, 6> c_inv4_x_point_gradient4 = c_inv4 * point_gradient4;
  429. Eigen::Matrix<float, 6, 1> x_trans4_dot_c_inv4_x_point_gradient4 = x_trans4 * c_inv4_x_point_gradient4;
  430. score_gradient.noalias() += (e_x_cov_x * x_trans4_dot_c_inv4_x_point_gradient4).cast<double>();
  431. if (compute_hessian) {
  432. Eigen::Matrix<float, 1, 4> x_trans4_x_c_inv4 = x_trans4 * c_inv4;
  433. Eigen::Matrix<float, 6, 6> point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i = point_gradient4.transpose() * c_inv4_x_point_gradient4;
  434. Eigen::Matrix<float, 6, 1> x_trans4_dot_c_inv4_x_ext_point_hessian_4ij;
  435. for (int i = 0; i < 6; i++) {
  436. // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  437. // Update gradient, Equation 6.12 [Magnusson 2009]
  438. x_trans4_dot_c_inv4_x_ext_point_hessian_4ij.noalias() = x_trans4_x_c_inv4 * point_hessian_.block<4, 6>(i * 4, 0);
  439. for (int j = 0; j < hessian.cols(); j++) {
  440. // Update hessian, Equation 6.13 [Magnusson 2009]
  441. hessian(i, j) += e_x_cov_x * (-gauss_d2 * x_trans4_dot_c_inv4_x_point_gradient4(i) * x_trans4_dot_c_inv4_x_point_gradient4(j) +
  442. x_trans4_dot_c_inv4_x_ext_point_hessian_4ij(j) +
  443. point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i(j, i));
  444. }
  445. }
  446. }
  447. return (score_inc);
  448. }
  449. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  450. template<typename PointSource, typename PointTarget> void
  451. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeHessian (Eigen::Matrix<double, 6, 6> &hessian,
  452. PointCloudSource &trans_cloud, Eigen::Matrix<double, 6, 1> &)
  453. {
  454. // Original Point and Transformed Point
  455. PointSource x_pt, x_trans_pt;
  456. // Original Point and Transformed Point (for math)
  457. Eigen::Vector3d x, x_trans;
  458. // Occupied Voxel
  459. TargetGridLeafConstPtr cell;
  460. // Inverse Covariance of Occupied Voxel
  461. Eigen::Matrix3d c_inv;
  462. // Initialize Point Gradient and Hessian
  463. Eigen::Matrix<double, 3, 6> point_gradient_;
  464. Eigen::Matrix<double, 18, 6> point_hessian_;
  465. point_gradient_.setZero();
  466. point_gradient_.block<3, 3>(0, 0).setIdentity();
  467. point_hessian_.setZero();
  468. hessian.setZero ();
  469. // Precompute Angular Derivatives unessisary because only used after regular derivative calculation
  470. // Update hessian for each point, line 17 in Algorithm 2 [Magnusson 2009]
  471. for (size_t idx = 0; idx < input_->points.size (); idx++)
  472. {
  473. x_trans_pt = trans_cloud.points[idx];
  474. // Find nieghbors (Radius search has been experimentally faster than direct neighbor checking.
  475. std::vector<TargetGridLeafConstPtr> neighborhood;
  476. std::vector<float> distances;
  477. target_cells_.radiusSearch (x_trans_pt, resolution_, neighborhood, distances);
  478. for (typename std::vector<TargetGridLeafConstPtr>::iterator neighborhood_it = neighborhood.begin (); neighborhood_it != neighborhood.end (); neighborhood_it++)
  479. {
  480. cell = *neighborhood_it;
  481. {
  482. x_pt = input_->points[idx];
  483. x = Eigen::Vector3d (x_pt.x, x_pt.y, x_pt.z);
  484. x_trans = Eigen::Vector3d (x_trans_pt.x, x_trans_pt.y, x_trans_pt.z);
  485. // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
  486. x_trans -= cell->getMean ();
  487. // Uses precomputed covariance for speed.
  488. c_inv = cell->getInverseCov ();
  489. // Compute derivative of transform function w.r.t. transform vector, J_E and H_E in Equations 6.18 and 6.20 [Magnusson 2009]
  490. computePointDerivatives (x, point_gradient_, point_hessian_);
  491. // Update hessian, lines 21 in Algorithm 2, according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009]
  492. updateHessian (hessian, point_gradient_, point_hessian_, x_trans, c_inv);
  493. }
  494. }
  495. }
  496. }
  497. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  498. template<typename PointSource, typename PointTarget> void
  499. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateHessian (Eigen::Matrix<double, 6, 6> &hessian,
  500. const Eigen::Matrix<double, 3, 6> &point_gradient_,
  501. const Eigen::Matrix<double, 18, 6> &point_hessian_,
  502. const Eigen::Vector3d &x_trans,
  503. const Eigen::Matrix3d &c_inv) const
  504. {
  505. Eigen::Vector3d cov_dxd_pi;
  506. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  507. double e_x_cov_x = gauss_d2_ * exp (-gauss_d2_ * x_trans.dot (c_inv * x_trans) / 2);
  508. // Error checking for invalid values.
  509. if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x)
  510. return;
  511. // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  512. e_x_cov_x *= gauss_d1_;
  513. for (int i = 0; i < 6; i++)
  514. {
  515. // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  516. cov_dxd_pi = c_inv * point_gradient_.col (i);
  517. for (int j = 0; j < hessian.cols (); j++)
  518. {
  519. // Update hessian, Equation 6.13 [Magnusson 2009]
  520. hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) +
  521. x_trans.dot (c_inv * point_hessian_.block<3, 1>(3 * i, j)) +
  522. point_gradient_.col (j).dot (cov_dxd_pi) );
  523. }
  524. }
  525. }
  526. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  527. template<typename PointSource, typename PointTarget> bool
  528. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateIntervalMT (double &a_l, double &f_l, double &g_l,
  529. double &a_u, double &f_u, double &g_u,
  530. double a_t, double f_t, double g_t)
  531. {
  532. // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, Thuente 1994]
  533. if (f_t > f_l)
  534. {
  535. a_u = a_t;
  536. f_u = f_t;
  537. g_u = g_t;
  538. return (false);
  539. }
  540. // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente 1994]
  541. else
  542. if (g_t * (a_l - a_t) > 0)
  543. {
  544. a_l = a_t;
  545. f_l = f_t;
  546. g_l = g_t;
  547. return (false);
  548. }
  549. // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente 1994]
  550. else
  551. if (g_t * (a_l - a_t) < 0)
  552. {
  553. a_u = a_l;
  554. f_u = f_l;
  555. g_u = g_l;
  556. a_l = a_t;
  557. f_l = f_t;
  558. g_l = g_t;
  559. return (false);
  560. }
  561. // Interval Converged
  562. else
  563. return (true);
  564. }
  565. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  566. template<typename PointSource, typename PointTarget> double
  567. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::trialValueSelectionMT (double a_l, double f_l, double g_l,
  568. double a_u, double f_u, double g_u,
  569. double a_t, double f_t, double g_t)
  570. {
  571. // Case 1 in Trial Value Selection [More, Thuente 1994]
  572. if (f_t > f_l)
  573. {
  574. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  575. // Equation 2.4.52 [Sun, Yuan 2006]
  576. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  577. double w = std::sqrt (z * z - g_t * g_l);
  578. // Equation 2.4.56 [Sun, Yuan 2006]
  579. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  580. // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l
  581. // Equation 2.4.2 [Sun, Yuan 2006]
  582. double a_q = a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t));
  583. if (std::fabs (a_c - a_l) < std::fabs (a_q - a_l))
  584. return (a_c);
  585. else
  586. return (0.5 * (a_q + a_c));
  587. }
  588. // Case 2 in Trial Value Selection [More, Thuente 1994]
  589. else
  590. if (g_t * g_l < 0)
  591. {
  592. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  593. // Equation 2.4.52 [Sun, Yuan 2006]
  594. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  595. double w = std::sqrt (z * z - g_t * g_l);
  596. // Equation 2.4.56 [Sun, Yuan 2006]
  597. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  598. // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t
  599. // Equation 2.4.5 [Sun, Yuan 2006]
  600. double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
  601. if (std::fabs (a_c - a_t) >= std::fabs (a_s - a_t))
  602. return (a_c);
  603. else
  604. return (a_s);
  605. }
  606. // Case 3 in Trial Value Selection [More, Thuente 1994]
  607. else
  608. if (std::fabs (g_t) <= std::fabs (g_l))
  609. {
  610. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  611. // Equation 2.4.52 [Sun, Yuan 2006]
  612. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  613. double w = std::sqrt (z * z - g_t * g_l);
  614. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  615. // Calculate the minimizer of the quadratic that interpolates g_l and g_t
  616. // Equation 2.4.5 [Sun, Yuan 2006]
  617. double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
  618. double a_t_next;
  619. if (std::fabs (a_c - a_t) < std::fabs (a_s - a_t))
  620. a_t_next = a_c;
  621. else
  622. a_t_next = a_s;
  623. if (a_t > a_l)
  624. return (std::min (a_t + 0.66 * (a_u - a_t), a_t_next));
  625. else
  626. return (std::max (a_t + 0.66 * (a_u - a_t), a_t_next));
  627. }
  628. // Case 4 in Trial Value Selection [More, Thuente 1994]
  629. else
  630. {
  631. // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t
  632. // Equation 2.4.52 [Sun, Yuan 2006]
  633. double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u;
  634. double w = std::sqrt (z * z - g_t * g_u);
  635. // Equation 2.4.56 [Sun, Yuan 2006]
  636. return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w));
  637. }
  638. }
  639. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  640. template<typename PointSource, typename PointTarget> double
  641. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeStepLengthMT (const Eigen::Matrix<double, 6, 1> &x, Eigen::Matrix<double, 6, 1> &step_dir, double step_init, double step_max,
  642. double step_min, double &score, Eigen::Matrix<double, 6, 1> &score_gradient, Eigen::Matrix<double, 6, 6> &hessian,
  643. PointCloudSource &trans_cloud)
  644. {
  645. // Set the value of phi(0), Equation 1.3 [More, Thuente 1994]
  646. double phi_0 = -score;
  647. // Set the value of phi'(0), Equation 1.3 [More, Thuente 1994]
  648. double d_phi_0 = -(score_gradient.dot (step_dir));
  649. Eigen::Matrix<double, 6, 1> x_t;
  650. if (d_phi_0 >= 0)
  651. {
  652. // Not a decent direction
  653. if (d_phi_0 == 0)
  654. return 0;
  655. else
  656. {
  657. // Reverse step direction and calculate optimal step.
  658. d_phi_0 *= -1;
  659. step_dir *= -1;
  660. }
  661. }
  662. // The Search Algorithm for T(mu) [More, Thuente 1994]
  663. int max_step_iterations = 10;
  664. int step_iterations = 0;
  665. // Sufficient decreace constant, Equation 1.1 [More, Thuete 1994]
  666. double mu = 1.e-4;
  667. // Curvature condition constant, Equation 1.2 [More, Thuete 1994]
  668. double nu = 0.9;
  669. // Initial endpoints of Interval I,
  670. double a_l = 0, a_u = 0;
  671. // Auxiliary function psi is used until I is determined ot be a closed interval, Equation 2.1 [More, Thuente 1994]
  672. double f_l = auxilaryFunction_PsiMT (a_l, phi_0, phi_0, d_phi_0, mu);
  673. double g_l = auxilaryFunction_dPsiMT (d_phi_0, d_phi_0, mu);
  674. double f_u = auxilaryFunction_PsiMT (a_u, phi_0, phi_0, d_phi_0, mu);
  675. double g_u = auxilaryFunction_dPsiMT (d_phi_0, d_phi_0, mu);
  676. // Check used to allow More-Thuente step length calculation to be skipped by making step_min == step_max
  677. bool interval_converged = (step_max - step_min) > 0, open_interval = true;
  678. double a_t = step_init;
  679. a_t = std::min (a_t, step_max);
  680. a_t = std::max (a_t, step_min);
  681. x_t = x + step_dir * a_t;
  682. final_transformation_ = (Eigen::Translation<float, 3>(static_cast<float> (x_t (0)), static_cast<float> (x_t (1)), static_cast<float> (x_t (2))) *
  683. Eigen::AngleAxis<float> (static_cast<float> (x_t (3)), Eigen::Vector3f::UnitX ()) *
  684. Eigen::AngleAxis<float> (static_cast<float> (x_t (4)), Eigen::Vector3f::UnitY ()) *
  685. Eigen::AngleAxis<float> (static_cast<float> (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix ();
  686. // New transformed point cloud
  687. transformPointCloud (*input_, trans_cloud, final_transformation_);
  688. // Updates score, gradient and hessian. Hessian calculation is unessisary but testing showed that most step calculations use the
  689. // initial step suggestion and recalculation the reusable portions of the hessian would intail more computation time.
  690. score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, true);
  691. // Calculate phi(alpha_t)
  692. double phi_t = -score;
  693. // Calculate phi'(alpha_t)
  694. double d_phi_t = -(score_gradient.dot (step_dir));
  695. // Calculate psi(alpha_t)
  696. double psi_t = auxilaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu);
  697. // Calculate psi'(alpha_t)
  698. double d_psi_t = auxilaryFunction_dPsiMT (d_phi_t, d_phi_0, mu);
  699. // Iterate until max number of iterations, interval convergance or a value satisfies the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More, Thuente 1994]
  700. while (!interval_converged && step_iterations < max_step_iterations && !(psi_t <= 0 /*Sufficient Decrease*/ && d_phi_t <= -nu * d_phi_0 /*Curvature Condition*/))
  701. {
  702. // Use auxilary function if interval I is not closed
  703. if (open_interval)
  704. {
  705. a_t = trialValueSelectionMT (a_l, f_l, g_l,
  706. a_u, f_u, g_u,
  707. a_t, psi_t, d_psi_t);
  708. }
  709. else
  710. {
  711. a_t = trialValueSelectionMT (a_l, f_l, g_l,
  712. a_u, f_u, g_u,
  713. a_t, phi_t, d_phi_t);
  714. }
  715. a_t = std::min (a_t, step_max);
  716. a_t = std::max (a_t, step_min);
  717. x_t = x + step_dir * a_t;
  718. final_transformation_ = (Eigen::Translation<float, 3> (static_cast<float> (x_t (0)), static_cast<float> (x_t (1)), static_cast<float> (x_t (2))) *
  719. Eigen::AngleAxis<float> (static_cast<float> (x_t (3)), Eigen::Vector3f::UnitX ()) *
  720. Eigen::AngleAxis<float> (static_cast<float> (x_t (4)), Eigen::Vector3f::UnitY ()) *
  721. Eigen::AngleAxis<float> (static_cast<float> (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix ();
  722. // New transformed point cloud
  723. // Done on final cloud to prevent wasted computation
  724. transformPointCloud (*input_, trans_cloud, final_transformation_);
  725. // Updates score, gradient. Values stored to prevent wasted computation.
  726. score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, false);
  727. // Calculate phi(alpha_t+)
  728. phi_t = -score;
  729. // Calculate phi'(alpha_t+)
  730. d_phi_t = -(score_gradient.dot (step_dir));
  731. // Calculate psi(alpha_t+)
  732. psi_t = auxilaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu);
  733. // Calculate psi'(alpha_t+)
  734. d_psi_t = auxilaryFunction_dPsiMT (d_phi_t, d_phi_0, mu);
  735. // Check if I is now a closed interval
  736. if (open_interval && (psi_t <= 0 && d_psi_t >= 0))
  737. {
  738. open_interval = false;
  739. // Converts f_l and g_l from psi to phi
  740. f_l = f_l + phi_0 - mu * d_phi_0 * a_l;
  741. g_l = g_l + mu * d_phi_0;
  742. // Converts f_u and g_u from psi to phi
  743. f_u = f_u + phi_0 - mu * d_phi_0 * a_u;
  744. g_u = g_u + mu * d_phi_0;
  745. }
  746. if (open_interval)
  747. {
  748. // Update interval end points using Updating Algorithm [More, Thuente 1994]
  749. interval_converged = updateIntervalMT (a_l, f_l, g_l,
  750. a_u, f_u, g_u,
  751. a_t, psi_t, d_psi_t);
  752. }
  753. else
  754. {
  755. // Update interval end points using Modified Updating Algorithm [More, Thuente 1994]
  756. interval_converged = updateIntervalMT (a_l, f_l, g_l,
  757. a_u, f_u, g_u,
  758. a_t, phi_t, d_phi_t);
  759. }
  760. step_iterations++;
  761. }
  762. // If inner loop was run then hessian needs to be calculated.
  763. // Hessian is unnessisary for step length determination but gradients are required
  764. // so derivative and transform data is stored for the next iteration.
  765. if (step_iterations)
  766. computeHessian (hessian, trans_cloud, x_t);
  767. return (a_t);
  768. }
  769. template<typename PointSource, typename PointTarget>
  770. double pclomp::NormalDistributionsTransform<PointSource, PointTarget>::calculateScore(const PointCloudSource & trans_cloud) const
  771. {
  772. double score = 0;
  773. for (int idx = 0; idx < trans_cloud.points.size(); idx++)
  774. {
  775. PointSource x_trans_pt = trans_cloud.points[idx];
  776. // Find nieghbors (Radius search has been experimentally faster than direct neighbor checking.
  777. std::vector<TargetGridLeafConstPtr> neighborhood;
  778. std::vector<float> distances;
  779. target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
  780. for (typename std::vector<TargetGridLeafConstPtr>::iterator neighborhood_it = neighborhood.begin(); neighborhood_it != neighborhood.end(); neighborhood_it++)
  781. {
  782. TargetGridLeafConstPtr cell = *neighborhood_it;
  783. Eigen::Vector3d x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z);
  784. // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
  785. x_trans -= cell->getMean();
  786. // Uses precomputed covariance for speed.
  787. Eigen::Matrix3d c_inv = cell->getInverseCov();
  788. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  789. double e_x_cov_x = exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2);
  790. // Calculate probability of transtormed points existance, Equation 6.9 [Magnusson 2009]
  791. double score_inc = -gauss_d1_ * e_x_cov_x - gauss_d3_;
  792. score += score_inc / neighborhood.size();
  793. }
  794. }
  795. return (score) / static_cast<double> (trans_cloud.size());
  796. }
  797. #endif // PCL_REGISTRATION_NDT_IMPL_H_