Apollo  6.0
Open source self driving car software
Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget > Class Template Reference

#include <ndt_solver.h>

Collaboration diagram for apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >:
Collaboration graph

Public Types

typedef boost::shared_ptr< NormalDistributionsTransform< PointSource, PointTarget > > Ptr
 Typedef shared pointer. More...
 
typedef boost::shared_ptr< const NormalDistributionsTransform< PointSource, PointTarget > > ConstPtr
 

Public Member Functions

 NormalDistributionsTransform ()
 Constructor. More...
 
 ~NormalDistributionsTransform ()
 Destructor. More...
 
void SetInputTarget (const std::vector< Leaf > &cell_leaf, const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target. More...
 
void SetInputSource (const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target. More...
 
void SetResolution (float resolution)
 Set/change the voxel grid resolution. More...
 
float GetResolution () const
 Get voxel grid resolution. More...
 
double GetStepSize () const
 Get the newton line search maximum step length. More...
 
void SetStepSize (double step_size)
 Set/change the newton line search maximum step length. More...
 
double GetOulierRatio () const
 Get the point cloud outlier ratio. More...
 
void SetOulierRatio (double outlier_ratio)
 Set/change the point cloud outlier ratio. More...
 
double GetTransformationProbability () const
 Get the registration alignment probability. More...
 
int GetFinalNumIteration () const
 Get the number of iterations required to calculate alignment. More...
 
bool HasConverged () const
 Return the state of convergence after the last align run. More...
 
Eigen::Matrix4f GetFinalTransformation () const
 Get the final transformation matrix estimated by the registration method. More...
 
void SetMaximumIterations (int nr_iterations)
 Set the maximum number of iterations the internal optimization should run for. More...
 
void SetTransformationEpsilon (double epsilon)
 Set the transformation epsilon (maximum allowable difference between two consecutive transformations. More...
 
void GetGridPointCloud (pcl::PointCloud< pcl::PointXYZ > *cell_cloud)
 Obtain probability point cloud. More...
 
void SetLeftTopCorner (const Eigen::Vector3d &left_top_corner)
 Set left top corner of target point cloud. More...
 
double GetFitnessScore (double max_range=std::numeric_limits< double >::max())
 Obtain the Euclidean fitness score. More...
 
void Align (PointCloudSourcePtr output, const Eigen::Matrix4f &guess)
 Call the registration algorithm which estimates the transformation and returns the transformed source. More...
 

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. More...
 
static void ConvertTransform (const Eigen::Matrix< double, 6, 1 > &x, Eigen::Matrix4f *trans)
 Convert 6 element transformation vector to transformation matrix. More...
 

Protected Types

typedef pcl::PointCloud< PointSource > PointCloudSource
 Typename of source point. More...
 
typedef boost::shared_ptr< PointCloudSourcePointCloudSourcePtr
 
typedef boost::shared_ptr< const PointCloudSourcePointCloudSourceConstPtr
 
typedef pcl::PointCloud< PointTarget > PointCloudTarget
 Typename of target point. More...
 
typedef boost::shared_ptr< const PointCloudTargetPointCloudTargetConstPtr
 
typedef VoxelGridCovariance< PointTarget > TargetGrid
 Typename of searchable voxel grid containing mean and covariance. More...
 
typedef TargetGridTargetGridPtr
 
typedef const TargetGridTargetGridConstPtr
 
typedef LeafConstPtr TargetGridLeafConstPtr
 
typedef pcl::search::KdTree< PointTarget > KdTree
 Typename of KD-Tree. More...
 
typedef pcl::search::KdTree< PointTarget >::Ptr KdTreePtr
 

Protected Member Functions

void ComputeTransformation (PointCloudSourcePtr output)
 Estimate the transformation and returns the transformed source (input) as output. More...
 
void ComputeTransformation (PointCloudSourcePtr output, const Eigen::Matrix4f &guess)
 Estimate the transformation and returns the transformed source (input) as output. More...
 
double ComputeDerivatives (Eigen::Matrix< double, 6, 1 > *score_gradient, Eigen::Matrix< double, 6, 6 > *hessian, PointCloudSourcePtr trans_cloud, Eigen::Matrix< double, 6, 1 > *p, bool ComputeHessian=true)
 Compute derivatives of probability function w.r.t. the transformation vector. More...
 
double UpdateDerivatives (Eigen::Matrix< double, 6, 1 > *score_gradient, Eigen::Matrix< double, 6, 6 > *hessian, const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv, bool ComputeHessian=true)
 Compute individual point contributions to derivatives of probability function w.r.t. the transformation vector. More...
 
void ComputeAngleDerivatives (const Eigen::Matrix< double, 6, 1 > &p, bool ComputeHessian=true)
 Precompute anglular components of derivatives. More...
 
void ComputePointDerivatives (const Eigen::Vector3d &x, bool ComputeHessian=true)
 Compute point derivatives. More...
 
void ComputeHessian (Eigen::Matrix< double, 6, 6 > *hessian, const PointCloudSource &trans_cloud, Eigen::Matrix< double, 6, 1 > *p)
 Compute hessian of probability function w.r.t. the transformation vector. More...
 
void UpdateHessian (Eigen::Matrix< double, 6, 6 > *hessian, const Eigen::Vector3d &x_trans, const Eigen::Matrix3d &c_inv)
 Compute individual point contributions to hessian of probability function. More...
 
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, PointCloudSourcePtr trans_cloud)
 Compute line search step length and update transform and probability derivatives. More...
 
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. More...
 
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. More...
 
double AuxilaryFunctionPsimt (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. More...
 
double AuxilaryFunctionDpsimt (double g_a, double g_0, double mu=1.e-4)
 Auxiliary function derivative used to determine endpoints of More-Thuente interval. More...
 

Protected Attributes

PointCloudTargetConstPtr target_
 A pointer of input target point cloud. More...
 
KdTreePtr target_tree_
 A pointer to the spatial search object. More...
 
TargetGrid target_cells_
 The voxel grid generated from target cloud containing point means and covariances. More...
 
PointCloudSourceConstPtr input_
 A pointer of input source point cloud. More...
 
int nr_iterations_
 finnal iterations. More...
 
bool converged_
 
Eigen::Matrix4f previous_transformation_
 transformations. More...
 
Eigen::Matrix4f final_transformation_
 
Eigen::Matrix4f transformation_
 
int max_iterations_
 max iterations. More...
 
double transformation_epsilon_
 Transformation epsilon parameter. More...
 
float resolution_
 The side length of voxels. More...
 
double step_size_
 The maximum step length. More...
 
double outlier_ratio_
 The ratio of outliers of points w.r.t. a normal distribution, Equation 6.7 [Magnusson 2009]. More...
 
double gauss_d1_
 The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009]. More...
 
double gauss_d2_
 
double trans_probability_
 The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009]. More...
 
Eigen::Vector3d j_ang_a_
 The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009]. More...
 
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_
 
