Apollo 10.0
自动驾驶开放平台
|
#include <ndt_solver.h>
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< PointCloudSource > | PointCloudSourcePtr |
typedef boost::shared_ptr< const PointCloudSource > | PointCloudSourceConstPtr |
typedef pcl::PointCloud< PointTarget > | PointCloudTarget |
Typename of target point. | |
typedef boost::shared_ptr< const PointCloudTarget > | PointCloudTargetConstPtr |
typedef VoxelGridCovariance< PointTarget > | TargetGrid |
Typename of searchable voxel grid containing mean and covariance. | |
typedef TargetGrid * | TargetGridPtr |
typedef const TargetGrid * | TargetGridConstPtr |
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. | |
在文件 ndt_solver.h 第 73 行定义.
typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::ConstPtr |
在文件 ndt_solver.h 第 101 行定义.
|
protected |
Typename of KD-Tree.
在文件 ndt_solver.h 第 91 行定义.
|
protected |
在文件 ndt_solver.h 第 92 行定义.
|
protected |
Typename of source point.
在文件 ndt_solver.h 第 76 行定义.
|
protected |
在文件 ndt_solver.h 第 78 行定义.
|
protected |
在文件 ndt_solver.h 第 77 行定义.
|
protected |
Typename of target point.
在文件 ndt_solver.h 第 81 行定义.
|
protected |
在文件 ndt_solver.h 第 82 行定义.
typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::Ptr |
Typedef shared pointer.
在文件 ndt_solver.h 第 98 行定义.
|
protected |
Typename of searchable voxel grid containing mean and covariance.
在文件 ndt_solver.h 第 85 行定义.
|
protected |
在文件 ndt_solver.h 第 87 行定义.
|
protected |
在文件 ndt_solver.h 第 88 行定义.
|
protected |
在文件 ndt_solver.h 第 86 行定义.
apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform | ( | ) |
Constructor.
|
inline |
Destructor.
在文件 ndt_solver.h 第 107 行定义.
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.
|
inlineprotected |
Auxiliary function derivative used to determine endpoints of More-Thuente interval.
在文件 ndt_solver.h 第 314 行定义.
|
inlineprotected |
Auxiliary function used to determine endpoints of More-Thuente interval.
在文件 ndt_solver.h 第 307 行定义.
|
protected |
Precompute anglular components of derivatives.
|
protected |
Compute derivatives of probability function w.r.t.
the transformation vector.
|
protected |
Compute hessian of probability function w.r.t.
the transformation vector.
|
protected |
Compute point derivatives.
|
protected |
Compute line search step length and update transform and probability derivatives.
|
inlineprotected |
Estimate the transformation and returns the transformed source (input) as output.
在文件 ndt_solver.h 第 240 行定义.
|
protected |
Estimate the transformation and returns the transformed source (input) as output.
|
inlinestatic |
Convert 6 element transformation vector to affine transformation.
在文件 ndt_solver.h 第 199 行定义.
|
inlinestatic |
Convert 6 element transformation vector to transformation matrix.
在文件 ndt_solver.h 第 213 行定义.
|
inline |
Get the number of iterations required to calculate alignment.
在文件 ndt_solver.h 第 175 行定义.
|
inline |
Get the final transformation matrix estimated by the registration method.
在文件 ndt_solver.h 第 182 行定义.
double apollo::localization::ndt::NormalDistributionsTransform< PointSource, PointTarget >::GetFitnessScore | ( | double | max_range = std::numeric_limits< double >::max() | ) |
Obtain the Euclidean fitness score.
|
inline |
Obtain probability point cloud.
在文件 ndt_solver.h 第 221 行定义.
|
inline |
Get the point cloud outlier ratio.
在文件 ndt_solver.h 第 162 行定义.
|
inline |
Get voxel grid resolution.
在文件 ndt_solver.h 第 149 行定义.
|
inline |
Get the newton line search maximum step length.
在文件 ndt_solver.h 第 154 行定义.
|
inline |
Get the registration alignment probability.
在文件 ndt_solver.h 第 170 行定义.
|
inline |
Return the state of convergence after the last align run.
在文件 ndt_solver.h 第 178 行定义.
|
inline |
|
inline |
Provide a pointer to the input target.
在文件 ndt_solver.h 第 113 行定义.
|
inline |
Set left top corner of target point cloud.
在文件 ndt_solver.h 第 226 行定义.
|
inline |
Set the maximum number of iterations the internal optimization should run for.
在文件 ndt_solver.h 第 188 行定义.
|
inline |
Set/change the point cloud outlier ratio.
在文件 ndt_solver.h 第 165 行定义.
|
inline |
Set/change the voxel grid resolution.
在文件 ndt_solver.h 第 140 行定义.
|
inline |
Set/change the newton line search maximum step length.
[in] | step_size | maximum step length |
在文件 ndt_solver.h 第 159 行定义.
|
inline |
Set the transformation epsilon (maximum allowable difference between two consecutive transformations.
在文件 ndt_solver.h 第 194 行定义.
|
protected |
Select new trial value for More-Thuente method.
|
protected |
Compute individual point contributions to derivatives of probability function w.r.t.
the transformation vector.
|
protected |
Compute individual point contributions to hessian of probability function.
|
protected |
Update interval of possible step lengths for More-Thuente method.
|
protected |
在文件 ndt_solver.h 第 333 行定义.
|
protected |
在文件 ndt_solver.h 第 336 行定义.
|
protected |
The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009].
在文件 ndt_solver.h 第 352 行定义.
|
protected |
在文件 ndt_solver.h 第 352 行定义.
|
protected |
The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009].
在文件 ndt_solver.h 第 363 行定义.
|
protected |
在文件 ndt_solver.h 第 363 行定义.
|
protected |
在文件 ndt_solver.h 第 363 行定义.
|
protected |
在文件 ndt_solver.h 第 363 行定义.
|
protected |
在文件 ndt_solver.h 第 363 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 364 行定义.
|
protected |
在文件 ndt_solver.h 第 365 行定义.
|
protected |
在文件 ndt_solver.h 第 365 行定义.
|
protected |
在文件 ndt_solver.h 第 365 行定义.
|
protected |
在文件 ndt_solver.h 第 365 行定义.
|
protected |
A pointer of input source point cloud.
在文件 ndt_solver.h 第 329 行定义.
|
protected |
The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009].
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 359 行定义.
|
protected |
在文件 ndt_solver.h 第 360 行定义.
|
protected |
在文件 ndt_solver.h 第 360 行定义.
|
protected |
max iterations.
在文件 ndt_solver.h 第 340 行定义.
|
protected |
finnal iterations.
在文件 ndt_solver.h 第 332 行定义.
|
protected |
The ratio of outliers of points w.r.t.
a normal distribution, Equation 6.7 [Magnusson 2009].
在文件 ndt_solver.h 第 349 行定义.
|
protected |
The first order derivative of the transformation of a point w.r.t.
the transform vector, Equation 6.18 [Magnusson 2009].
在文件 ndt_solver.h 第 368 行定义.
|
protected |
The second order derivative of the transformation of a point w.r.t.
the transform vector, Equation 6.20 [Magnusson 2009].
在文件 ndt_solver.h 第 371 行定义.
|
protected |
transformations.
在文件 ndt_solver.h 第 335 行定义.
|
protected |
The side length of voxels.
在文件 ndt_solver.h 第 344 行定义.
|
protected |
The maximum step length.
在文件 ndt_solver.h 第 346 行定义.
|
protected |
A pointer of input target point cloud.
在文件 ndt_solver.h 第 321 行定义.
|
protected |
The voxel grid generated from target cloud containing point means and covariances.
在文件 ndt_solver.h 第 326 行定义.
|
protected |
A pointer to the spatial search object.
在文件 ndt_solver.h 第 323 行定义.
|
protected |
The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009].
在文件 ndt_solver.h 第 355 行定义.
|
protected |
在文件 ndt_solver.h 第 337 行定义.
|
protected |
Transformation epsilon parameter.
在文件 ndt_solver.h 第 342 行定义.