Point Cloud Library (PCL)  1.9.1-dev
ndt.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, 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 #pragma once
42 
43 #include <pcl/registration/registration.h>
44 #include <pcl/filters/voxel_grid_covariance.h>
45 
46 #include <unsupported/Eigen/NonLinearOptimization>
47 
48 namespace pcl
49 {
50  /** \brief A 3D Normal Distribution Transform registration implementation for point cloud data.
51  * \note For more information please see
52  * <b>Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform —
53  * an Efficient Representation for Registration, Surface Analysis, and Loop Detection.
54  * PhD thesis, Orebro University. Orebro Studies in Technology 36.</b>,
55  * <b>More, J., and Thuente, D. (1994). Line Search Algorithm with Guaranteed Sufficient Decrease
56  * In ACM Transactions on Mathematical Software.</b> and
57  * Sun, W. and Yuan, Y, (2006) Optimization Theory and Methods: Nonlinear Programming. 89-100
58  * \note Math refactored by Todor Stoyanov.
59  * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific)
60  */
61  template<typename PointSource, typename PointTarget>
62  class NormalDistributionsTransform : public Registration<PointSource, PointTarget>
63  {
64  protected:
65 
67  typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
68  typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
69 
71  typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
72  typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
73 
76 
77  /** \brief Typename of searchable voxel grid containing mean and covariance. */
79  /** \brief Typename of pointer to searchable voxel grid. */
80  typedef TargetGrid* TargetGridPtr;
81  /** \brief Typename of const pointer to searchable voxel grid. */
82  typedef const TargetGrid* TargetGridConstPtr;
83  /** \brief Typename of const pointer to searchable voxel grid leaf. */
85 
86 
87  public:
88 
89  typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > Ptr;
90  typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > ConstPtr;
91 
92 
93  /** \brief Constructor.
94  * Sets \ref outlier_ratio_ to 0.35, \ref step_size_ to 0.05 and \ref resolution_ to 1.0
95  */
97 
98  /** \brief Empty destructor */
100 
101  /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to).
102  * \param[in] cloud the input point cloud target
103  */
104  inline void
105  setInputTarget (const PointCloudTargetConstPtr &cloud)
106  {
108  init ();
109  }
110 
111  /** \brief Set/change the voxel grid resolution.
112  * \param[in] resolution side length of voxels
113  */
114  inline void
115  setResolution (float resolution)
116  {
117  // Prevents unnessary voxel initiations
118  if (resolution_ != resolution)
119  {
120  resolution_ = resolution;
121  if (input_)
122  init ();
123  }
124  }
125 
126  /** \brief Get voxel grid resolution.
127  * \return side length of voxels
128  */
129  inline float
130  getResolution () const
131  {
132  return (resolution_);
133  }
134 
135  /** \brief Get the newton line search maximum step length.
136  * \return maximum step length
137  */
138  inline double
139  getStepSize () const
140  {
141  return (step_size_);
142  }
143 
144  /** \brief Set/change the newton line search maximum step length.
145  * \param[in] step_size maximum step length
146  */
147  inline void
148  setStepSize (double step_size)
149  {
150  step_size_ = step_size;
151  }
152 
153  /** \brief Get the point cloud outlier ratio.
154  * \return outlier ratio
155  */
156  inline double
157  getOulierRatio () const
158  {
159  return (outlier_ratio_);
160  }
161 
162  /** \brief Set/change the point cloud outlier ratio.
163  * \param[in] outlier_ratio outlier ratio
164  */
165  inline void
166  setOulierRatio (double outlier_ratio)
167  {
168  outlier_ratio_ = outlier_ratio;
169  }
170 
171  /** \brief Get the registration alignment probability.
172  * \return transformation probability
173  */
174  inline double
176  {
177  return (trans_probability_);
178  }
179 
180  /** \brief Get the number of iterations required to calculate alignment.
181  * \return final number of iterations
182  */
183  inline int
185  {
186  return (nr_iterations_);
187  }
188 
189  /** \brief Convert 6 element transformation vector to affine transformation.
190  * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw]
191  * \param[out] trans affine transform corresponding to given transfomation vector
192  */
193  static void
194  convertTransform (const Eigen::Matrix<double, 6, 1> &x, Eigen::Affine3f &trans)
195  {
196  trans = Eigen::Translation<float, 3>(float (x (0)), float (x (1)), float (x (2))) *
197  Eigen::AngleAxis<float>(float (x (3)), Eigen::Vector3f::UnitX ()) *
198  Eigen::AngleAxis<float>(float (x (4)), Eigen::Vector3f::UnitY ()) *
199  Eigen::AngleAxis<float>(float (x (5)), Eigen::Vector3f::UnitZ ());
200  }
201 
202  /** \brief Convert 6 element transformation vector to transformation matrix.
203  * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw]
204  * \param[out] trans 4x4 transformation matrix corresponding to given transfomation vector
205  */
206  static void
207  convertTransform (const Eigen::Matrix<double, 6, 1> &x, Eigen::Matrix4f &trans)
208  {
209  Eigen::Affine3f _affine;
210  convertTransform (x, _affine);
211  trans = _affine.matrix ();
212  }
213 
214  protected:
215 
231 
233 
234  /** \brief Estimate the transformation and returns the transformed source (input) as output.
235  * \param[out] output the resultant input transformed point cloud dataset
236  */
237  virtual void
238  computeTransformation (PointCloudSource &output)
239  {
240  computeTransformation (output, Eigen::Matrix4f::Identity ());
241  }
242 
243  /** \brief Estimate the transformation and returns the transformed source (input) as output.
244  * \param[out] output the resultant input transformed point cloud dataset
245  * \param[in] guess the initial gross estimation of the transformation
246  */
247  virtual void
248  computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
249 
250  /** \brief Initiate covariance voxel structure. */
251  void inline
252  init ()
253  {
256  // Initiate voxel structure.
257  target_cells_.filter (true);
258  }
259 
260  /** \brief Compute derivatives of probability function w.r.t. the transformation vector.
261  * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
262  * \param[out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector
263  * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
264  * \param[in] trans_cloud transformed point cloud
265  * \param[in] p the current transform vector
266  * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
267  */
268  double
269  computeDerivatives (Eigen::Matrix<double, 6, 1> &score_gradient,
270  Eigen::Matrix<double, 6, 6> &hessian,
271  PointCloudSource &trans_cloud,
272  Eigen::Matrix<double, 6, 1> &p,
273  bool compute_hessian = true);
274 
275  /** \brief Compute individual point contirbutions to derivatives of probability function w.r.t. the transformation vector.
276  * \note Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
277  * \param[in,out] score_gradient the gradient vector of the probability function w.r.t. the transformation vector
278  * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
279  * \param[in] x_trans transformed point minus mean of occupied covariance voxel
280  * \param[in] c_inv covariance of occupied covariance voxel
281  * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
282  */
283  double
284  updateDerivatives (Eigen::Matrix<double, 6, 1> &score_gradient,
285  Eigen::Matrix<double, 6, 6> &hessian,
286  Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv,
287  bool compute_hessian = true);
288 
289  /** \brief Precompute anglular components of derivatives.
290  * \note Equation 6.19 and 6.21 [Magnusson 2009].
291  * \param[in] p the current transform vector
292  * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
293  */
294  void
295  computeAngleDerivatives (Eigen::Matrix<double, 6, 1> &p, bool compute_hessian = true);
296 
297  /** \brief Compute point derivatives.
298  * \note Equation 6.18-21 [Magnusson 2009].
299  * \param[in] x point from the input cloud
300  * \param[in] compute_hessian flag to calculate hessian, unnessissary for step calculation.
301  */
302  void
303  computePointDerivatives (Eigen::Vector3d &x, bool compute_hessian = true);
304 
305  /** \brief Compute hessian of probability function w.r.t. the transformation vector.
306  * \note Equation 6.13 [Magnusson 2009].
307  * \param[out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
308  * \param[in] trans_cloud transformed point cloud
309  * \param[in] p the current transform vector
310  */
311  void
312  computeHessian (Eigen::Matrix<double, 6, 6> &hessian,
313  PointCloudSource &trans_cloud,
314  Eigen::Matrix<double, 6, 1> &p);
315 
316  /** \brief Compute individual point contirbutions to hessian of probability function w.r.t. the transformation vector.
317  * \note Equation 6.13 [Magnusson 2009].
318  * \param[in,out] hessian the hessian matrix of the probability function w.r.t. the transformation vector
319  * \param[in] x_trans transformed point minus mean of occupied covariance voxel
320  * \param[in] c_inv covariance of occupied covariance voxel
321  */
322  void
323  updateHessian (Eigen::Matrix<double, 6, 6> &hessian,
324  Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv);
325 
326  /** \brief Compute line search step length and update transform and probability derivatives using More-Thuente method.
327  * \note Search Algorithm [More, Thuente 1994]
328  * \param[in] x initial transformation vector, \f$ x \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \vec{p} \f$ in Algorithm 2 [Magnusson 2009]
329  * \param[in] step_dir descent direction, \f$ p \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in Algorithm 2 [Magnusson 2009]
330  * \param[in] step_init initial step length estimate, \f$ \alpha_0 \f$ in Moore-Thuente (1994) and the noramal of \f$ \delta \vec{p} \f$ in Algorithm 2 [Magnusson 2009]
331  * \param[in] step_max maximum step length, \f$ \alpha_max \f$ in Moore-Thuente (1994)
332  * \param[in] step_min minimum step length, \f$ \alpha_min \f$ in Moore-Thuente (1994)
333  * \param[out] score final score function value, \f$ f(x + \alpha p) \f$ in Equation 1.3 (Moore, Thuente 1994) and \f$ score \f$ in Algorithm 2 [Magnusson 2009]
334  * \param[in,out] score_gradient gradient of score function w.r.t. transformation vector, \f$ f'(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ \vec{g} \f$ in Algorithm 2 [Magnusson 2009]
335  * \param[out] hessian hessian of score function w.r.t. transformation vector, \f$ f''(x + \alpha p) \f$ in Moore-Thuente (1994) and \f$ H \f$ in Algorithm 2 [Magnusson 2009]
336  * \param[in,out] trans_cloud transformed point cloud, \f$ X \f$ transformed by \f$ T(\vec{p},\vec{x}) \f$ in Algorithm 2 [Magnusson 2009]
337  * \return final step length
338  */
339  double
340  computeStepLengthMT (const Eigen::Matrix<double, 6, 1> &x,
341  Eigen::Matrix<double, 6, 1> &step_dir,
342  double step_init,
343  double step_max, double step_min,
344  double &score,
345  Eigen::Matrix<double, 6, 1> &score_gradient,
346  Eigen::Matrix<double, 6, 6> &hessian,
347  PointCloudSource &trans_cloud);
348 
349  /** \brief Update interval of possible step lengths for More-Thuente method, \f$ I \f$ in More-Thuente (1994)
350  * \note Updating Algorithm until some value satisfies \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$
351  * and Modified Updating Algorithm from then on [More, Thuente 1994].
352  * \param[in,out] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994)
353  * \param[in,out] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_l) \f$ for Update Algorithm and \f$ \phi(\alpha_l) \f$ for Modified Update Algorithm
354  * \param[in,out] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_l) \f$ for Update Algorithm and \f$ \phi'(\alpha_l) \f$ for Modified Update Algorithm
355  * \param[in,out] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994)
356  * \param[in,out] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_u) \f$ for Update Algorithm and \f$ \phi(\alpha_u) \f$ for Modified Update Algorithm
357  * \param[in,out] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_u) \f$ for Update Algorithm and \f$ \phi'(\alpha_u) \f$ for Modified Update Algorithm
358  * \param[in] a_t trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994)
359  * \param[in] f_t value at trial value, \f$ f_t \f$ in Moore-Thuente (1994), \f$ \psi(\alpha_t) \f$ for Update Algorithm and \f$ \phi(\alpha_t) \f$ for Modified Update Algorithm
360  * \param[in] g_t derivative at trial value, \f$ g_t \f$ in Moore-Thuente (1994), \f$ \psi'(\alpha_t) \f$ for Update Algorithm and \f$ \phi'(\alpha_t) \f$ for Modified Update Algorithm
361  * \return if interval converges
362  */
363  bool
364  updateIntervalMT (double &a_l, double &f_l, double &g_l,
365  double &a_u, double &f_u, double &g_u,
366  double a_t, double f_t, double g_t);
367 
368  /** \brief Select new trial value for More-Thuente method.
369  * \note Trial Value Selection [More, Thuente 1994], \f$ \psi(\alpha_k) \f$ is used for \f$ f_k \f$ and \f$ g_k \f$
370  * until some value satisfies the test \f$ \psi(\alpha_k) \leq 0 \f$ and \f$ \phi'(\alpha_k) \geq 0 \f$
371  * then \f$ \phi(\alpha_k) \f$ is used from then on.
372  * \note Interpolation Minimizer equations from Optimization Theory and Methods: Nonlinear Programming By Wenyu Sun, Ya-xiang Yuan (89-100).
373  * \param[in] a_l first endpoint of interval \f$ I \f$, \f$ \alpha_l \f$ in Moore-Thuente (1994)
374  * \param[in] f_l value at first endpoint, \f$ f_l \f$ in Moore-Thuente (1994)
375  * \param[in] g_l derivative at first endpoint, \f$ g_l \f$ in Moore-Thuente (1994)
376  * \param[in] a_u second endpoint of interval \f$ I \f$, \f$ \alpha_u \f$ in Moore-Thuente (1994)
377  * \param[in] f_u value at second endpoint, \f$ f_u \f$ in Moore-Thuente (1994)
378  * \param[in] g_u derivative at second endpoint, \f$ g_u \f$ in Moore-Thuente (1994)
379  * \param[in] a_t previous trial value, \f$ \alpha_t \f$ in Moore-Thuente (1994)
380  * \param[in] f_t value at previous trial value, \f$ f_t \f$ in Moore-Thuente (1994)
381  * \param[in] g_t derivative at previous trial value, \f$ g_t \f$ in Moore-Thuente (1994)
382  * \return new trial value
383  */
384  double
385  trialValueSelectionMT (double a_l, double f_l, double g_l,
386  double a_u, double f_u, double g_u,
387  double a_t, double f_t, double g_t);
388 
389  /** \brief Auxiliary function used to determine endpoints of More-Thuente interval.
390  * \note \f$ \psi(\alpha) \f$ in Equation 1.6 (Moore, Thuente 1994)
391  * \param[in] a the step length, \f$ \alpha \f$ in More-Thuente (1994)
392  * \param[in] f_a function value at step length a, \f$ \phi(\alpha) \f$ in More-Thuente (1994)
393  * \param[in] f_0 initial function value, \f$ \phi(0) \f$ in Moore-Thuente (1994)
394  * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994)
395  * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994]
396  * \return sufficient decrease value
397  */
398  inline double
399  auxilaryFunction_PsiMT (double a, double f_a, double f_0, double g_0, double mu = 1.e-4)
400  {
401  return (f_a - f_0 - mu * g_0 * a);
402  }
403 
404  /** \brief Auxiliary function derivative used to determine endpoints of More-Thuente interval.
405  * \note \f$ \psi'(\alpha) \f$, derivative of Equation 1.6 (Moore, Thuente 1994)
406  * \param[in] g_a function gradient at step length a, \f$ \phi'(\alpha) \f$ in More-Thuente (1994)
407  * \param[in] g_0 initial function gradiant, \f$ \phi'(0) \f$ in More-Thuente (1994)
408  * \param[in] mu the step length, constant \f$ \mu \f$ in Equation 1.1 [More, Thuente 1994]
409  * \return sufficient decrease derivative
410  */
411  inline double
412  auxilaryFunction_dPsiMT (double g_a, double g_0, double mu = 1.e-4)
413  {
414  return (g_a - mu * g_0);
415  }
416 
417  /** \brief The voxel grid generated from target cloud containing point means and covariances. */
418  TargetGrid target_cells_;
419 
420  //double fitness_epsilon_;
421 
422  /** \brief The side length of voxels. */
423  float resolution_;
424 
425  /** \brief The maximum step length. */
426  double step_size_;
427 
428  /** \brief The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009]. */
430 
431  /** \brief The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009]. */
433 
434  /** \brief The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009]. */
436 
437  /** \brief Precomputed Angular Gradient
438  *
439  * The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009].
440  */
442 
443  /** \brief Precomputed Angular Hessian
444  *
445  * The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009].
446  */
447  Eigen::Vector3d h_ang_a2_, h_ang_a3_,
453 
454  /** \brief The first order derivative of the transformation of a point w.r.t. the transform vector, \f$ J_E \f$ in Equation 6.18 [Magnusson 2009]. */
455  Eigen::Matrix<double, 3, 6> point_gradient_;
456 
457  /** \brief The second order derivative of the transformation of a point w.r.t. the transform vector, \f$ H_E \f$ in Equation 6.20 [Magnusson 2009]. */
458  Eigen::Matrix<double, 18, 6> point_hessian_;
459 
460  public:
461  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
462 
463  };
464 
465 }
466 
467 #include <pcl/registration/impl/ndt.hpp>
Eigen::Vector3d h_ang_f2_
Definition: ndt.h:447
double computeDerivatives(Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Matrix< double, 6, 6 > &hessian, PointCloudSource &trans_cloud, Eigen::Matrix< double, 6, 1 > &p, bool compute_hessian=true)
Compute derivatives of probability function w.r.t.
Definition: ndt.hpp:182
double auxilaryFunction_PsiMT(double a, double f_a, double f_0, double g_0, double mu=1.e-4)
Auxiliary function used to determine endpoints of More-Thuente interval.
Definition: ndt.h:399
Registration< PointSource, PointTarget >::PointCloudSource PointCloudSource
Definition: ndt.h:66
Eigen::Vector3d h_ang_c2_
Definition: ndt.h:447
double getOulierRatio() const
Get the point cloud outlier ratio.
Definition: ndt.h:157
float resolution_
The side length of voxels.
Definition: ndt.h:423
void setOulierRatio(double outlier_ratio)
Set/change the point cloud outlier ratio.
Definition: ndt.h:166
PointIndices::ConstPtr PointIndicesConstPtr
Definition: ndt.h:75
void filter(PointCloud &output, bool searchable=false)
Filter cloud and initializes voxel structure.
Eigen::Vector3d h_ang_d1_
Definition: ndt.h:447
TargetGrid target_cells_
The voxel grid generated from target cloud containing point means and covariances.
Definition: ndt.h:418
void setStepSize(double step_size)
Set/change the newton line search maximum step length.
Definition: ndt.h:148
Eigen::Vector3d j_ang_d_
Definition: ndt.h:441
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:44
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
Definition: registration.h:490
double step_size_
The maximum step length.
Definition: ndt.h:426
const Leaf * LeafConstPtr
Const pointer to VoxelGridCovariance leaf structure.
double updateDerivatives(Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Matrix< double, 6, 6 > &hessian, Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv, bool compute_hessian=true)
Compute individual point contirbutions to derivatives of probability function w.r.t.
Definition: ndt.hpp:357
static void convertTransform(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Affine3f &trans)
Convert 6 element transformation vector to affine transformation.
Definition: ndt.h:194
VoxelGridCovariance< PointTarget > TargetGrid
Typename of searchable voxel grid containing mean and covariance.
Definition: ndt.h:78
Eigen::Vector3d j_ang_a_
Precomputed Angular Gradient.
Definition: ndt.h:441
virtual ~NormalDistributionsTransform()
Empty destructor.
Definition: ndt.h:99
void init()
Initiate covariance voxel structure.
Definition: ndt.h:252
boost::shared_ptr< NormalDistributionsTransform< PointSource, PointTarget > > Ptr
Definition: ndt.h:89
double trans_probability_
The probability score of the transform applied to the input cloud, Equation 6.9 and 6...
Definition: ndt.h:435
PointCloudTarget::Ptr PointCloudTargetPtr
Definition: ndt.h:71
float getResolution() const
Get voxel grid resolution.
Definition: ndt.h:130
PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: ndt.h:72
boost::shared_ptr< const NormalDistributionsTransform< PointSource, PointTarget > > ConstPtr
Definition: ndt.h:90
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)
Select new trial value for More-Thuente method.
Definition: ndt.hpp:527
PointIndices::Ptr PointIndicesPtr
Definition: ndt.h:74
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
const TargetGrid * TargetGridConstPtr
Typename of const pointer to searchable voxel grid.
Definition: ndt.h:82
Eigen::Vector3d h_ang_a2_
Precomputed Angular Hessian.
Definition: ndt.h:447
Eigen::Vector3d h_ang_a3_
Definition: ndt.h:447
A 3D Normal Distribution Transform registration implementation for point cloud data.
Definition: ndt.h:62
Eigen::Vector3d h_ang_f1_
Definition: ndt.h:447
double computeStepLengthMT(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix< double, 6, 1 > &step_dir, double step_init, double step_max, double step_min, double &score, Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Matrix< double, 6, 6 > &hessian, PointCloudSource &trans_cloud)
Compute line search step length and update transform and probability derivatives using More-Thuente m...
Definition: ndt.hpp:610
void updateHessian(Eigen::Matrix< double, 6, 6 > &hessian, Eigen::Vector3d &x_trans, Eigen::Matrix3d &c_inv)
Compute individual point contirbutions to hessian of probability function w.r.t.
Definition: ndt.hpp:455
Eigen::Vector3d j_ang_b_
Definition: ndt.h:441
double getStepSize() const
Get the newton line search maximum step length.
Definition: ndt.h:139
Eigen::Vector3d j_ang_c_
Definition: ndt.h:441
void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
Definition: ndt.h:105
PointCloudTargetConstPtr target_
The input point cloud dataset target.
Definition: registration.h:501
Eigen::Vector3d j_ang_h_
Definition: ndt.h:441
double outlier_ratio_
The ratio of outliers of points w.r.t.
Definition: ndt.h:429
Eigen::Vector3d h_ang_e3_
Definition: ndt.h:447
Eigen::Vector3d h_ang_b3_
Definition: ndt.h:447
PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition: ndt.h:68
double gauss_d1_
The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009].
Definition: ndt.h:432
Eigen::Vector3d h_ang_d2_
Definition: ndt.h:447
void computeAngleDerivatives(Eigen::Matrix< double, 6, 1 > &p, bool compute_hessian=true)
Precompute anglular components of derivatives.
Definition: ndt.hpp:239
Registration represents the base registration class for general purpose, ICP-like methods...
Definition: registration.h:61
PointCloudSource::Ptr PointCloudSourcePtr
Definition: ndt.h:67
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)
Update interval of possible step lengths for More-Thuente method, in More-Thuente (1994) ...
Definition: ndt.hpp:486
Eigen::Vector3d j_ang_f_
Definition: ndt.h:441
boost::shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:22
Eigen::Vector3d j_ang_g_
Definition: ndt.h:441
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:66
void setResolution(float resolution)
Set/change the voxel grid resolution.
Definition: ndt.h:115
TargetGrid * TargetGridPtr
Typename of pointer to searchable voxel grid.
Definition: ndt.h:80
TargetGrid::LeafConstPtr TargetGridLeafConstPtr
Typename of const pointer to searchable voxel grid leaf.
Definition: ndt.h:84
NormalDistributionsTransform()
Constructor.
Definition: ndt.hpp:46
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:150
void computePointDerivatives(Eigen::Vector3d &x, bool compute_hessian=true)
Compute point derivatives.
Definition: ndt.hpp:316
Eigen::Matrix< double, 18, 6 > point_hessian_
The second order derivative of the transformation of a point w.r.t.
Definition: ndt.h:458
Eigen::Vector3d h_ang_d3_
Definition: ndt.h:447
Eigen::Vector3d h_ang_b2_
Definition: ndt.h:447
int getFinalNumIteration() const
Get the number of iterations required to calculate alignment.
Definition: ndt.h:184
Eigen::Matrix< double, 3, 6 > point_gradient_
The first order derivative of the transformation of a point w.r.t.
Definition: ndt.h:455
Eigen::Vector3d h_ang_e1_
Definition: ndt.h:447
Eigen::Vector3d h_ang_f3_
Definition: ndt.h:447
Eigen::Vector3d h_ang_c3_
Definition: ndt.h:447
static void convertTransform(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix4f &trans)
Convert 6 element transformation vector to transformation matrix.
Definition: ndt.h:207
Eigen::Vector3d h_ang_e2_
Definition: ndt.h:447
Registration< PointSource, PointTarget >::PointCloudTarget PointCloudTarget
Definition: ndt.h:70
double auxilaryFunction_dPsiMT(double g_a, double g_0, double mu=1.e-4)
Auxiliary function derivative used to determine endpoints of More-Thuente interval.
Definition: ndt.h:412
virtual void computeTransformation(PointCloudSource &output)
Estimate the transformation and returns the transformed source (input) as output. ...
Definition: ndt.h:238
double getTransformationProbability() const
Get the registration alignment probability.
Definition: ndt.h:175
boost::shared_ptr< ::pcl::PointIndices const > ConstPtr
Definition: PointIndices.h:23
Eigen::Vector3d j_ang_e_
Definition: ndt.h:441
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:223
void computeHessian(Eigen::Matrix< double, 6, 6 > &hessian, PointCloudSource &trans_cloud, Eigen::Matrix< double, 6, 1 > &p)
Compute hessian of probability function w.r.t.
Definition: ndt.hpp:403