Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::NormalDistributionsTransform< PointSource, PointTarget > Class Template Reference

A 3D Normal Distribution Transform registration implementation for point cloud data. More...

#include <ndt.h>

Inheritance diagram for pcl::NormalDistributionsTransform< PointSource, PointTarget >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
NormalDistributionsTransform
< PointSource, PointTarget > > 
ConstPtr
typedef boost::shared_ptr
< NormalDistributionsTransform
< PointSource, PointTarget > > 
Ptr

Public Member Functions

int getFinalNumIteration () const
 Get the number of iterations required to calculate alignment.
double getOulierRatio () const
 Get the point cloud outlier ratio.
float getResolution () const
 Get voxel grid resolution.
double getStepSize () const
 Get the newton line search maximum step length.
double getTransformationProbability () const
 Get the registration alignment probability.
 NormalDistributionsTransform ()
 Constructor. Sets outlier_ratio_ to 0.35, step_size_ to 0.05 and resolution_ to 1.0.
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 to).
void setOulierRatio (double outlier_ratio)
 Set/change the point cloud outlier ratio.
void setResolution (float resolution)
 Set/change the voxel grid resolution.
void setStepSize (double step_size)
 Set/change the newton line search maximum step length.
virtual ~NormalDistributionsTransform ()
 Empty destructor.

Static Public Member Functions

static void convertTransform (const Eigen::Matrix< double, 6, 1 > &x, Eigen::Affine3f &trans)
 Convert 6 element transformation vector to affine transformation.
static void convertTransform (const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix4f &trans)
 Convert 6 element transformation vector to transformation matrix.

Protected Types

typedef Registration
< PointSource, PointTarget >
::PointCloudSource 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef Registration
< PointSource, PointTarget >
::PointCloudTarget 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr
typedef VoxelGridCovariance
< PointTarget > 
TargetGrid
 Typename of searchable voxel grid containing mean and covariance.
typedef const TargetGridTargetGridConstPtr
 Typename of const pointer to searchable voxel grid.
typedef TargetGrid::LeafConstPtr TargetGridLeafConstPtr
 Typename of const pointer to searchable voxel grid leaf.
typedef TargetGridTargetGridPtr
 Typename of pointer to searchable voxel grid.

Protected Member Functions

double auxilaryFunction_dPsiMT (double g_a, double g_0, double mu=1.e-4)
 Auxilary function derivative used to determin endpoints of More-Thuente interval.
double auxilaryFunction_PsiMT (double a, double f_a, double f_0, double g_0, double mu=1.e-4)
 Auxilary function used to determin endpoints of More-Thuente interval.
void computeAngleDerivatives (Eigen::Matrix< double, 6, 1 > &p, bool compute_hessian=true)
 Precompute anglular components of derivatives.
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. the transformation vector.
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. the transformation vector.
void computePointDerivatives (Eigen::Vector3d &x, bool compute_hessian=true)
 Compute point derivatives.
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 method.
virtual void computeTransformation (PointCloudSource &output)
 Estimate the transformation and returns the transformed source (input) as output.
virtual void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
 Estimate the transformation and returns the transformed source (input) as output.
void init ()
 Initiate covariance voxel structure.
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.
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. the transformation vector.
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. the transformation vector.
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, $ I $ in More-Thuente (1994)

Protected Attributes

double gauss_d1_
 The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009].
double gauss_d2_
Eigen::Vector3d h_ang_a2_
 Precomputed Angular Hessian.
Eigen::Vector3d h_ang_a3_
Eigen::Vector3d h_ang_b2_
Eigen::Vector3d h_ang_b3_
Eigen::Vector3d h_ang_c2_
Eigen::Vector3d h_ang_c3_
Eigen::Vector3d h_ang_d1_
Eigen::Vector3d h_ang_d2_
Eigen::Vector3d h_ang_d3_
Eigen::Vector3d h_ang_e1_
Eigen::Vector3d h_ang_e2_
Eigen::Vector3d h_ang_e3_
Eigen::Vector3d h_ang_f1_
Eigen::Vector3d h_ang_f2_
Eigen::Vector3d h_ang_f3_
Eigen::Vector3d j_ang_a_
 Precomputed Angular Gradient.
Eigen::Vector3d j_ang_b_
Eigen::Vector3d j_ang_c_
Eigen::Vector3d j_ang_d_
Eigen::Vector3d j_ang_e_
Eigen::Vector3d j_ang_f_
Eigen::Vector3d j_ang_g_
Eigen::Vector3d j_ang_h_
double outlier_ratio_
 The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009].
