ndt_omp_impl.hpp 40 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985
  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 gaussian 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 gaussian 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 derivatives 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 guaranteed 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 relative 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(input_->points.size());
  158. std::vector<Eigen::Matrix<double, 6, 1>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 1>>> score_gradients(input_->points.size());
  159. std::vector<Eigen::Matrix<double, 6, 6>, Eigen::aligned_allocator<Eigen::Matrix<double, 6, 6>>> hessians(input_->points.size());
  160. for (std::size_t i = 0; i < input_->points.size(); 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 (std::size_t 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 neighbors (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[idx] = score_pt;
  226. score_gradients[idx].noalias() = score_gradient_pt;
  227. hessians[idx].noalias() = hessian_pt;
  228. }
  229. // Ensure that the result is invariant against the summing up order
  230. for (std::size_t i = 0; i < input_->points.size(); i++) {
  231. score += scores[i];
  232. score_gradient += score_gradients[i];
  233. hessian += hessians[i];
  234. }
  235. return (score);
  236. }
  237. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  238. template<typename PointSource, typename PointTarget> void
  239. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeAngleDerivatives(Eigen::Matrix<double, 6, 1> &p, bool compute_hessian)
  240. {
  241. // Simplified math for near 0 angles
  242. double cx, cy, cz, sx, sy, sz;
  243. if (fabs(p(3)) < 10e-5)
  244. {
  245. //p(3) = 0;
  246. cx = 1.0;
  247. sx = 0.0;
  248. }
  249. else
  250. {
  251. cx = cos(p(3));
  252. sx = sin(p(3));
  253. }
  254. if (fabs(p(4)) < 10e-5)
  255. {
  256. //p(4) = 0;
  257. cy = 1.0;
  258. sy = 0.0;
  259. }
  260. else
  261. {
  262. cy = cos(p(4));
  263. sy = sin(p(4));
  264. }
  265. if (fabs(p(5)) < 10e-5)
  266. {
  267. //p(5) = 0;
  268. cz = 1.0;
  269. sz = 0.0;
  270. }
  271. else
  272. {
  273. cz = cos(p(5));
  274. sz = sin(p(5));
  275. }
  276. // Precomputed angular gradiant components. Letters correspond to Equation 6.19 [Magnusson 2009]
  277. j_ang_a_ << (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy);
  278. j_ang_b_ << (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy);
  279. j_ang_c_ << (-sy * cz), sy * sz, cy;
  280. j_ang_d_ << sx * cy * cz, (-sx * cy * sz), sx * sy;
  281. j_ang_e_ << (-cx * cy * cz), cx * cy * sz, (-cx * sy);
  282. j_ang_f_ << (-cy * sz), (-cy * cz), 0;
  283. j_ang_g_ << (cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0;
  284. j_ang_h_ << (sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0;
  285. j_ang.setZero();
  286. j_ang.row(0).noalias() = Eigen::Vector4f((-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy), 0.0f);
  287. j_ang.row(1).noalias() = Eigen::Vector4f((cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy), 0.0f);
  288. j_ang.row(2).noalias() = Eigen::Vector4f((-sy * cz), sy * sz, cy, 0.0f);
  289. j_ang.row(3).noalias() = Eigen::Vector4f(sx * cy * cz, (-sx * cy * sz), sx * sy, 0.0f);
  290. j_ang.row(4).noalias() = Eigen::Vector4f((-cx * cy * cz), cx * cy * sz, (-cx * sy), 0.0f);
  291. j_ang.row(5).noalias() = Eigen::Vector4f((-cy * sz), (-cy * cz), 0, 0.0f);
  292. j_ang.row(6).noalias() = Eigen::Vector4f((cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0, 0.0f);
  293. j_ang.row(7).noalias() = Eigen::Vector4f((sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0, 0.0f);
  294. if (compute_hessian)
  295. {
  296. // Precomputed angular hessian components. Letters correspond to Equation 6.21 and numbers correspond to row index [Magnusson 2009]
  297. h_ang_a2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy;
  298. h_ang_a3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy);
  299. h_ang_b2_ << (cx * cy * cz), (-cx * cy * sz), (cx * sy);
  300. h_ang_b3_ << (sx * cy * cz), (-sx * cy * sz), (sx * sy);
  301. // The sign of 'sx * sz' in c2 is incorrect in [Magnusson 2009], and it is fixed here.
  302. h_ang_c2_ << (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0;
  303. h_ang_c3_ << (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0;
  304. h_ang_d1_ << (-cy * cz), (cy * sz), (-sy);
  305. h_ang_d2_ << (-sx * sy * cz), (sx * sy * sz), (sx * cy);
  306. h_ang_d3_ << (cx * sy * cz), (-cx * sy * sz), (-cx * cy);
  307. h_ang_e1_ << (sy * sz), (sy * cz), 0;
  308. h_ang_e2_ << (-sx * cy * sz), (-sx * cy * cz), 0;
  309. h_ang_e3_ << (cx * cy * sz), (cx * cy * cz), 0;
  310. h_ang_f1_ << (-cy * cz), (cy * sz), 0;
  311. h_ang_f2_ << (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0;
  312. h_ang_f3_ << (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0;
  313. h_ang.setZero();
  314. h_ang.row(0).noalias() = Eigen::Vector4f((-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy, 0.0f); // a2
  315. h_ang.row(1).noalias() = Eigen::Vector4f((-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy), 0.0f); // a3
  316. h_ang.row(2).noalias() = Eigen::Vector4f((cx * cy * cz), (-cx * cy * sz), (cx * sy), 0.0f); // b2
  317. h_ang.row(3).noalias() = Eigen::Vector4f((sx * cy * cz), (-sx * cy * sz), (sx * sy), 0.0f); // b3
  318. h_ang.row(4).noalias() = Eigen::Vector4f((-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0, 0.0f); // c2
  319. h_ang.row(5).noalias() = Eigen::Vector4f((cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0, 0.0f); // c3
  320. h_ang.row(6).noalias() = Eigen::Vector4f((-cy * cz), (cy * sz), (sy), 0.0f); // d1
  321. h_ang.row(7).noalias() = Eigen::Vector4f((-sx * sy * cz), (sx * sy * sz), (sx * cy), 0.0f); // d2
  322. h_ang.row(8).noalias() = Eigen::Vector4f((cx * sy * cz), (-cx * sy * sz), (-cx * cy), 0.0f); // d3
  323. h_ang.row(9).noalias() = Eigen::Vector4f((sy * sz), (sy * cz), 0, 0.0f); // e1
  324. h_ang.row(10).noalias() = Eigen::Vector4f ((-sx * cy * sz), (-sx * cy * cz), 0, 0.0f); // e2
  325. h_ang.row(11).noalias() = Eigen::Vector4f ((cx * cy * sz), (cx * cy * cz), 0, 0.0f); // e3
  326. h_ang.row(12).noalias() = Eigen::Vector4f ((-cy * cz), (cy * sz), 0, 0.0f); // f1
  327. h_ang.row(13).noalias() = Eigen::Vector4f ((-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0, 0.0f); // f2
  328. h_ang.row(14).noalias() = Eigen::Vector4f ((-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0, 0.0f); // f3
  329. }
  330. }
  331. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  332. template<typename PointSource, typename PointTarget> void
  333. 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
  334. {
  335. Eigen::Vector4f x4(x[0], x[1], x[2], 0.0f);
  336. // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  337. // Derivative w.r.t. ith element of transform vector corresponds to column i, Equation 6.18 and 6.19 [Magnusson 2009]
  338. Eigen::Matrix<float, 8, 1> x_j_ang = j_ang * x4;
  339. point_gradient_(1, 3) = x_j_ang[0];
  340. point_gradient_(2, 3) = x_j_ang[1];
  341. point_gradient_(0, 4) = x_j_ang[2];
  342. point_gradient_(1, 4) = x_j_ang[3];
  343. point_gradient_(2, 4) = x_j_ang[4];
  344. point_gradient_(0, 5) = x_j_ang[5];
  345. point_gradient_(1, 5) = x_j_ang[6];
  346. point_gradient_(2, 5) = x_j_ang[7];
  347. if (compute_hessian)
  348. {
  349. Eigen::Matrix<float, 16, 1> x_h_ang = h_ang * x4;
  350. // Vectors from Equation 6.21 [Magnusson 2009]
  351. Eigen::Vector4f a (0, x_h_ang[0], x_h_ang[1], 0.0f);
  352. Eigen::Vector4f b (0, x_h_ang[2], x_h_ang[3], 0.0f);
  353. Eigen::Vector4f c (0, x_h_ang[4], x_h_ang[5], 0.0f);
  354. Eigen::Vector4f d (x_h_ang[6], x_h_ang[7], x_h_ang[8], 0.0f);
  355. Eigen::Vector4f e (x_h_ang[9], x_h_ang[10], x_h_ang[11], 0.0f);
  356. Eigen::Vector4f f (x_h_ang[12], x_h_ang[13], x_h_ang[14], 0.0f);
  357. // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  358. // 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]
  359. point_hessian_.block<4, 1>((9/3)*4, 3) = a;
  360. point_hessian_.block<4, 1>((12/3)*4, 3) = b;
  361. point_hessian_.block<4, 1>((15/3)*4, 3) = c;
  362. point_hessian_.block<4, 1>((9/3)*4, 4) = b;
  363. point_hessian_.block<4, 1>((12/3)*4, 4) = d;
  364. point_hessian_.block<4, 1>((15/3)*4, 4) = e;
  365. point_hessian_.block<4, 1>((9/3)*4, 5) = c;
  366. point_hessian_.block<4, 1>((12/3)*4, 5) = e;
  367. point_hessian_.block<4, 1>((15/3)*4, 5) = f;
  368. }
  369. }
  370. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  371. template<typename PointSource, typename PointTarget> void
  372. 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
  373. {
  374. // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  375. // Derivative w.r.t. ith element of transform vector corresponds to column i, Equation 6.18 and 6.19 [Magnusson 2009]
  376. point_gradient_(1, 3) = x.dot(j_ang_a_);
  377. point_gradient_(2, 3) = x.dot(j_ang_b_);
  378. point_gradient_(0, 4) = x.dot(j_ang_c_);
  379. point_gradient_(1, 4) = x.dot(j_ang_d_);
  380. point_gradient_(2, 4) = x.dot(j_ang_e_);
  381. point_gradient_(0, 5) = x.dot(j_ang_f_);
  382. point_gradient_(1, 5) = x.dot(j_ang_g_);
  383. point_gradient_(2, 5) = x.dot(j_ang_h_);
  384. if (compute_hessian)
  385. {
  386. // Vectors from Equation 6.21 [Magnusson 2009]
  387. Eigen::Vector3d a, b, c, d, e, f;
  388. a << 0, x.dot(h_ang_a2_), x.dot(h_ang_a3_);
  389. b << 0, x.dot(h_ang_b2_), x.dot(h_ang_b3_);
  390. c << 0, x.dot(h_ang_c2_), x.dot(h_ang_c3_);
  391. d << x.dot(h_ang_d1_), x.dot(h_ang_d2_), x.dot(h_ang_d3_);
  392. e << x.dot(h_ang_e1_), x.dot(h_ang_e2_), x.dot(h_ang_e3_);
  393. f << x.dot(h_ang_f1_), x.dot(h_ang_f2_), x.dot(h_ang_f3_);
  394. // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform vector p.
  395. // 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]
  396. point_hessian_.block<3, 1>(9, 3) = a;
  397. point_hessian_.block<3, 1>(12, 3) = b;
  398. point_hessian_.block<3, 1>(15, 3) = c;
  399. point_hessian_.block<3, 1>(9, 4) = b;
  400. point_hessian_.block<3, 1>(12, 4) = d;
  401. point_hessian_.block<3, 1>(15, 4) = e;
  402. point_hessian_.block<3, 1>(9, 5) = c;
  403. point_hessian_.block<3, 1>(12, 5) = e;
  404. point_hessian_.block<3, 1>(15, 5) = f;
  405. }
  406. }
  407. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  408. template<typename PointSource, typename PointTarget> double
  409. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateDerivatives(Eigen::Matrix<double, 6, 1> &score_gradient,
  410. Eigen::Matrix<double, 6, 6> &hessian,
  411. const Eigen::Matrix<float, 4, 6> &point_gradient4,
  412. const Eigen::Matrix<float, 24, 6> &point_hessian_,
  413. const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv,
  414. bool compute_hessian) const
  415. {
  416. Eigen::Matrix<float, 1, 4> x_trans4( x_trans[0], x_trans[1], x_trans[2], 0.0f );
  417. Eigen::Matrix4f c_inv4 = Eigen::Matrix4f::Zero();
  418. c_inv4.topLeftCorner(3, 3) = c_inv.cast<float>();
  419. float gauss_d2 = gauss_d2_;
  420. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  421. float e_x_cov_x = exp(-gauss_d2 * x_trans4.dot(x_trans4 * c_inv4) * 0.5f);
  422. // Calculate probability of transformed points existence, Equation 6.9 [Magnusson 2009]
  423. float score_inc = -gauss_d1_ * e_x_cov_x;
  424. e_x_cov_x = gauss_d2 * e_x_cov_x;
  425. // Error checking for invalid values.
  426. if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x)
  427. return (0);
  428. // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  429. e_x_cov_x *= gauss_d1_;
  430. Eigen::Matrix<float, 4, 6> c_inv4_x_point_gradient4 = c_inv4 * point_gradient4;
  431. Eigen::Matrix<float, 6, 1> x_trans4_dot_c_inv4_x_point_gradient4 = x_trans4 * c_inv4_x_point_gradient4;
  432. score_gradient.noalias() += (e_x_cov_x * x_trans4_dot_c_inv4_x_point_gradient4).cast<double>();
  433. if (compute_hessian) {
  434. Eigen::Matrix<float, 1, 4> x_trans4_x_c_inv4 = x_trans4 * c_inv4;
  435. Eigen::Matrix<float, 6, 6> point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i = point_gradient4.transpose() * c_inv4_x_point_gradient4;
  436. Eigen::Matrix<float, 6, 1> x_trans4_dot_c_inv4_x_ext_point_hessian_4ij;
  437. for (int i = 0; i < 6; i++) {
  438. // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  439. // Update gradient, Equation 6.12 [Magnusson 2009]
  440. x_trans4_dot_c_inv4_x_ext_point_hessian_4ij.noalias() = x_trans4_x_c_inv4 * point_hessian_.block<4, 6>(i * 4, 0);
  441. for (int j = 0; j < hessian.cols(); j++) {
  442. // Update hessian, Equation 6.13 [Magnusson 2009]
  443. 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) +
  444. x_trans4_dot_c_inv4_x_ext_point_hessian_4ij(j) +
  445. point_gradient4_colj_dot_c_inv4_x_point_gradient4_col_i(j, i));
  446. }
  447. }
  448. }
  449. return (score_inc);
  450. }
  451. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  452. template<typename PointSource, typename PointTarget> void
  453. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::computeHessian (Eigen::Matrix<double, 6, 6> &hessian,
  454. PointCloudSource &trans_cloud, Eigen::Matrix<double, 6, 1> &)
  455. {
  456. // Original Point and Transformed Point
  457. PointSource x_pt, x_trans_pt;
  458. // Original Point and Transformed Point (for math)
  459. Eigen::Vector3d x, x_trans;
  460. // Occupied Voxel
  461. TargetGridLeafConstPtr cell;
  462. // Inverse Covariance of Occupied Voxel
  463. Eigen::Matrix3d c_inv;
  464. // Initialize Point Gradient and Hessian
  465. Eigen::Matrix<double, 3, 6> point_gradient_;
  466. Eigen::Matrix<double, 18, 6> point_hessian_;
  467. point_gradient_.setZero();
  468. point_gradient_.block<3, 3>(0, 0).setIdentity();
  469. point_hessian_.setZero();
  470. hessian.setZero ();
  471. // Precompute Angular Derivatives unnecessary because only used after regular derivative calculation
  472. // Update hessian for each point, line 17 in Algorithm 2 [Magnusson 2009]
  473. for (size_t idx = 0; idx < input_->points.size (); idx++)
  474. {
  475. x_trans_pt = trans_cloud.points[idx];
  476. // Find neighbors (Radius search has been experimentally faster than direct neighbor checking.
  477. std::vector<TargetGridLeafConstPtr> neighborhood;
  478. std::vector<float> distances;
  479. switch (search_method) {
  480. case KDTREE:
  481. target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
  482. break;
  483. case DIRECT26:
  484. target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);
  485. break;
  486. default:
  487. case DIRECT7:
  488. target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood);
  489. break;
  490. case DIRECT1:
  491. target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood);
  492. break;
  493. }
  494. for (typename std::vector<TargetGridLeafConstPtr>::iterator neighborhood_it = neighborhood.begin (); neighborhood_it != neighborhood.end (); neighborhood_it++)
  495. {
  496. cell = *neighborhood_it;
  497. {
  498. x_pt = input_->points[idx];
  499. x = Eigen::Vector3d (x_pt.x, x_pt.y, x_pt.z);
  500. x_trans = Eigen::Vector3d (x_trans_pt.x, x_trans_pt.y, x_trans_pt.z);
  501. // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
  502. x_trans -= cell->getMean ();
  503. // Uses precomputed covariance for speed.
  504. c_inv = cell->getInverseCov ();
  505. // Compute derivative of transform function w.r.t. transform vector, J_E and H_E in Equations 6.18 and 6.20 [Magnusson 2009]
  506. computePointDerivatives (x, point_gradient_, point_hessian_);
  507. // Update hessian, lines 21 in Algorithm 2, according to Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009]
  508. updateHessian (hessian, point_gradient_, point_hessian_, x_trans, c_inv);
  509. }
  510. }
  511. }
  512. }
  513. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  514. template<typename PointSource, typename PointTarget> void
  515. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateHessian (Eigen::Matrix<double, 6, 6> &hessian,
  516. const Eigen::Matrix<double, 3, 6> &point_gradient_,
  517. const Eigen::Matrix<double, 18, 6> &point_hessian_,
  518. const Eigen::Vector3d &x_trans,
  519. const Eigen::Matrix3d &c_inv) const
  520. {
  521. Eigen::Vector3d cov_dxd_pi;
  522. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  523. double e_x_cov_x = gauss_d2_ * exp (-gauss_d2_ * x_trans.dot (c_inv * x_trans) / 2);
  524. // Error checking for invalid values.
  525. if (e_x_cov_x > 1 || e_x_cov_x < 0 || e_x_cov_x != e_x_cov_x)
  526. return;
  527. // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  528. e_x_cov_x *= gauss_d1_;
  529. for (int i = 0; i < 6; i++)
  530. {
  531. // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
  532. cov_dxd_pi = c_inv * point_gradient_.col (i);
  533. for (int j = 0; j < hessian.cols (); j++)
  534. {
  535. // Update hessian, Equation 6.13 [Magnusson 2009]
  536. hessian (i, j) += e_x_cov_x * (-gauss_d2_ * x_trans.dot (cov_dxd_pi) * x_trans.dot (c_inv * point_gradient_.col (j)) +
  537. x_trans.dot (c_inv * point_hessian_.block<3, 1>(3 * i, j)) +
  538. point_gradient_.col (j).dot (cov_dxd_pi) );
  539. }
  540. }
  541. }
  542. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  543. template<typename PointSource, typename PointTarget> bool
  544. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::updateIntervalMT (double &a_l, double &f_l, double &g_l,
  545. double &a_u, double &f_u, double &g_u,
  546. double a_t, double f_t, double g_t)
  547. {
  548. // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, Thuente 1994]
  549. if (f_t > f_l)
  550. {
  551. a_u = a_t;
  552. f_u = f_t;
  553. g_u = g_t;
  554. return (false);
  555. }
  556. // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente 1994]
  557. else
  558. if (g_t * (a_l - a_t) > 0)
  559. {
  560. a_l = a_t;
  561. f_l = f_t;
  562. g_l = g_t;
  563. return (false);
  564. }
  565. // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente 1994]
  566. else
  567. if (g_t * (a_l - a_t) < 0)
  568. {
  569. a_u = a_l;
  570. f_u = f_l;
  571. g_u = g_l;
  572. a_l = a_t;
  573. f_l = f_t;
  574. g_l = g_t;
  575. return (false);
  576. }
  577. // Interval Converged
  578. else
  579. return (true);
  580. }
  581. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  582. template<typename PointSource, typename PointTarget> double
  583. pclomp::NormalDistributionsTransform<PointSource, PointTarget>::trialValueSelectionMT (double a_l, double f_l, double g_l,
  584. double a_u, double f_u, double g_u,
  585. double a_t, double f_t, double g_t)
  586. {
  587. // Case 1 in Trial Value Selection [More, Thuente 1994]
  588. if (f_t > f_l)
  589. {
  590. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  591. // Equation 2.4.52 [Sun, Yuan 2006]
  592. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  593. double w = std::sqrt (z * z - g_t * g_l);
  594. // Equation 2.4.56 [Sun, Yuan 2006]
  595. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  596. // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l
  597. // Equation 2.4.2 [Sun, Yuan 2006]
  598. double a_q = a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t));
  599. if (std::fabs (a_c - a_l) < std::fabs (a_q - a_l))
  600. return (a_c);
  601. else
  602. return (0.5 * (a_q + a_c));
  603. }
  604. // Case 2 in Trial Value Selection [More, Thuente 1994]
  605. else
  606. if (g_t * g_l < 0)
  607. {
  608. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  609. // Equation 2.4.52 [Sun, Yuan 2006]
  610. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  611. double w = std::sqrt (z * z - g_t * g_l);
  612. // Equation 2.4.56 [Sun, Yuan 2006]
  613. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  614. // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t
  615. // Equation 2.4.5 [Sun, Yuan 2006]
  616. double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
  617. if (std::fabs (a_c - a_t) >= std::fabs (a_s - a_t))
  618. return (a_c);
  619. else
  620. return (a_s);
  621. }
  622. // Case 3 in Trial Value Selection [More, Thuente 1994]
  623. else
  624. if (std::fabs (g_t) <= std::fabs (g_l))
  625. {
  626. // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
  627. // Equation 2.4.52 [Sun, Yuan 2006]
  628. double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
  629. double w = std::sqrt (z * z - g_t * g_l);
  630. double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
  631. // Calculate the minimizer of the quadratic that interpolates g_l and g_t
  632. // Equation 2.4.5 [Sun, Yuan 2006]
  633. double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
  634. double a_t_next;
  635. if (std::fabs (a_c - a_t) < std::fabs (a_s - a_t))
  636. a_t_next = a_c;
  637. else
  638. a_t_next = a_s;
  639. if (a_t > a_l)
  640. return (std::min (a_t + 0.66 * (a_u - a_t), a_t_next));
  641. else
  642. return (std::max (a_t + 0.66 * (a_u - a_t), a_t_next));
  643. }
  644. // Case 4 in Trial Value Selection [More, Thuente 1994]
  645. else
  646. {
  647. // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t
  648. // Equation 2.4.52 [Sun, Yuan 2006]
  649. double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u;
  650. double w = std::sqrt (z * z - g_t * g_u);
  651. // Equation 2.4.56 [Sun, Yuan 2006]
  652. return (a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w));
  653. }
  654. }
  655. //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  656. template<typename PointSource, typename PointTarget> double
  657. 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,
  658. double step_min, double &score, Eigen::Matrix<double, 6, 1> &score_gradient, Eigen::Matrix<double, 6, 6> &hessian,
  659. PointCloudSource &trans_cloud)
  660. {
  661. // Set the value of phi(0), Equation 1.3 [More, Thuente 1994]
  662. double phi_0 = -score;
  663. // Set the value of phi'(0), Equation 1.3 [More, Thuente 1994]
  664. double d_phi_0 = -(score_gradient.dot (step_dir));
  665. Eigen::Matrix<double, 6, 1> x_t;
  666. if (d_phi_0 >= 0)
  667. {
  668. // Not a decent direction
  669. if (d_phi_0 == 0)
  670. return 0;
  671. else
  672. {
  673. // Reverse step direction and calculate optimal step.
  674. d_phi_0 *= -1;
  675. step_dir *= -1;
  676. }
  677. }
  678. // The Search Algorithm for T(mu) [More, Thuente 1994]
  679. int max_step_iterations = 10;
  680. int step_iterations = 0;
  681. // Sufficient decrease constant, Equation 1.1 [More, Thuete 1994]
  682. double mu = 1.e-4;
  683. // Curvature condition constant, Equation 1.2 [More, Thuete 1994]
  684. double nu = 0.9;
  685. // Initial endpoints of Interval I,
  686. double a_l = 0, a_u = 0;
  687. // Auxiliary function psi is used until I is determined ot be a closed interval, Equation 2.1 [More, Thuente 1994]
  688. double f_l = auxiliaryFunction_PsiMT (a_l, phi_0, phi_0, d_phi_0, mu);
  689. double g_l = auxiliaryFunction_dPsiMT (d_phi_0, d_phi_0, mu);
  690. double f_u = auxiliaryFunction_PsiMT (a_u, phi_0, phi_0, d_phi_0, mu);
  691. double g_u = auxiliaryFunction_dPsiMT (d_phi_0, d_phi_0, mu);
  692. // Check used to allow More-Thuente step length calculation to be skipped by making step_min == step_max
  693. bool interval_converged = (step_max - step_min) < 0, open_interval = true;
  694. double a_t = step_init;
  695. a_t = std::min (a_t, step_max);
  696. a_t = std::max (a_t, step_min);
  697. x_t = x + step_dir * a_t;
  698. final_transformation_ = (Eigen::Translation<float, 3>(static_cast<float> (x_t (0)), static_cast<float> (x_t (1)), static_cast<float> (x_t (2))) *
  699. Eigen::AngleAxis<float> (static_cast<float> (x_t (3)), Eigen::Vector3f::UnitX ()) *
  700. Eigen::AngleAxis<float> (static_cast<float> (x_t (4)), Eigen::Vector3f::UnitY ()) *
  701. Eigen::AngleAxis<float> (static_cast<float> (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix ();
  702. // New transformed point cloud
  703. transformPointCloud (*input_, trans_cloud, final_transformation_);
  704. // Updates score, gradient and hessian. Hessian calculation is unnecessary but testing showed that most step calculations use the
  705. // initial step suggestion and recalculation the reusable portions of the hessian would intail more computation time.
  706. score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, true);
  707. // Calculate phi(alpha_t)
  708. double phi_t = -score;
  709. // Calculate phi'(alpha_t)
  710. double d_phi_t = -(score_gradient.dot (step_dir));
  711. // Calculate psi(alpha_t)
  712. double psi_t = auxiliaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu);
  713. // Calculate psi'(alpha_t)
  714. double d_psi_t = auxiliaryFunction_dPsiMT (d_phi_t, d_phi_0, mu);
  715. // Iterate until max number of iterations, interval convergence or a value satisfies the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More, Thuente 1994]
  716. while (!interval_converged && step_iterations < max_step_iterations && !(psi_t <= 0 /*Sufficient Decrease*/ && d_phi_t <= -nu * d_phi_0 /*Curvature Condition*/))
  717. {
  718. // Use auxiliary function if interval I is not closed
  719. if (open_interval)
  720. {
  721. a_t = trialValueSelectionMT (a_l, f_l, g_l,
  722. a_u, f_u, g_u,
  723. a_t, psi_t, d_psi_t);
  724. }
  725. else
  726. {
  727. a_t = trialValueSelectionMT (a_l, f_l, g_l,
  728. a_u, f_u, g_u,
  729. a_t, phi_t, d_phi_t);
  730. }
  731. a_t = std::min (a_t, step_max);
  732. a_t = std::max (a_t, step_min);
  733. x_t = x + step_dir * a_t;
  734. final_transformation_ = (Eigen::Translation<float, 3> (static_cast<float> (x_t (0)), static_cast<float> (x_t (1)), static_cast<float> (x_t (2))) *
  735. Eigen::AngleAxis<float> (static_cast<float> (x_t (3)), Eigen::Vector3f::UnitX ()) *
  736. Eigen::AngleAxis<float> (static_cast<float> (x_t (4)), Eigen::Vector3f::UnitY ()) *
  737. Eigen::AngleAxis<float> (static_cast<float> (x_t (5)), Eigen::Vector3f::UnitZ ())).matrix ();
  738. // New transformed point cloud
  739. // Done on final cloud to prevent wasted computation
  740. transformPointCloud (*input_, trans_cloud, final_transformation_);
  741. // Updates score, gradient. Values stored to prevent wasted computation.
  742. score = computeDerivatives (score_gradient, hessian, trans_cloud, x_t, false);
  743. // Calculate phi(alpha_t+)
  744. phi_t = -score;
  745. // Calculate phi'(alpha_t+)
  746. d_phi_t = -(score_gradient.dot (step_dir));
  747. // Calculate psi(alpha_t+)
  748. psi_t = auxiliaryFunction_PsiMT (a_t, phi_t, phi_0, d_phi_0, mu);
  749. // Calculate psi'(alpha_t+)
  750. d_psi_t = auxiliaryFunction_dPsiMT (d_phi_t, d_phi_0, mu);
  751. // Check if I is now a closed interval
  752. if (open_interval && (psi_t <= 0 && d_psi_t >= 0))
  753. {
  754. open_interval = false;
  755. // Converts f_l and g_l from psi to phi
  756. f_l = f_l + phi_0 - mu * d_phi_0 * a_l;
  757. g_l = g_l + mu * d_phi_0;
  758. // Converts f_u and g_u from psi to phi
  759. f_u = f_u + phi_0 - mu * d_phi_0 * a_u;
  760. g_u = g_u + mu * d_phi_0;
  761. }
  762. if (open_interval)
  763. {
  764. // Update interval end points using Updating Algorithm [More, Thuente 1994]
  765. interval_converged = updateIntervalMT (a_l, f_l, g_l,
  766. a_u, f_u, g_u,
  767. a_t, psi_t, d_psi_t);
  768. }
  769. else
  770. {
  771. // Update interval end points using Modified Updating Algorithm [More, Thuente 1994]
  772. interval_converged = updateIntervalMT (a_l, f_l, g_l,
  773. a_u, f_u, g_u,
  774. a_t, phi_t, d_phi_t);
  775. }
  776. step_iterations++;
  777. }
  778. // If inner loop was run then hessian needs to be calculated.
  779. // Hessian is unnecessary for step length determination but gradients are required
  780. // so derivative and transform data is stored for the next iteration.
  781. if (step_iterations)
  782. computeHessian (hessian, trans_cloud, x_t);
  783. return (a_t);
  784. }
  785. template<typename PointSource, typename PointTarget>
  786. double pclomp::NormalDistributionsTransform<PointSource, PointTarget>::calculateScore(const PointCloudSource & trans_cloud) const
  787. {
  788. double score = 0;
  789. for (std::size_t idx = 0; idx < trans_cloud.points.size(); idx++)
  790. {
  791. PointSource x_trans_pt = trans_cloud.points[idx];
  792. // Find neighbors (Radius search has been experimentally faster than direct neighbor checking.
  793. std::vector<TargetGridLeafConstPtr> neighborhood;
  794. std::vector<float> distances;
  795. switch (search_method) {
  796. case KDTREE:
  797. target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
  798. break;
  799. case DIRECT26:
  800. target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);
  801. break;
  802. default:
  803. case DIRECT7:
  804. target_cells_.getNeighborhoodAtPoint7(x_trans_pt, neighborhood);
  805. break;
  806. case DIRECT1:
  807. target_cells_.getNeighborhoodAtPoint1(x_trans_pt, neighborhood);
  808. break;
  809. }
  810. for (typename std::vector<TargetGridLeafConstPtr>::iterator neighborhood_it = neighborhood.begin(); neighborhood_it != neighborhood.end(); neighborhood_it++)
  811. {
  812. TargetGridLeafConstPtr cell = *neighborhood_it;
  813. Eigen::Vector3d x_trans = Eigen::Vector3d(x_trans_pt.x, x_trans_pt.y, x_trans_pt.z);
  814. // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
  815. x_trans -= cell->getMean();
  816. // Uses precomputed covariance for speed.
  817. Eigen::Matrix3d c_inv = cell->getInverseCov();
  818. // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
  819. double e_x_cov_x = exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2);
  820. // Calculate probability of transformed points existence, Equation 6.9 [Magnusson 2009]
  821. double score_inc = -gauss_d1_ * e_x_cov_x - gauss_d3_;
  822. score += score_inc / neighborhood.size();
  823. }
  824. }
  825. return (score) / static_cast<double> (trans_cloud.size());
  826. }
  827. #endif // PCL_REGISTRATION_NDT_IMPL_H_