Eigen::Vector3d h_ang_a2_
 The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009]. More...
 
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::Matrix< double, 3, 6 > point_gradient_
 The first order derivative of the transformation of a point w.r.t. the transform vector, Equation 6.18 [Magnusson 2009]. More...
 
Eigen::Matrix< double, 18, 6 > point_hessian_
 The second order derivative of the transformation of a point w.r.t. the transform vector, Equation 6.20 [Magnusson 2009]. More...
 

Member Typedef Documentation

◆ ConstPtr

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ConstPtr

◆ KdTree

template<typename PointSource, typename PointTarget>
typedef pcl::search::KdTree<PointTarget> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::KdTree
protected

Typename of KD-Tree.

◆ KdTreePtr

template<typename PointSource, typename PointTarget>
typedef pcl::search::KdTree<PointTarget>::Ptr apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::KdTreePtr
protected

◆ PointCloudSource

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSource
protected

Typename of source point.

◆ PointCloudSourceConstPtr

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr<const PointCloudSource> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourceConstPtr
protected

◆ PointCloudSourcePtr

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr<PointCloudSource> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourcePtr
protected

◆ PointCloudTarget

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTarget
protected

Typename of target point.

◆ PointCloudTargetConstPtr

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr<const PointCloudTarget> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTargetConstPtr
protected

◆ Ptr

template<typename PointSource, typename PointTarget>
typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::Ptr

Typedef shared pointer.

◆ TargetGrid

template<typename PointSource, typename PointTarget>
typedef VoxelGridCovariance<PointTarget> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::TargetGrid
protected

Typename of searchable voxel grid containing mean and covariance.

◆ TargetGridConstPtr

template<typename PointSource, typename PointTarget>
typedef const TargetGrid* apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridConstPtr
protected

◆ TargetGridLeafConstPtr

template<typename PointSource, typename PointTarget>
typedef LeafConstPtr apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridLeafConstPtr
protected

◆ TargetGridPtr

template<typename PointSource, typename PointTarget>
typedef TargetGrid* apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridPtr
protected

Constructor & Destructor Documentation

◆ NormalDistributionsTransform()

