Apollo 10.0
自动驾驶开放平台
apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget > 模板类 参考

#include <ndt_solver.h>

apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget > 的协作图:

Public 类型

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

Public 成员函数

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

静态 Public 成员函数

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 类型

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

Protected 成员函数

void ComputeTransformation (PointCloudSourcePtr output)
 Estimate the transformation and returns the transformed source (input) as output.
 
void ComputeTransformation (PointCloudSourcePtr output, const Eigen::Matrix4f &guess)
 Estimate the transformation and returns the transformed source (input) as output.
 
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.
 
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.
 
void ComputeAngleDerivatives (const Eigen::Matrix< double, 6, 1 > &p, bool ComputeHessian=true)
 Precompute anglular components of derivatives.
 
void ComputePointDerivatives (const Eigen::Vector3d &x, bool ComputeHessian=true)
 Compute point derivatives.
 
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.
 
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.
 
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.
 
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.
 
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 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.
 
double AuxilaryFunctionDpsimt (double g_a, double g_0, double mu=1.e-4)
 Auxiliary function derivative used to determine endpoints of More-Thuente interval.
 

Protected 属性

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

详细描述

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

在文件 ndt_solver.h73 行定义.

成员类型定义说明

◆ ConstPtr

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

在文件 ndt_solver.h101 行定义.

◆ KdTree

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

Typename of KD-Tree.

在文件 ndt_solver.h91 行定义.

◆ KdTreePtr

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

在文件 ndt_solver.h92 行定义.

◆ PointCloudSource

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

Typename of source point.

在文件 ndt_solver.h76 行定义.

◆ PointCloudSourceConstPtr

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

在文件 ndt_solver.h78 行定义.

◆ PointCloudSourcePtr

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

在文件 ndt_solver.h77 行定义.

◆ PointCloudTarget

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

Typename of target point.

在文件 ndt_solver.h81 行定义.

◆ PointCloudTargetConstPtr

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

在文件 ndt_solver.h82 行定义.

◆ Ptr

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

Typedef shared pointer.

在文件 ndt_solver.h98 行定义.

◆ 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.

在文件 ndt_solver.h85 行定义.

◆ TargetGridConstPtr

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

在文件 ndt_solver.h87 行定义.

◆ TargetGridLeafConstPtr

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

在文件 ndt_solver.h88 行定义.

◆ TargetGridPtr

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

在文件 ndt_solver.h86 行定义.

构造及析构函数说明

◆ 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.

在文件 ndt_solver.h107 行定义.

107 {
108 target_.reset();
109 input_.reset();
110 }
PointCloudSourceConstPtr input_
A pointer of input source point cloud.
Definition ndt_solver.h:329
PointCloudTargetConstPtr target_
A pointer of input target point cloud.
Definition ndt_solver.h:321

成员函数说明

◆ 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.

在文件 ndt_solver.h314 行定义.

315 {
316 return (g_a - mu * g_0);
317 }

◆ 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.

在文件 ndt_solver.h307 行定义.

308 {
309 return (f_a - f_0 - mu * g_0 * a);
310 }

◆ 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.

在文件 ndt_solver.h240 行定义.

240 {
241 ComputeTransformation(output, Eigen::Matrix4f::Identity());
242 }
void ComputeTransformation(PointCloudSourcePtr output)
Estimate the transformation and returns the transformed source (input) as output.
Definition ndt_solver.h:240

◆ 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.

在文件 ndt_solver.h199 行定义.

200 {
201 *trans = Eigen::Translation<float, 3>(static_cast<float>(x(0)),
202 static_cast<float>(x(1)),
203 static_cast<float>(x(2))) *
204 Eigen::AngleAxis<float>(static_cast<float>(x(3)),
205 Eigen::Vector3f::UnitX()) *
206 Eigen::AngleAxis<float>(static_cast<float>(x(4)),
207 Eigen::Vector3f::UnitY()) *
208 Eigen::AngleAxis<float>(static_cast<float>(x(5)),
209 Eigen::Vector3f::UnitZ());
210 }

◆ 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.

在文件 ndt_solver.h213 行定义.

214 {
215 Eigen::Affine3f _affine;
216 ConvertTransform(x, &_affine);
217 *trans = _affine.matrix();
218 }
static void ConvertTransform(const Eigen::Matrix< double, 6, 1 > &x, Eigen::Affine3f *trans)
Convert 6 element transformation vector to affine transformation.
Definition ndt_solver.h:199

◆ 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.

在文件 ndt_solver.h175 行定义.

◆ 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.

在文件 ndt_solver.h182 行定义.

◆ 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.

在文件 ndt_solver.h221 行定义.

221 {
222 target_cells_.GetDisplayCloud(*cell_cloud);
223 }
TargetGrid target_cells_
The voxel grid generated from target cloud containing point means and covariances.
Definition ndt_solver.h:326
void GetDisplayCloud(pcl::PointCloud< pcl::PointXYZ > *cell_cloud)

◆ GetOulierRatio()

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

Get the point cloud outlier ratio.

在文件 ndt_solver.h162 行定义.

162{ return outlier_ratio_; }
double outlier_ratio_
The ratio of outliers of points w.r.t.
Definition ndt_solver.h:349

◆ GetResolution()

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

Get voxel grid resolution.

在文件 ndt_solver.h149 行定义.

