Point Cloud Library (PCL)  1.15.1-dev
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, typename Scalar>
47 void
49  unsigned int nr_threads)
50 {
51 #ifdef _OPENMP
52  if (nr_threads == 0)
53  threads_ = omp_get_num_procs();
54  else
55  threads_ = nr_threads;
56  PCL_DEBUG("[pcl::NormalDistributionsTransform::setNumberOfThreads] Setting "
57  "number of threads to %u.\n",
58  threads_);
59 #else
60  threads_ = 1;
61  if (nr_threads != 1)
62  PCL_WARN("[pcl::NormalDistributionsTransform::setNumberOfThreads] "
63  "Parallelization is requested, but OpenMP is not available! Continuing "
64  "without parallelization.\n");
65 #endif // _OPENMP
66 }
67 
68 template <typename PointSource, typename PointTarget, typename Scalar>
71 : target_cells_()
72 {
73  reg_name_ = "NormalDistributionsTransform";
74 
76  max_iterations_ = 35;
77 }
78 
79 template <typename PointSource, typename PointTarget, typename Scalar>
80 void
82  PointCloudSource& output, const Matrix4& guess)
83 {
84  nr_iterations_ = 0;
85  converged_ = false;
86  if (target_cells_.getCentroids()->empty()) {
87  PCL_ERROR("[%s::computeTransformation] Voxel grid is not searchable!\n",
88  getClassName().c_str());
89  return;
90  }
91 
92  // Initializes the gaussian fitting parameters (eq. 6.8) [Magnusson 2009]
93  const double gauss_c1 = 10 * (1 - outlier_ratio_);
94  const double gauss_c2 = outlier_ratio_ / pow(resolution_, 3);
95  const double gauss_d3 = -std::log(gauss_c2);
96  gauss_d1_ = -std::log(gauss_c1 + gauss_c2) - gauss_d3;
97  gauss_d2_ =
98  -2 * std::log((-std::log(gauss_c1 * std::exp(-0.5) + gauss_c2) - gauss_d3) /
99  gauss_d1_);
100 
101  if (guess != Matrix4::Identity()) {
102  // Initialise final transformation to the guessed one
103  final_transformation_ = guess;
104  // Apply guessed transformation prior to search for neighbours
105  transformPointCloud(output, output, guess);
106  }
107 
108  // Initialize Point Gradient and Hessian
109  point_jacobian_.setZero();
110  point_jacobian_.block<3, 3>(0, 0).setIdentity();
111  point_hessian_.setZero();
112 
113  Eigen::Transform<Scalar, 3, Eigen::Affine, Eigen::ColMajor> eig_transformation;
114  eig_transformation.matrix() = final_transformation_;
115 
116  // Convert initial guess matrix to 6 element transformation vector
117  Eigen::Matrix<double, 6, 1> transform, score_gradient;
118  Vector3 init_translation = eig_transformation.translation();
119  Vector3 init_rotation = eig_transformation.rotation().eulerAngles(0, 1, 2);
120  transform << init_translation.template cast<double>(),
121  init_rotation.template cast<double>();
122 
123  Eigen::Matrix<double, 6, 6> hessian;
124 
125  // Calculate derivates of initial transform vector, subsequent derivative calculations
126  // are done in the step length determination.
127  double score = computeDerivatives(score_gradient, hessian, output, transform);
128 
129  while (!converged_) {
130  // Store previous transformation
131  previous_transformation_ = transformation_;
132 
133  // Solve for decent direction using newton method, line 23 in Algorithm 2 [Magnusson
134  // 2009]
135  Eigen::JacobiSVD<Eigen::Matrix<double, 6, 6>> sv(
136  hessian, Eigen::ComputeFullU | Eigen::ComputeFullV);
137 #if EIGEN_VERSION_AT_LEAST(3, 4, 0)
138  if (sv.info() != Eigen::ComputationInfo::Success) {
139  trans_likelihood_ = score / static_cast<double>(input_->size());
140  converged_ = 0;
141  PCL_ERROR("[%s::computeTransformation] JacobiSVD on hessian failed!\n",
142  getClassName().c_str());
143  return;
144  }
145 #endif
146  // Negative for maximization as opposed to minimization
147  Eigen::Matrix<double, 6, 1> delta = sv.solve(-score_gradient);
148 
149  // Calculate step length with guaranteed sufficient decrease [More, Thuente 1994]
150  double delta_norm = delta.norm();
151 
152  if (delta_norm == 0 || std::isnan(delta_norm)) {
153  trans_likelihood_ = score / static_cast<double>(input_->size());
154  converged_ = delta_norm == 0;
155  return;
156  }
157 
158  delta /= delta_norm;
159  delta_norm = computeStepLengthMT(transform,
160  delta,
161  delta_norm,
162  step_size_,
163  transformation_epsilon_ / 2,
164  score,
165  score_gradient,
166  hessian,
167  output);
168  delta *= delta_norm;
169 
170  // Convert delta into matrix form
171  convertTransform(delta, transformation_);
172 
173  transform += delta;
174 
175  // Update Visualizer (untested)
176  if (update_visualizer_)
177  update_visualizer_(output, pcl::Indices(), *target_, pcl::Indices());
178 
179  const double cos_angle =
180  0.5 * (transformation_.template block<3, 3>(0, 0).trace() - 1);
181  const double translation_sqr =
182  transformation_.template block<3, 1>(0, 3).squaredNorm();
183 
184  nr_iterations_++;
185 
186  if (nr_iterations_ >= max_iterations_ ||
187  ((transformation_epsilon_ > 0 && translation_sqr <= transformation_epsilon_) &&
188  (transformation_rotation_epsilon_ > 0 &&
189  cos_angle >= transformation_rotation_epsilon_)) ||
190  ((transformation_epsilon_ <= 0) &&
191  (transformation_rotation_epsilon_ > 0 &&
192  cos_angle >= transformation_rotation_epsilon_)) ||
193  ((transformation_epsilon_ > 0 && translation_sqr <= transformation_epsilon_) &&
194  (transformation_rotation_epsilon_ <= 0))) {
195  converged_ = true;
196  }
197  }
198 
199  // Store transformation likelihood. The relative differences within each scan
200  // registration are accurate but the normalization constants need to be modified for
201  // it to be globally accurate
202  trans_likelihood_ = score / static_cast<double>(input_->size());
203 }
204 
205 template <typename PointSource, typename PointTarget, typename Scalar>
206 double
208  Eigen::Matrix<double, 6, 1>& score_gradient,
209  Eigen::Matrix<double, 6, 6>& hessian,
210  const PointCloudSource& trans_cloud,
211  const Eigen::Matrix<double, 6, 1>& transform,
212  bool compute_hessian)
213 {
214  score_gradient.setZero();
215  hessian.setZero();
216  double score = 0;
217 
218  // Precompute Angular Derivatives (eq. 6.19 and 6.21)[Magnusson 2009]
219  computeAngleDerivatives(transform);
220 
221  std::vector<TargetGridLeafConstPtr> neighborhood;
222  std::vector<float> distances;
223 
224  Eigen::Matrix<double, 3, 6> point_jacobian = Eigen::Matrix<double, 3, 6>::Zero();
225  point_jacobian.block<3, 3>(0, 0).setIdentity();
226  Eigen::Matrix<double, 18, 6> point_hessian = Eigen::Matrix<double, 18, 6>::Zero();
227 
228 #pragma omp parallel num_threads(threads_) default(none) shared(score_gradient, hessian, trans_cloud, compute_hessian) firstprivate(neighborhood, distances, point_jacobian, point_hessian) reduction(+: score)
229  {
230  // workaround for a user-defined reduction on score_gradient and hessian, that still
231  // works with OpenMP 2.0
232  Eigen::Matrix<double, 6, 1> score_gradient_private =
233  Eigen::Matrix<double, 6, 1>::Zero();
234  Eigen::Matrix<double, 6, 6> hessian_private = Eigen::Matrix<double, 6, 6>::Zero();
235 #pragma omp for schedule(dynamic, 32)
236  // Update gradient and hessian for each point, line 17 in Algorithm 2 [Magnusson
237  // 2009]
238  for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t>(input_->size());
239  idx++) {
240  // Transformed Point
241  const auto& x_trans_pt = trans_cloud[idx];
242 
243  // Find neighbors with different search method
244  neighborhood.clear();
245  switch (search_method_) {
247  // Radius search has been experimentally faster than direct neighbor checking.
248  target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
249  break;
251  target_cells_.getAllNeighborsAtPoint(x_trans_pt, neighborhood);
252  break;
254  target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);
255  break;
257  target_cells_.getFaceNeighborsAtPoint(x_trans_pt, neighborhood);
258  break;
260  target_cells_.getVoxelAtPoint(x_trans_pt, neighborhood);
261  break;
262  }
263 
264  // Original Point
265  const Eigen::Vector3d x = (*input_)[idx].getVector3fMap().template cast<double>();
266  const Eigen::Vector3d x_trans_position =
267  x_trans_pt.getVector3fMap().template cast<double>();
268 
269  for (const auto& cell : neighborhood) {
270  // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
271  const Eigen::Vector3d x_trans = x_trans_position - cell->getMean();
272  // Inverse Covariance of Occupied Voxel
273  // Uses precomputed covariance for speed.
274  const Eigen::Matrix3d c_inv = cell->getInverseCov();
275 
276  // Compute derivative of transform function w.r.t. transform vector, J_E and H_E
277  // in Equations 6.18 and 6.20 [Magnusson 2009]
278  computePointDerivatives(
279  x, point_jacobian, compute_hessian ? &point_hessian : nullptr);
280  // Update score, gradient and hessian, lines 19-21 in Algorithm 2, according to
281  // Equations 6.10, 6.12 and 6.13, respectively [Magnusson 2009]
282  score += updateDerivatives(score_gradient_private,
283  hessian_private,
284  x_trans,
285  c_inv,
286  point_jacobian,
287  compute_hessian ? &point_hessian : nullptr);
288  }
289  }
290 #pragma omp critical(accum_score_gradient)
291  {
292  score_gradient += score_gradient_private;
293  }
294 #pragma omp critical(accum_hessian)
295  {
296  hessian += hessian_private;
297  }
298  } // end of omp parallel
299  return score;
300 }
301 
302 template <typename PointSource, typename PointTarget, typename Scalar>
303 void
305  const Eigen::Matrix<double, 6, 1>& transform, bool compute_hessian)
306 {
307  // Simplified math for near 0 angles
308  const auto calculate_cos_sin = [](double angle, double& c, double& s) {
309  if (std::abs(angle) < 10e-5) {
310  c = 1.0;
311  s = 0.0;
312  }
313  else {
314  c = std::cos(angle);
315  s = std::sin(angle);
316  }
317  };
318 
319  double cx, cy, cz, sx, sy, sz;
320  calculate_cos_sin(transform(3), cx, sx);
321  calculate_cos_sin(transform(4), cy, sy);
322  calculate_cos_sin(transform(5), cz, sz);
323 
324  // Precomputed angular gradient components. Letters correspond to Equation 6.19
325  // [Magnusson 2009]
326  angular_jacobian_.setZero();
327  angular_jacobian_.row(0).noalias() = Eigen::Vector4d(
328  (-sx * sz + cx * sy * cz), (-sx * cz - cx * sy * sz), (-cx * cy), 1.0); // a
329  angular_jacobian_.row(1).noalias() = Eigen::Vector4d(
330  (cx * sz + sx * sy * cz), (cx * cz - sx * sy * sz), (-sx * cy), 1.0); // b
331  angular_jacobian_.row(2).noalias() =
332  Eigen::Vector4d((-sy * cz), sy * sz, cy, 1.0); // c
333  angular_jacobian_.row(3).noalias() =
334  Eigen::Vector4d(sx * cy * cz, (-sx * cy * sz), sx * sy, 1.0); // d
335  angular_jacobian_.row(4).noalias() =
336  Eigen::Vector4d((-cx * cy * cz), cx * cy * sz, (-cx * sy), 1.0); // e
337  angular_jacobian_.row(5).noalias() =
338  Eigen::Vector4d((-cy * sz), (-cy * cz), 0, 1.0); // f
339  angular_jacobian_.row(6).noalias() =
340  Eigen::Vector4d((cx * cz - sx * sy * sz), (-cx * sz - sx * sy * cz), 0, 1.0); // g
341  angular_jacobian_.row(7).noalias() =
342  Eigen::Vector4d((sx * cz + cx * sy * sz), (cx * sy * cz - sx * sz), 0, 1.0); // h
343 
344  if (compute_hessian) {
345  // Precomputed angular hessian components. Letters correspond to Equation 6.21 and
346  // numbers correspond to row index [Magnusson 2009]
347  angular_hessian_.setZero();
348  angular_hessian_.row(0).noalias() = Eigen::Vector4d(
349  (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), sx * cy, 0.0f); // a2
350  angular_hessian_.row(1).noalias() = Eigen::Vector4d(
351  (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), (-cx * cy), 0.0f); // a3
352 
353  angular_hessian_.row(2).noalias() =
354  Eigen::Vector4d((cx * cy * cz), (-cx * cy * sz), (cx * sy), 0.0f); // b2
355  angular_hessian_.row(3).noalias() =
356  Eigen::Vector4d((sx * cy * cz), (-sx * cy * sz), (sx * sy), 0.0f); // b3
357 
358  // The sign of 'sx * sz' in c2 is incorrect in the thesis, and is fixed here.
359  angular_hessian_.row(4).noalias() = Eigen::Vector4d(
360  (-sx * cz - cx * sy * sz), (sx * sz - cx * sy * cz), 0, 0.0f); // c2
361  angular_hessian_.row(5).noalias() = Eigen::Vector4d(
362  (cx * cz - sx * sy * sz), (-sx * sy * cz - cx * sz), 0, 0.0f); // c3
363 
364  angular_hessian_.row(6).noalias() =
365  Eigen::Vector4d((-cy * cz), (cy * sz), (-sy), 0.0f); // d1
366  angular_hessian_.row(7).noalias() =
367  Eigen::Vector4d((-sx * sy * cz), (sx * sy * sz), (sx * cy), 0.0f); // d2
368  angular_hessian_.row(8).noalias() =
369  Eigen::Vector4d((cx * sy * cz), (-cx * sy * sz), (-cx * cy), 0.0f); // d3
370 
371  angular_hessian_.row(9).noalias() =
372  Eigen::Vector4d((sy * sz), (sy * cz), 0, 0.0f); // e1
373  angular_hessian_.row(10).noalias() =
374  Eigen::Vector4d((-sx * cy * sz), (-sx * cy * cz), 0, 0.0f); // e2
375  angular_hessian_.row(11).noalias() =
376  Eigen::Vector4d((cx * cy * sz), (cx * cy * cz), 0, 0.0f); // e3
377 
378  angular_hessian_.row(12).noalias() =
379  Eigen::Vector4d((-cy * cz), (cy * sz), 0, 0.0f); // f1
380  angular_hessian_.row(13).noalias() = Eigen::Vector4d(
381  (-cx * sz - sx * sy * cz), (-cx * cz + sx * sy * sz), 0, 0.0f); // f2
382  angular_hessian_.row(14).noalias() = Eigen::Vector4d(
383  (-sx * sz + cx * sy * cz), (-cx * sy * sz - sx * cz), 0, 0.0f); // f3
384  }
385 }
386 
387 template <typename PointSource, typename PointTarget, typename Scalar>
388 void
390  const Eigen::Vector3d& x,
391  Eigen::Matrix<double, 3, 6>& point_jacobian,
392  Eigen::Matrix<double, 18, 6>* point_hessian) const
393 {
394  // Calculate first derivative of Transformation Equation 6.17 w.r.t. transform vector.
395  // Derivative w.r.t. ith element of transform vector corresponds to column i,
396  // Equation 6.18 and 6.19 [Magnusson 2009]
397  Eigen::Matrix<double, 8, 1> point_angular_jacobian =
398  angular_jacobian_ * Eigen::Vector4d(x[0], x[1], x[2], 0.0);
399  point_jacobian(1, 3) = point_angular_jacobian[0];
400  point_jacobian(2, 3) = point_angular_jacobian[1];
401  point_jacobian(0, 4) = point_angular_jacobian[2];
402  point_jacobian(1, 4) = point_angular_jacobian[3];
403  point_jacobian(2, 4) = point_angular_jacobian[4];
404  point_jacobian(0, 5) = point_angular_jacobian[5];
405  point_jacobian(1, 5) = point_angular_jacobian[6];
406  point_jacobian(2, 5) = point_angular_jacobian[7];
407 
408  if (point_hessian) {
409  Eigen::Matrix<double, 15, 1> point_angular_hessian =
410  angular_hessian_ * Eigen::Vector4d(x[0], x[1], x[2], 0.0);
411 
412  // Vectors from Equation 6.21 [Magnusson 2009]
413  const Eigen::Vector3d a(0, point_angular_hessian[0], point_angular_hessian[1]);
414  const Eigen::Vector3d b(0, point_angular_hessian[2], point_angular_hessian[3]);
415  const Eigen::Vector3d c(0, point_angular_hessian[4], point_angular_hessian[5]);
416  const Eigen::Vector3d d = point_angular_hessian.block<3, 1>(6, 0);
417  const Eigen::Vector3d e = point_angular_hessian.block<3, 1>(9, 0);
418  const Eigen::Vector3d f = point_angular_hessian.block<3, 1>(12, 0);
419 
420  // Calculate second derivative of Transformation Equation 6.17 w.r.t. transform
421  // vector. Derivative w.r.t. ith and jth elements of transform vector corresponds to
422  // the 3x1 block matrix starting at (3i,j), Equation 6.20 and 6.21 [Magnusson 2009]
423  point_hessian->block<3, 1>(9, 3) = a;
424  point_hessian->block<3, 1>(12, 3) = b;
425  point_hessian->block<3, 1>(15, 3) = c;
426  point_hessian->block<3, 1>(9, 4) = b;
427  point_hessian->block<3, 1>(12, 4) = d;
428  point_hessian->block<3, 1>(15, 4) = e;
429  point_hessian->block<3, 1>(9, 5) = c;
430  point_hessian->block<3, 1>(12, 5) = e;
431  point_hessian->block<3, 1>(15, 5) = f;
432  }
433 }
434 
435 template <typename PointSource, typename PointTarget, typename Scalar>
436 void
438  const Eigen::Vector3d& x, bool compute_hessian)
439 {
440  computePointDerivatives(
441  x, point_jacobian_, compute_hessian ? &point_hessian_ : nullptr);
442 }
443 
444 template <typename PointSource, typename PointTarget, typename Scalar>
445 double
447  Eigen::Matrix<double, 6, 1>& score_gradient,
448  Eigen::Matrix<double, 6, 6>& hessian,
449  const Eigen::Vector3d& x_trans,
450  const Eigen::Matrix3d& c_inv,
451  const Eigen::Matrix<double, 3, 6>& point_jacobian,
452  const Eigen::Matrix<double, 18, 6>* point_hessian) const
453 {
454  // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
455  double e_x_cov_x = std::exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2);
456  // Calculate likelihood of transformed points existence, Equation 6.9 [Magnusson
457  // 2009]
458  const double score_inc = -gauss_d1_ * e_x_cov_x;
459 
460  e_x_cov_x = gauss_d2_ * e_x_cov_x;
461 
462  // Error checking for invalid values.
463  if (e_x_cov_x > 1 || e_x_cov_x < 0 || std::isnan(e_x_cov_x)) {
464  return 0;
465  }
466 
467  // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
468  e_x_cov_x *= gauss_d1_;
469 
470  for (int i = 0; i < 6; i++) {
471  // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson
472  // 2009]
473  const Eigen::Vector3d cov_dxd_pi = c_inv * point_jacobian.col(i);
474 
475  // Update gradient, Equation 6.12 [Magnusson 2009]
476  score_gradient(i) += x_trans.dot(cov_dxd_pi) * e_x_cov_x;
477 
478  if (point_hessian) {
479  for (Eigen::Index j = 0; j < hessian.cols(); j++) {
480  // Update hessian, Equation 6.13 [Magnusson 2009]
481  hessian(i, j) +=
482  e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) *
483  x_trans.dot(c_inv * point_jacobian.col(j)) +
484  x_trans.dot(c_inv * point_hessian->block<3, 1>(3 * i, j)) +
485  point_jacobian.col(j).dot(cov_dxd_pi));
486  }
487  }
488  }
489 
490  return score_inc;
491 }
492 
493 template <typename PointSource, typename PointTarget, typename Scalar>
494 double
496  Eigen::Matrix<double, 6, 1>& score_gradient,
497  Eigen::Matrix<double, 6, 6>& hessian,
498  const Eigen::Vector3d& x_trans,
499  const Eigen::Matrix3d& c_inv,
500  bool compute_hessian) const
501 {
502  return updateDerivatives(score_gradient,
503  hessian,
504  x_trans,
505  c_inv,
506  point_jacobian_,
507  compute_hessian ? &point_hessian_ : nullptr);
508 }
509 
510 template <typename PointSource, typename PointTarget, typename Scalar>
511 void
513  Eigen::Matrix<double, 6, 6>& hessian, const PointCloudSource& trans_cloud)
514 {
515  hessian.setZero();
516 
517  // Precompute Angular Derivatives unnecessary because only used after regular
518  // derivative calculation Update hessian for each point, line 17 in Algorithm 2
519  // [Magnusson 2009]
520  for (std::size_t idx = 0; idx < input_->size(); idx++) {
521  // Transformed Point
522  const auto& x_trans_pt = trans_cloud[idx];
523 
524  std::vector<TargetGridLeafConstPtr> neighborhood;
525  std::vector<float> distances;
526 
527  // Find neighbors with different search methods
528  switch (search_method_) {
530  // Radius search has been experimentally faster than direct neighbor checking.
531  target_cells_.radiusSearch(x_trans_pt, resolution_, neighborhood, distances);
532  break;
534  target_cells_.getAllNeighborsAtPoint(x_trans_pt, neighborhood);
535  break;
537  target_cells_.getNeighborhoodAtPoint(x_trans_pt, neighborhood);
538  break;
540  target_cells_.getFaceNeighborsAtPoint(x_trans_pt, neighborhood);
541  break;
543  target_cells_.getVoxelAtPoint(x_trans_pt, neighborhood);
544  break;
545  }
546 
547  for (const auto& cell : neighborhood) {
548  // Original Point
549  const auto& x_pt = (*input_)[idx];
550  const Eigen::Vector3d x = x_pt.getVector3fMap().template cast<double>();
551 
552  // Denorm point, x_k' in Equations 6.12 and 6.13 [Magnusson 2009]
553  const Eigen::Vector3d x_trans =
554  x_trans_pt.getVector3fMap().template cast<double>() - cell->getMean();
555  // Inverse Covariance of Occupied Voxel
556  // Uses precomputed covariance for speed.
557  const Eigen::Matrix3d c_inv = cell->getInverseCov();
558 
559  // Compute derivative of transform function w.r.t. transform vector, J_E and H_E
560  // in Equations 6.18 and 6.20 [Magnusson 2009]
561  computePointDerivatives(x);
562  // Update hessian, lines 21 in Algorithm 2, according to Equations 6.10, 6.12
563  // and 6.13, respectively [Magnusson 2009]
564  updateHessian(hessian, x_trans, c_inv);
565  }
566  }
567 }
568 
569 template <typename PointSource, typename PointTarget, typename Scalar>
570 void
572  Eigen::Matrix<double, 6, 6>& hessian,
573  const Eigen::Vector3d& x_trans,
574  const Eigen::Matrix3d& c_inv,
575  const Eigen::Matrix<double, 3, 6>& point_jacobian,
576  const Eigen::Matrix<double, 18, 6>& point_hessian) const
577 {
578  // e^(-d_2/2 * (x_k - mu_k)^T Sigma_k^-1 (x_k - mu_k)) Equation 6.9 [Magnusson 2009]
579  double e_x_cov_x =
580  gauss_d2_ * std::exp(-gauss_d2_ * x_trans.dot(c_inv * x_trans) / 2);
581 
582  // Error checking for invalid values.
583  if (e_x_cov_x > 1 || e_x_cov_x < 0 || std::isnan(e_x_cov_x)) {
584  return;
585  }
586 
587  // Reusable portion of Equation 6.12 and 6.13 [Magnusson 2009]
588  e_x_cov_x *= gauss_d1_;
589 
590  for (int i = 0; i < 6; i++) {
591  // Sigma_k^-1 d(T(x,p))/dpi, Reusable portion of Equation 6.12 and 6.13 [Magnusson
592  // 2009]
593  const Eigen::Vector3d cov_dxd_pi = c_inv * point_jacobian.col(i);
594 
595  for (Eigen::Index j = 0; j < hessian.cols(); j++) {
596  // Update hessian, Equation 6.13 [Magnusson 2009]
597  hessian(i, j) +=
598  e_x_cov_x * (-gauss_d2_ * x_trans.dot(cov_dxd_pi) *
599  x_trans.dot(c_inv * point_jacobian.col(j)) +
600  x_trans.dot(c_inv * point_hessian.block<3, 1>(3 * i, j)) +
601  point_jacobian.col(j).dot(cov_dxd_pi));
602  }
603  }
604 }
605 
606 template <typename PointSource, typename PointTarget, typename Scalar>
607 void
609  Eigen::Matrix<double, 6, 6>& hessian,
610  const Eigen::Vector3d& x_trans,
611  const Eigen::Matrix3d& c_inv) const
612 {
613  updateHessian(hessian, x_trans, c_inv, point_jacobian_, point_hessian_);
614 }
615 
616 template <typename PointSource, typename PointTarget, typename Scalar>
617 bool
619  double& a_l,
620  double& f_l,
621  double& g_l,
622  double& a_u,
623  double& f_u,
624  double& g_u,
625  double a_t,
626  double f_t,
627  double g_t) const
628 {
629  // Case U1 in Update Algorithm and Case a in Modified Update Algorithm [More, Thuente
630  // 1994]
631  if (f_t > f_l) {
632  a_u = a_t;
633  f_u = f_t;
634  g_u = g_t;
635  return false;
636  }
637  // Case U2 in Update Algorithm and Case b in Modified Update Algorithm [More, Thuente
638  // 1994]
639  if (g_t * (a_l - a_t) > 0) {
640  a_l = a_t;
641  f_l = f_t;
642  g_l = g_t;
643  return false;
644  }
645  // Case U3 in Update Algorithm and Case c in Modified Update Algorithm [More, Thuente
646  // 1994]
647  if (g_t * (a_l - a_t) < 0) {
648  a_u = a_l;
649  f_u = f_l;
650  g_u = g_l;
651 
652  a_l = a_t;
653  f_l = f_t;
654  g_l = g_t;
655  return false;
656  }
657  // Interval Converged
658  return true;
659 }
660 
661 template <typename PointSource, typename PointTarget, typename Scalar>
662 double
664  double a_l,
665  double f_l,
666  double g_l,
667  double a_u,
668  double f_u,
669  double g_u,
670  double a_t,
671  double f_t,
672  double g_t) const
673 {
674  if (a_t == a_l && a_t == a_u) {
675  return a_t;
676  }
677 
678  // Endpoints condition check [More, Thuente 1994], p.299 - 300
679  enum class EndpointsCondition { Case1, Case2, Case3, Case4 };
680  EndpointsCondition condition;
681 
682  if (a_t == a_l) {
683  condition = EndpointsCondition::Case4;
684  }
685  else if (f_t > f_l) {
686  condition = EndpointsCondition::Case1;
687  }
688  else if (g_t * g_l < 0) {
689  condition = EndpointsCondition::Case2;
690  }
691  else if (std::fabs(g_t) <= std::fabs(g_l)) {
692  condition = EndpointsCondition::Case3;
693  }
694  else {
695  condition = EndpointsCondition::Case4;
696  }
697 
698  switch (condition) {
699  case EndpointsCondition::Case1: {
700  // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
701  // Equation 2.4.52 [Sun, Yuan 2006]
702  const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
703  const double w = std::sqrt(z * z - g_t * g_l);
704  // Equation 2.4.56 [Sun, Yuan 2006]
705  const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
706 
707  // Calculate the minimizer of the quadratic that interpolates f_l, f_t and g_l
708  // Equation 2.4.2 [Sun, Yuan 2006]
709  const double a_q =
710  a_l - 0.5 * (a_l - a_t) * g_l / (g_l - (f_l - f_t) / (a_l - a_t));
711 
712  if (std::fabs(a_c - a_l) < std::fabs(a_q - a_l)) {
713  return a_c;
714  }
715  return 0.5 * (a_q + a_c);
716  }
717 
718  case EndpointsCondition::Case2: {
719  // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
720  // Equation 2.4.52 [Sun, Yuan 2006]
721  const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
722  const double w = std::sqrt(z * z - g_t * g_l);
723  // Equation 2.4.56 [Sun, Yuan 2006]
724  const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
725 
726  // Calculate the minimizer of the quadratic that interpolates f_l, g_l and g_t
727  // Equation 2.4.5 [Sun, Yuan 2006]
728  const double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
729 
730  if (std::fabs(a_c - a_t) >= std::fabs(a_s - a_t)) {
731  return a_c;
732  }
733  return a_s;
734  }
735 
736  case EndpointsCondition::Case3: {
737  // Calculate the minimizer of the cubic that interpolates f_l, f_t, g_l and g_t
738  // Equation 2.4.52 [Sun, Yuan 2006]
739  const double z = 3 * (f_t - f_l) / (a_t - a_l) - g_t - g_l;
740  const double w = std::sqrt(z * z - g_t * g_l);
741  const double a_c = a_l + (a_t - a_l) * (w - g_l - z) / (g_t - g_l + 2 * w);
742 
743  // Calculate the minimizer of the quadratic that interpolates g_l and g_t
744  // Equation 2.4.5 [Sun, Yuan 2006]
745  const double a_s = a_l - (a_l - a_t) / (g_l - g_t) * g_l;
746 
747  double a_t_next;
748 
749  if (std::fabs(a_c - a_t) < std::fabs(a_s - a_t)) {
750  a_t_next = a_c;
751  }
752  else {
753  a_t_next = a_s;
754  }
755 
756  if (a_t > a_l) {
757  return std::min(a_t + 0.66 * (a_u - a_t), a_t_next);
758  }
759  return std::max(a_t + 0.66 * (a_u - a_t), a_t_next);
760  }
761 
762  default:
763  case EndpointsCondition::Case4: {
764  // Calculate the minimizer of the cubic that interpolates f_u, f_t, g_u and g_t
765  // Equation 2.4.52 [Sun, Yuan 2006]
766  const double z = 3 * (f_t - f_u) / (a_t - a_u) - g_t - g_u;
767  const double w = std::sqrt(z * z - g_t * g_u);
768  // Equation 2.4.56 [Sun, Yuan 2006]
769  return a_u + (a_t - a_u) * (w - g_u - z) / (g_t - g_u + 2 * w);
770  }
771  }
772 }
773 
774 template <typename PointSource, typename PointTarget, typename Scalar>
775 double
777  const Eigen::Matrix<double, 6, 1>& x,
778  Eigen::Matrix<double, 6, 1>& step_dir,
779  double step_init,
780  double step_max,
781  double step_min,
782  double& score,
783  Eigen::Matrix<double, 6, 1>& score_gradient,
784  Eigen::Matrix<double, 6, 6>& hessian,
785  PointCloudSource& trans_cloud)
786 {
787  // Set the value of phi(0), Equation 1.3 [More, Thuente 1994]
788  const double phi_0 = -score;
789  // Set the value of phi'(0), Equation 1.3 [More, Thuente 1994]
790  double d_phi_0 = -(score_gradient.dot(step_dir));
791 
792  if (d_phi_0 >= 0) {
793  // Not a decent direction
794  if (d_phi_0 == 0) {
795  return 0;
796  }
797  // Reverse step direction and calculate optimal step.
798  d_phi_0 *= -1;
799  step_dir *= -1;
800  }
801 
802  // The Search Algorithm for T(mu) [More, Thuente 1994]
803 
804  constexpr int max_step_iterations = 10;
805  int step_iterations = 0;
806 
807  // Sufficient decrease constant, Equation 1.1 [More, Thuete 1994]
808  constexpr double mu = 1.e-4;
809  // Curvature condition constant, Equation 1.2 [More, Thuete 1994]
810  constexpr double nu = 0.9;
811 
812  // Initial endpoints of Interval I,
813  double a_l = 0, a_u = 0;
814 
815  // Auxiliary function psi is used until I is determined ot be a closed interval,
816  // Equation 2.1 [More, Thuente 1994]
817  double f_l = auxilaryFunction_PsiMT(a_l, phi_0, phi_0, d_phi_0, mu);
818  double g_l = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu);
819 
820  double f_u = auxilaryFunction_PsiMT(a_u, phi_0, phi_0, d_phi_0, mu);
821  double g_u = auxilaryFunction_dPsiMT(d_phi_0, d_phi_0, mu);
822 
823  // Check used to allow More-Thuente step length calculation to be skipped by making
824  // step_min == step_max
825  bool interval_converged = (step_max - step_min) < 0, open_interval = true;
826 
827  double a_t = step_init;
828  a_t = std::min(a_t, step_max);
829  a_t = std::max(a_t, step_min);
830 
831  Eigen::Matrix<double, 6, 1> x_t = x + step_dir * a_t;
832 
833  // Convert x_t into matrix form
834  convertTransform(x_t, final_transformation_);
835 
836  // New transformed point cloud
837  transformPointCloud(*input_, trans_cloud, final_transformation_);
838 
839  // Updates score, gradient and hessian. Hessian calculation is unnecessary but
840  // testing showed that most step calculations use the initial step suggestion and
841  // recalculation the reusable portions of the hessian would entail more computation
842  // time.
843  score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true);
844 
845  // Calculate phi(alpha_t)
846  double phi_t = -score;
847  // Calculate phi'(alpha_t)
848  double d_phi_t = -(score_gradient.dot(step_dir));
849 
850  // Calculate psi(alpha_t)
851  double psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu);
852  // Calculate psi'(alpha_t)
853  double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu);
854 
855  // Iterate until max number of iterations, interval convergence or a value satisfies
856  // the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More,
857  // Thuente 1994]
858  while (!interval_converged && step_iterations < max_step_iterations &&
859  (psi_t > 0 /*Sufficient Decrease*/ ||
860  d_phi_t > -nu * d_phi_0 /*Curvature Condition*/)) {
861  // Use auxiliary function if interval I is not closed
862  if (open_interval) {
863  a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t);
864  }
865  else {
866  a_t = trialValueSelectionMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t);
867  }
868 
869  a_t = std::min(a_t, step_max);
870  a_t = std::max(a_t, step_min);
871 
872  x_t = x + step_dir * a_t;
873 
874  // Convert x_t into matrix form
875  convertTransform(x_t, final_transformation_);
876 
877  // New transformed point cloud
878  // Done on final cloud to prevent wasted computation
879  transformPointCloud(*input_, trans_cloud, final_transformation_);
880 
881  // Updates score, gradient. Values stored to prevent wasted computation.
882  score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, false);
883 
884  // Calculate phi(alpha_t+)
885  phi_t = -score;
886  // Calculate phi'(alpha_t+)
887  d_phi_t = -(score_gradient.dot(step_dir));
888 
889  // Calculate psi(alpha_t+)
890  psi_t = auxilaryFunction_PsiMT(a_t, phi_t, phi_0, d_phi_0, mu);
891  // Calculate psi'(alpha_t+)
892  d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu);
893 
894  // Check if I is now a closed interval
895  if (open_interval && (psi_t <= 0 && d_psi_t >= 0)) {
896  open_interval = false;
897 
898  // Converts f_l and g_l from psi to phi
899  f_l += phi_0 - mu * d_phi_0 * a_l;
900  g_l += mu * d_phi_0;
901 
902  // Converts f_u and g_u from psi to phi
903  f_u += phi_0 - mu * d_phi_0 * a_u;
904  g_u += mu * d_phi_0;
905  }
906 
907  if (open_interval) {
908  // Update interval end points using Updating Algorithm [More, Thuente 1994]
909  interval_converged =
910  updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, psi_t, d_psi_t);
911  }
912  else {
913  // Update interval end points using Modified Updating Algorithm [More, Thuente
914  // 1994]
915  interval_converged =
916  updateIntervalMT(a_l, f_l, g_l, a_u, f_u, g_u, a_t, phi_t, d_phi_t);
917  }
918 
919  step_iterations++;
920  }
921 
922  // If inner loop was run then hessian needs to be calculated.
923  // Hessian is unnecessary for step length determination but gradients are required
924  // so derivative and transform data is stored for the next iteration.
925  if (step_iterations) {
926  computeHessian(hessian, trans_cloud);
927  }
928 
929  return a_t;
930 }
931 
932 } // namespace pcl
933 
934 #endif // PCL_REGISTRATION_NDT_IMPL_H_
void setNumberOfThreads(unsigned int nr_threads=0)
Initialize the scheduler and set the number of threads to use.
Definition: ndt.hpp:48
virtual void computeTransformation(PointCloudSource &output)
Estimate the transformation and returns the transformed source (input) as output.
Definition: ndt.h:340
void computePointDerivatives(const Eigen::Vector3d &x, Eigen::Matrix< double, 3, 6 > &point_jacobian, Eigen::Matrix< double, 18, 6 > *point_hessian) const
Compute point derivatives.
Definition: ndt.hpp:389
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 likelihood function w.r.t.
Definition: ndt.hpp:207
void computeAngleDerivatives(const Eigen::Matrix< double, 6, 1 > &transform, bool compute_hessian=true)
Precompute angular components of derivatives.
Definition: ndt.hpp:304
typename Registration< PointSource, PointTarget, Scalar >::PointCloudSource PointCloudSource
Definition: ndt.h:79
NormalDistributionsTransform()
Constructor.
Definition: ndt.hpp:70
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:618
void computeHessian(Eigen::Matrix< double, 6, 6 > &hessian, const PointCloudSource &trans_cloud)
Compute hessian of likelihood function w.r.t.
Definition: ndt.hpp:512
typename Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: ndt.h:106
typename Registration< PointSource, PointTarget, Scalar >::Matrix4 Matrix4
Definition: ndt.h:107
void updateHessian(Eigen::Matrix< double, 6, 6 > &hessian, const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv, const Eigen::Matrix< double, 3, 6 > &point_jacobian, const Eigen::Matrix< double, 18, 6 > &point_hessian) const
Compute individual point contributions to hessian of likelihood function w.r.t.
Definition: ndt.hpp:571
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:663
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 likelihood derivatives using More-Thuente me...
Definition: ndt.hpp:776
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, const Eigen::Matrix< double, 3, 6 > &point_jacobian, const Eigen::Matrix< double, 18, 6 > *point_hessian) const
Compute individual point contributions to derivatives of likelihood function w.r.t.
Definition: ndt.hpp:446
std::string reg_name_
The registration method name.
Definition: registration.h:548
int max_iterations_
The maximum number of iterations the internal optimization should run for.
Definition: registration.h:563
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:585
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