Eigen::Matrix< double, 3, 6 > point_gradient_
 The first order derivative of the transformation of a point w.r.t. the transform vector, $ J_E $ in Equation 6.18 [Magnusson 2009].
Eigen::Matrix< double, 18, 6 > point_hessian_
 The second order derivative of the transformation of a point w.r.t. the transform vector, $ H_E $ in Equation 6.20 [Magnusson 2009].
float resolution_
 The side length of voxels.
double step_size_
 The maximum step length.
TargetGrid target_cells_
 The voxel grid generated from target cloud containing point means and covariances.
double trans_probability_
 The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009].

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::NormalDistributionsTransform< PointSource, PointTarget >

A 3D Normal Distribution Transform registration implementation for point cloud data.

Note:
For more information please see Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform — an Efficient Representation for Registration, Surface Analysis, and Loop Detection. PhD thesis, Orebro University. Orebro Studies in Technology 36., More, J., and Thuente, D. (1994). Line Search Algorithm with Guaranteed Sufficient Decrease In ACM Transactions on Mathematical Software. and Sun, W. and Yuan, Y, (2006) Optimization Theory and Methods: Nonlinear Programming. 89-100
Math refactored by Todor Stoyanov.
Author:
Brian Okorn (Space and Naval Warfare Systems Center Pacific)