149{ return 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.

返回
maximum step length

在文件 ndt_solver.h154 行定义.

154{ return step_size_; }

◆ GetTransformationProbability()

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

Get the registration alignment probability.

在文件 ndt_solver.h170 行定义.

170 {
171 return trans_probability_;
172 }
double trans_probability_
The probability score of the transform applied to the input cloud, Equation 6.9 and 6....
Definition ndt_solver.h:355

◆ 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.

在文件 ndt_solver.h178 行定义.

◆ 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.

在文件 ndt_solver.h131 行定义.

131 {
132 if (cloud->points.empty()) {
133 AWARN << "Input source is empty.";
134 return;
135 }
136 input_ = cloud;
137 }
#define AWARN
Definition log.h:43

◆ 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.

在文件 ndt_solver.h113 行定义.

114 {
115 if (cell_leaf.empty()) {
116 AWARN << "Input leaf is empty.";
117 return;
118 }
119 if (cloud->points.empty()) {
120 AWARN << "Input target is empty.";
121 return;
122 }
123
124 target_ = cloud;
127 target_cells_.filter(cell_leaf, true);
128 }
void SetInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
void SetVoxelGridResolution(float lx, float ly, float lz)
void filter(const std::vector< Leaf > &cell_leaf, bool searchable=true)
Initializes voxel structure.

◆ 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.

在文件 ndt_solver.h226 行定义.

226 {
227 target_cells_.SetMapLeftTopCorner(left_top_corner);
228 }
void SetMapLeftTopCorner(const Eigen::Vector3d &left_top_corner)

◆ 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.

在文件 ndt_solver.h188 行定义.

188 {
189 max_iterations_ = nr_iterations;
190 }

◆ 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.

在文件 ndt_solver.h165 行定义.

165 {
166 outlier_ratio_ = outlier_ratio;
167 }

◆ SetResolution()

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

Set/change the voxel grid resolution.

在文件 ndt_solver.h140 行定义.

140 {
141 // Prevents unnessary voxel initiations
142 if (resolution_ != resolution) {
143 resolution_ = resolution;
144 }
145 AINFO << "NDT Resolution: " << resolution_;
146 }
#define AINFO
Definition log.h:42

◆ 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.

参数
[in]step_sizemaximum step length

在文件 ndt_solver.h159 行定义.

159{ step_size_ = step_size; }

◆ 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.

在文件 ndt_solver.h194 行定义.

194 {
195 transformation_epsilon_ = epsilon;
196 }
double transformation_epsilon_
Transformation epsilon parameter.
Definition ndt_solver.h:342

◆ 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.

类成员变量说明

◆ converged_

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

在文件 ndt_solver.h333 行定义.

◆ final_transformation_

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

在文件 ndt_solver.h336 行定义.

◆ 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].

在文件 ndt_solver.h352 行定义.

◆ gauss_d2_

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

在文件 ndt_solver.h352 行定义.

◆ 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].

在文件 ndt_solver.h363 行定义.

◆ h_ang_a3_

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

在文件 ndt_solver.h363 行定义.

◆ h_ang_b2_

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

在文件 ndt_solver.h363 行定义.

◆ h_ang_b3_

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

在文件 ndt_solver.h363 行定义.

◆ h_ang_c2_

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

在文件 ndt_solver.h363 行定义.

◆ h_ang_c3_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_d1_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_d2_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_d3_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_e1_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_e2_

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

在文件 ndt_solver.h364 行定义.

◆ h_ang_e3_

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

在文件 ndt_solver.h365 行定义.

◆ h_ang_f1_

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

在文件 ndt_solver.h365 行定义.

◆ h_ang_f2_

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

在文件 ndt_solver.h365 行定义.

◆ h_ang_f3_

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

在文件 ndt_solver.h365 行定义.

◆ input_

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

A pointer of input source point cloud.

在文件 ndt_solver.h329 行定义.

◆ 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].

在文件 ndt_solver.h359 行定义.

◆ j_ang_b_

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

在文件 ndt_solver.h359 行定义.

◆ j_ang_c_

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

在文件 ndt_solver.h359 行定义.

◆ j_ang_d_

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

在文件 ndt_solver.h359 行定义.

◆ j_ang_e_

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

在文件 ndt_solver.h359 行定义.

◆ j_ang_f_

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

在文件 ndt_solver.h359 行定义.

◆ j_ang_g_

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

在文件 ndt_solver.h360 行定义.

◆ j_ang_h_

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

在文件 ndt_solver.h360 行定义.

◆ max_iterations_

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

max iterations.

在文件 ndt_solver.h340 行定义.

◆ nr_iterations_

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

finnal iterations.

在文件 ndt_solver.h332 行定义.

◆ 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].

在文件 ndt_solver.h349 行定义.

◆ 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].

在文件 ndt_solver.h368 行定义.

◆ 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].

在文件 ndt_solver.h371 行定义.

◆ previous_transformation_

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

transformations.

在文件 ndt_solver.h335 行定义.

◆ resolution_

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

The side length of voxels.

在文件 ndt_solver.h344 行定义.

◆ step_size_

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

The maximum step length.

在文件 ndt_solver.h346 行定义.

◆ target_

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

A pointer of input target point cloud.

在文件 ndt_solver.h321 行定义.

◆ 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.

在文件 ndt_solver.h326 行定义.

◆ target_tree_

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

A pointer to the spatial search object.

在文件 ndt_solver.h323 行定义.

◆ 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].

在文件 ndt_solver.h355 行定义.

◆ transformation_

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

在文件 ndt_solver.h337 行定义.

◆ transformation_epsilon_

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

Transformation epsilon parameter.

在文件 ndt_solver.h342 行定义.


该类的文档由以下文件生成: