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