Definition at line 63 of file ndt.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > pcl::NormalDistributionsTransform< PointSource, PointTarget >::ConstPtr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 91 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSource [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 67 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourceConstPtr [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 69 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourcePtr [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 68 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTarget [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 71 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTargetConstPtr [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 73 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTargetPtr [protected]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 72 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointIndices::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointIndicesConstPtr [protected]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 76 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef PointIndices::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointIndicesPtr [protected]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 75 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > pcl::NormalDistributionsTransform< PointSource, PointTarget >::Ptr

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 90 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef VoxelGridCovariance<PointTarget> pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGrid [protected]

Typename of searchable voxel grid containing mean and covariance.

Definition at line 79 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef const TargetGrid* pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridConstPtr [protected]

Typename of const pointer to searchable voxel grid.

Definition at line 83 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef TargetGrid::LeafConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridLeafConstPtr [protected]

Typename of const pointer to searchable voxel grid leaf.

Definition at line 85 of file ndt.h.

template<typename PointSource, typename PointTarget>
typedef TargetGrid* pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridPtr [protected]

Typename of pointer to searchable voxel grid.

Definition at line 81 of file ndt.h.


Constructor & Destructor Documentation

template<typename PointSource , typename PointTarget >
pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform ( )

Constructor. Sets outlier_ratio_ to 0.35, step_size_ to 0.05 and resolution_ to 1.0.

Definition at line 46 of file ndt.hpp.

template<typename PointSource, typename PointTarget>
virtual pcl::NormalDistributionsTransform< PointSource, PointTarget >::~NormalDistributionsTransform ( ) [inline, virtual]

Empty destructor.

Definition at line 100 of file ndt.h.


Member Function Documentation

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::auxilaryFunction_dPsiMT ( double  g_a,
double  g_0,
double  mu = 1.e-4 
) [inline, protected]

Auxilary function derivative used to determin endpoints of More-Thuente interval.

Note:
$ \psi'(\alpha) $, derivative of Equation 1.6 (Moore, Thuente 1994)
Parameters:
[in]g_afunction gradient at step length a, $ \phi'(\alpha) $ in More-Thuente (1994)
[in]g_0initial function gradiant, $ \phi'(0) $ in More-Thuente (1994)
[in]muthe step length, constant $ \mu $ in Equation 1.1 [More, Thuente 1994]
Returns:
sufficent decrease derivative

Definition at line 412 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::auxilaryFunction_PsiMT ( double  a,
double  f_a,
double  f_0,
double  g_0,
double  mu = 1.e-4 
) [inline, protected]

Auxilary function used to determin endpoints of More-Thuente interval.

Note:
$ \psi(\alpha) $ in Equation 1.6 (Moore, Thuente 1994)
Parameters:
[in]athe step length, $ \alpha $ in More-Thuente (1994)
[in]f_afunction value at step length a, $ \phi(\alpha) $ in More-Thuente (1994)
[in]f_0initial function value, $ \phi(0) $ in Moore-Thuente (1994)
[in]g_0initial function gradiant, $ \phi'(0) $ in More-Thuente (1994)
[in]muthe step length, constant $ \mu $ in Equation 1.1 [More, Thuente 1994]
Returns:
sufficent decrease value

Definition at line 399 of file ndt.h.

template<typename PointSource , typename PointTarget >
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives ( Eigen::Matrix< double, 6, 1 > &  p,
bool  compute_hessian = true 
) [protected]

Precompute anglular components of derivatives.

Note:
Equation 6.19 and 6.21 [Magnusson 2009].
Parameters:
[in]pthe current transform vector
[in]compute_hessianflag to calculate hessian, unnessissary for step calculation.

Definition at line 233 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::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 
) [protected]

Compute derivatives of probability function w.r.t. the transformation vector.

Note:
Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
Parameters:
[out]score_gradientthe gradient vector of the probability function w.r.t. the transformation vector
[out]hessianthe hessian matrix of the probability function w.r.t. the transformation vector
[in]trans_cloudtransformed point cloud
[in]pthe current transform vector
[in]compute_hessianflag to calculate hessian, unnessissary for step calculation.

Definition at line 176 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian ( Eigen::Matrix< double, 6, 6 > &  hessian,
PointCloudSource trans_cloud,
Eigen::Matrix< double, 6, 1 > &  p 
) [protected]

Compute hessian of probability function w.r.t. the transformation vector.

Note:
Equation 6.13 [Magnusson 2009].
Parameters:
[out]hessianthe hessian matrix of the probability function w.r.t. the transformation vector
[in]trans_cloudtransformed point cloud
[in]pthe current transform vector

Definition at line 397 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives ( Eigen::Vector3d &  x,
bool  compute_hessian = true 
) [protected]

Compute point derivatives.

Note:
Equation 6.18-21 [Magnusson 2009].
Parameters:
[in]xpoint from the input cloud
[in]compute_hessianflag to calculate hessian, unnessissary for step calculation.

Definition at line 310 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::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 
) [protected]

Compute line search step length and update transform and probability derivatives using More-Thuente method.

Note:
Search Algorithm [More, Thuente 1994]
Parameters:
[in]xinitial transformation vector, $ x $ in Equation 1.3 (Moore, Thuente 1994) and $ \vec{p} $ in Algorithm 2 [Magnusson 2009]
[in]step_dirdescent direction, $ p $ in Equation 1.3 (Moore, Thuente 1994) and $ \delta \vec{p} $ normalized in Algorithm 2 [Magnusson 2009]
[in]step_initinitial step length estimate, $ \alpha_0 $ in Moore-Thuente (1994) and the noramal of $ \delta \vec{p} $ in Algorithm 2 [Magnusson 2009]
[in]step_maxmaximum step length, $ \alpha_max $ in Moore-Thuente (1994)
[in]step_minminimum step length, $ \alpha_min $ in Moore-Thuente (1994)
[out]scorefinal score function value, $ f(x + \alpha p) $ in Equation 1.3 (Moore, Thuente 1994) and $ score $ in Algorithm 2 [Magnusson 2009]
[in,out]score_gradientgradient of score function w.r.t. transformation vector, $ f'(x + \alpha p) $ in Moore-Thuente (1994) and $ \vec{g} $ in Algorithm 2 [Magnusson 2009]
[out]hessianhessian of score function w.r.t. transformation vector, $ f''(x + \alpha p) $ in Moore-Thuente (1994) and $ H $ in Algorithm 2 [Magnusson 2009]
[in,out]trans_cloudtransformed point cloud, $ X $ transformed by $ T(\vec{p},\vec{x}) $ in Algorithm 2 [Magnusson 2009]
Returns:
final step length

Definition at line 604 of file ndt.hpp.

template<typename PointSource, typename PointTarget>
virtual void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation ( PointCloudSource output) [inline, protected, virtual]

Estimate the transformation and returns the transformed source (input) as output.

Parameters:
[out]outputthe resultant input transfomed point cloud dataset

Definition at line 238 of file ndt.h.

template<typename PointSource , typename PointTarget >
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation ( PointCloudSource output,
const Eigen::Matrix4f &  guess 
) [protected, virtual]

Estimate the transformation and returns the transformed source (input) as output.

Parameters:
[out]outputthe resultant input transfomed point cloud dataset
[in]guessthe initial gross estimation of the transformation

Definition at line 77 of file ndt.hpp.

template<typename PointSource, typename PointTarget>
static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform ( const Eigen::Matrix< double, 6, 1 > &  x,
Eigen::Affine3f &  trans 
) [inline, static]

Convert 6 element transformation vector to affine transformation.

Parameters:
[in]xtransformation vector of the form [x, y, z, roll, pitch, yaw]
[out]transaffine transform corresponding to given transfomation vector

Definition at line 195 of file ndt.h.

template<typename PointSource, typename PointTarget>
static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform ( const Eigen::Matrix< double, 6, 1 > &  x,
Eigen::Matrix4f &  trans 
) [inline, static]

Convert 6 element transformation vector to transformation matrix.

Parameters:
[in]xtransformation vector of the form [x, y, z, roll, pitch, yaw]
[out]trans4x4 transformation matrix corresponding to given transfomation vector

Definition at line 208 of file ndt.h.

template<typename PointSource, typename PointTarget>
int pcl::NormalDistributionsTransform< PointSource, PointTarget >::getFinalNumIteration ( ) const [inline]

Get the number of iterations required to calculate alignment.

Returns:
final number of iterations

Definition at line 185 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getOulierRatio ( ) const [inline]

Get the point cloud outlier ratio.

Returns:
outlier ratio

Definition at line 158 of file ndt.h.

template<typename PointSource, typename PointTarget>
float pcl::NormalDistributionsTransform< PointSource, PointTarget >::getResolution ( ) const [inline]

Get voxel grid resolution.

Returns:
side length of voxels

Definition at line 131 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getStepSize ( ) const [inline]

Get the newton line search maximum step length.

Returns:
maximum step length

Definition at line 140 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getTransformationProbability ( ) const [inline]

Get the registration alignment probability.

Returns:
transformation probability

Definition at line 176 of file ndt.h.

template<typename PointSource, typename PointTarget>
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::init ( ) [inline, protected]

Initiate covariance voxel structure.

Definition at line 252 of file ndt.h.

template<typename PointSource, typename PointTarget>
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr cloud) [inline]

Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to).

Parameters:
[in]cloudthe input point cloud target

Definition at line 106 of file ndt.h.

template<typename PointSource, typename PointTarget>
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setOulierRatio ( double  outlier_ratio) [inline]

Set/change the point cloud outlier ratio.

Parameters:
[in]outlier_ratiooutlier ratio

Definition at line 167 of file ndt.h.

template<typename PointSource, typename PointTarget>
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setResolution ( float  resolution) [inline]

Set/change the voxel grid resolution.

Parameters:
[in]resolutionside length of voxels

Definition at line 116 of file ndt.h.

template<typename PointSource, typename PointTarget>
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setStepSize ( double  step_size) [inline]

Set/change the newton line search maximum step length.

Parameters:
[in]step_sizemaximum step length

Definition at line 149 of file ndt.h.

template<typename PointSource , typename PointTarget >
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::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 
) [protected]

