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