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