Select new trial value for More-Thuente method.

Note:
Trial Value Selection [More, Thuente 1994], $ \psi(\alpha_k) $ is used for $ f_k $ and $ g_k $ until some value satifies the test $ \psi(\alpha_k) \leq 0 $ and $ \phi'(\alpha_k) \geq 0 $ then $ \phi(\alpha_k) $ is used from then on.
Interpolation Minimizer equations from Optimization Theory and Methods: Nonlinear Programming By Wenyu Sun, Ya-xiang Yuan (89-100).< >
Parameters:
[in]a_lfirst endpoint of interval $ I $, $ \alpha_l $ in Moore-Thuente (1994)
[in]f_lvalue at first endpoint, $ f_l $ in Moore-Thuente (1994)
[in]g_lderivative at first endpoint, $ g_l $ in Moore-Thuente (1994)
[in]a_usecond endpoint of interval $ I $, $ \alpha_u $ in Moore-Thuente (1994)
[in]f_uvalue at second endpoint, $ f_u $ in Moore-Thuente (1994)
[in]g_uderivative at second endpoint, $ g_u $ in Moore-Thuente (1994)
[in]a_tprevious trial value, $ \alpha_t $ in Moore-Thuente (1994)
[in]f_tvalue at previous trial value, $ f_t $ in Moore-Thuente (1994)
[in]g_tderivative at previous trial value, $ g_t $ in Moore-Thuente (1994)
Returns:
new trial value

Definition at line 521 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::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 
) [protected]

Compute individual point contirbutions to derivatives of probability function w.r.t. the transformation vector.