template<typename PointSource, typename PointTarget>
apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform ( )

Constructor.

◆ ~NormalDistributionsTransform()

template<typename PointSource, typename PointTarget>
apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::~NormalDistributionsTransform ( )
inline

Destructor.

Member Function Documentation

◆ Align()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::Align ( PointCloudSourcePtr  output,
const Eigen::Matrix4f &  guess 
)

Call the registration algorithm which estimates the transformation and returns the transformed source.

◆ AuxilaryFunctionDpsimt()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::AuxilaryFunctionDpsimt ( double  g_a,
double  g_0,
double  mu = 1.e-4 
)
inlineprotected

Auxiliary function derivative used to determine endpoints of More-Thuente interval.

◆ AuxilaryFunctionPsimt()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::AuxilaryFunctionPsimt ( double  a,
double  f_a,
double  f_0,
double  g_0,
double  mu = 1.e-4 
)
inlineprotected

Auxiliary function used to determine endpoints of More-Thuente interval.

◆ ComputeAngleDerivatives()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputeAngleDerivatives ( const Eigen::Matrix< double, 6, 1 > &  p,
bool  ComputeHessian = true 
)
protected

Precompute anglular components of derivatives.

◆ ComputeDerivatives()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputeDerivatives ( Eigen::Matrix< double, 6, 1 > *  score_gradient,
Eigen::Matrix< double, 6, 6 > *  hessian,
PointCloudSourcePtr  trans_cloud,
Eigen::Matrix< double, 6, 1 > *  p,
bool  ComputeHessian = true 
)
protected

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

◆ ComputeHessian()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputeHessian ( Eigen::Matrix< double, 6, 6 > *  hessian,
const PointCloudSource trans_cloud,
Eigen::Matrix< double, 6, 1 > *  p 
)
protected

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

◆ ComputePointDerivatives()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputePointDerivatives ( const Eigen::Vector3d &  x,
bool  ComputeHessian = true 
)
protected

Compute point derivatives.

◆ ComputeStepLengthMt()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::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,
PointCloudSourcePtr  trans_cloud 
)
protected

Compute line search step length and update transform and probability derivatives.

◆ ComputeTransformation() [1/2]

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputeTransformation ( PointCloudSourcePtr  output)
inlineprotected

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

◆ ComputeTransformation() [2/2]

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ComputeTransformation ( PointCloudSourcePtr  output,
const Eigen::Matrix4f &  guess 
)
protected

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

◆ ConvertTransform() [1/2]

template<typename PointSource, typename PointTarget>
static void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ConvertTransform ( const Eigen::Matrix< double, 6, 1 > &  x,
Eigen::Affine3f *  trans 
)
inlinestatic

Convert 6 element transformation vector to affine transformation.

◆ ConvertTransform() [2/2]

template<typename PointSource, typename PointTarget>
static void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ConvertTransform ( const Eigen::Matrix< double, 6, 1 > &  x,
Eigen::Matrix4f *  trans 
)
inlinestatic

Convert 6 element transformation vector to transformation matrix.

◆ GetFinalNumIteration()

template<typename PointSource, typename PointTarget>
int apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetFinalNumIteration ( ) const
inline

Get the number of iterations required to calculate alignment.

◆ GetFinalTransformation()

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetFinalTransformation ( ) const
inline

Get the final transformation matrix estimated by the registration method.

◆ GetFitnessScore()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetFitnessScore ( double  max_range = std::numeric_limits< double >::max())

Obtain the Euclidean fitness score.

◆ GetGridPointCloud()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetGridPointCloud ( pcl::PointCloud< pcl::PointXYZ > *  cell_cloud)
inline

Obtain probability point cloud.

◆ GetOulierRatio()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetOulierRatio ( ) const
inline

Get the point cloud outlier ratio.

◆ GetResolution()

template<typename PointSource, typename PointTarget>
float apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetResolution ( ) const
inline

Get voxel grid resolution.

◆ GetStepSize()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetStepSize ( ) const
inline

Get the newton line search maximum step length.

Returns
maximum step length

◆ GetTransformationProbability()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetTransformationProbability ( ) const
inline

Get the registration alignment probability.

◆ HasConverged()

template<typename PointSource, typename PointTarget>
bool apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::HasConverged ( ) const
inline

Return the state of convergence after the last align run.

◆ SetInputSource()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetInputSource ( const PointCloudTargetConstPtr cloud)
inline

Provide a pointer to the input target.

◆ SetInputTarget()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetInputTarget ( const std::vector< Leaf > &  cell_leaf,
const PointCloudTargetConstPtr cloud 
)
inline

Provide a pointer to the input target.

◆ SetLeftTopCorner()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetLeftTopCorner ( const Eigen::Vector3d &  left_top_corner)
inline

Set left top corner of target point cloud.

◆ SetMaximumIterations()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetMaximumIterations ( int  nr_iterations)
inline

Set the maximum number of iterations the internal optimization should run for.

◆ SetOulierRatio()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetOulierRatio ( double  outlier_ratio)
inline

Set/change the point cloud outlier ratio.

◆ SetResolution()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetResolution ( float  resolution)
inline

Set/change the voxel grid resolution.

◆ SetStepSize()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetStepSize ( double  step_size)
inline

Set/change the newton line search maximum step length.

Parameters
[in]step_sizemaximum step length

◆ SetTransformationEpsilon()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::SetTransformationEpsilon ( double  epsilon)
inline

Set the transformation epsilon (maximum allowable difference between two consecutive transformations.

◆ TrialValueSelectionMt()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::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.

◆ UpdateDerivatives()

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::UpdateDerivatives ( Eigen::Matrix< double, 6, 1 > *  score_gradient,
Eigen::Matrix< double, 6, 6 > *  hessian,
const Eigen::Vector3d &  x_trans,
const Eigen::Matrix3d &  c_inv,
bool  ComputeHessian = true 
)
protected

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

◆ UpdateHessian()

template<typename PointSource, typename PointTarget>
void apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::UpdateHessian ( Eigen::Matrix< double, 6, 6 > *  hessian,
const Eigen::Vector3d &  x_trans,
const Eigen::Matrix3d &  c_inv 
)
protected

Compute individual point contributions to hessian of probability function.

◆ UpdateIntervalMt()

template<typename PointSource, typename PointTarget>
bool apollo::localization::ndt::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.

Member Data Documentation

◆ converged_

template<typename PointSource, typename PointTarget>
bool apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::converged_
protected

◆ final_transformation_

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::final_transformation_
protected

◆ gauss_d1_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_
protected

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

◆ gauss_d2_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_
protected

◆ h_ang_a2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_
protected

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

◆ h_ang_a3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_
protected

◆ h_ang_b2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_
protected

◆ h_ang_b3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_
protected

◆ h_ang_c2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_
protected

◆ h_ang_c3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_
protected

◆ h_ang_d1_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_
protected

◆ h_ang_d2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_
protected

◆ h_ang_d3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_
protected

◆ h_ang_e1_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_
protected

◆ h_ang_e2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_
protected

◆ h_ang_e3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_
protected

◆ h_ang_f1_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_
protected

◆ h_ang_f2_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_
protected

◆ h_ang_f3_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_
protected

◆ input_

template<typename PointSource, typename PointTarget>
PointCloudSourceConstPtr apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::input_
protected

A pointer of input source point cloud.

◆ j_ang_a_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_
protected

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

◆ j_ang_b_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_
protected

◆ j_ang_c_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_
protected

◆ j_ang_d_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_
protected

◆ j_ang_e_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_
protected

◆ j_ang_f_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_
protected

◆ j_ang_g_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_
protected

◆ j_ang_h_

template<typename PointSource, typename PointTarget>
Eigen::Vector3d apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_
protected

◆ max_iterations_

template<typename PointSource, typename PointTarget>
int apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::max_iterations_
protected

max iterations.

◆ nr_iterations_

template<typename PointSource, typename PointTarget>
int apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::nr_iterations_
protected

finnal iterations.

◆ outlier_ratio_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_
protected

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

◆ point_gradient_

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double, 3, 6> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_
protected

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

◆ point_hessian_

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double, 18, 6> apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_
protected

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

◆ previous_transformation_

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::previous_transformation_
protected

transformations.

◆ resolution_

template<typename PointSource, typename PointTarget>
float apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::resolution_
protected

The side length of voxels.

◆ step_size_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::step_size_
protected

The maximum step length.

◆ target_

template<typename PointSource, typename PointTarget>
PointCloudTargetConstPtr apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::target_
protected

A pointer of input target point cloud.

◆ target_cells_

template<typename PointSource, typename PointTarget>
TargetGrid apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_
protected

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

◆ target_tree_

template<typename PointSource, typename PointTarget>
KdTreePtr apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::target_tree_
protected

A pointer to the spatial search object.

◆ trans_probability_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::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].

◆ transformation_

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::transformation_
protected

◆ transformation_epsilon_

template<typename PointSource, typename PointTarget>
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::transformation_epsilon_
protected

Transformation epsilon parameter.


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