Note:
Equation 6.10, 6.12 and 6.13 [Magnusson 2009].
Parameters:
[in,out]score_gradientthe gradient vector of the probability function w.r.t. the transformation vector
[in,out]hessianthe hessian matrix of the probability function w.r.t. the transformation vector
[in]x_transtransformed point minus mean of occupied covariance voxel
[in]c_invcovariance of occupied covariance voxel
[in]compute_hessianflag to calculate hessian, unnessissary for step calculation.

Definition at line 351 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian ( Eigen::Matrix< double, 6, 6 > &  hessian,
Eigen::Vector3d &  x_trans,
Eigen::Matrix3d &  c_inv 
) [protected]

Compute individual point contirbutions to hessian of probability function w.r.t. the transformation vector.

Note:
Equation 6.13 [Magnusson 2009].
Parameters:
[in,out]hessianthe hessian matrix of the probability function w.r.t. the transformation vector
[in]x_transtransformed point minus mean of occupied covariance voxel
[in]c_invcovariance of occupied covariance voxel

Definition at line 449 of file ndt.hpp.

template<typename PointSource , typename PointTarget >
bool pcl::NormalDistributionsTransform< PointSource, PointTarget >::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 
) [protected]

Update interval of possible step lengths for More-Thuente method, $ I $ in More-Thuente (1994)

Note:
Updating Algorithm until some value satifies $ \psi(\alpha_k) \leq 0 $ and $ \phi'(\alpha_k) \geq 0 $ and Modified Updating Algorithm from then on [More, Thuente 1994].
Parameters:
[in,out]a_lfirst endpoint of interval $ I $, $ \alpha_l $ in Moore-Thuente (1994)
[in,out]f_lvalue at first endpoint, $ f_l $ in Moore-Thuente (1994), $ \psi(\alpha_l) $ for Update Algorithm and $ \phi(\alpha_l) $ for Modified Update Algorithm
[in,out]g_lderivative at first endpoint, $ g_l $ in Moore-Thuente (1994), $ \psi'(\alpha_l) $ for Update Algorithm and $ \phi'(\alpha_l) $ for Modified Update Algorithm
[in,out]a_usecond endpoint of interval $ I $, $ \alpha_u $ in Moore-Thuente (1994)
[in,out]f_uvalue at second endpoint, $ f_u $ in Moore-Thuente (1994), $ \psi(\alpha_u) $ for Update Algorithm and $ \phi(\alpha_u) $ for Modified Update Algorithm
[in,out]g_uderivative at second endpoint, $ g_u $ in Moore-Thuente (1994), $ \psi'(\alpha_u) $ for Update Algorithm and $ \phi'(\alpha_u) $ for Modified Update Algorithm
[in]a_ttrial value, $ \alpha_t $ in Moore-Thuente (1994)
[in]f_tvalue at trial value, $ f_t $ in Moore-Thuente (1994), $ \psi(\alpha_t) $ for Update Algorithm and $ \phi(\alpha_t) $ for Modified Update Algorithm
[in]g_tderivative at trial value, $ g_t $ in Moore-Thuente (1994), $ \psi'(\alpha_t) $ for Update Algorithm and $ \phi'(\alpha_t) $ for Modified Update Algorithm
Returns:
if interval converges

Definition at line 480 of file ndt.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_ [protected]

The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009].

Definition at line 432 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_ [protected]

Definition at line 432 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_ [protected]

Precomputed Angular Hessian.

The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009].

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_ [protected]

Definition at line 447 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_ [protected]

Precomputed Angular Gradient.

The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009].

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_ [protected]

Definition at line 441 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_ [protected]

The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009].

Definition at line 429 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double, 3, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_ [protected]

The first order derivative of the transformation of a point w.r.t. the transform vector, $ J_E $ in Equation 6.18 [Magnusson 2009].

Definition at line 455 of file ndt.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double, 18, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_ [protected]

The second order derivative of the transformation of a point w.r.t. the transform vector, $ H_E $ in Equation 6.20 [Magnusson 2009].

Definition at line 458 of file ndt.h.

template<typename PointSource, typename PointTarget>
float pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_ [protected]

The side length of voxels.

Definition at line 423 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_ [protected]

The maximum step length.

Definition at line 426 of file ndt.h.

template<typename PointSource, typename PointTarget>
TargetGrid pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_ [protected]

The voxel grid generated from target cloud containing point means and covariances.

Definition at line 418 of file ndt.h.

template<typename PointSource, typename PointTarget>
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::trans_probability_ [protected]

The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009].

Definition at line 435 of file ndt.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:28