A 3D Normal Distribution Transform registration implementation for point cloud data. More...
#include <ndt.h>
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 TargetGrid * | TargetGridConstPtr |
Typename of const pointer to searchable voxel grid. | |
typedef TargetGrid::LeafConstPtr | TargetGridLeafConstPtr |
Typename of const pointer to searchable voxel grid leaf. | |
typedef TargetGrid * | TargetGridPtr |
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, 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, 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, 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]. |
A 3D Normal Distribution Transform registration implementation for point cloud data.
typedef boost::shared_ptr< const NormalDistributionsTransform<PointSource, PointTarget> > pcl::NormalDistributionsTransform< PointSource, PointTarget >::ConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSource [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourceConstPtr [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudSourcePtr [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTarget [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudTarget::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTargetConstPtr [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudTarget::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointCloudTargetPtr [protected] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointIndices::ConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointIndicesConstPtr [protected] |
Reimplemented from pcl::PCLBase< PointSource >.
typedef PointIndices::Ptr pcl::NormalDistributionsTransform< PointSource, PointTarget >::PointIndicesPtr [protected] |
Reimplemented from pcl::PCLBase< PointSource >.
typedef boost::shared_ptr< NormalDistributionsTransform<PointSource, PointTarget> > pcl::NormalDistributionsTransform< PointSource, PointTarget >::Ptr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef VoxelGridCovariance<PointTarget> pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGrid [protected] |
typedef const TargetGrid* pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridConstPtr [protected] |
typedef TargetGrid::LeafConstPtr pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridLeafConstPtr [protected] |
typedef TargetGrid* pcl::NormalDistributionsTransform< PointSource, PointTarget >::TargetGridPtr [protected] |
pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform | ( | ) |
Constructor. Sets outlier_ratio_ to 0.35, step_size_ to 0.05 and resolution_ to 1.0.
virtual pcl::NormalDistributionsTransform< PointSource, PointTarget >::~NormalDistributionsTransform | ( | ) | [inline, virtual] |
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.
[in] | g_a | function gradient at step length a, in More-Thuente (1994) |
[in] | g_0 | initial function gradiant, in More-Thuente (1994) |
[in] | mu | the step length, constant in Equation 1.1 [More, Thuente 1994] |
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.
[in] | a | the step length, in More-Thuente (1994) |
[in] | f_a | function value at step length a, in More-Thuente (1994) |
[in] | f_0 | initial function value, in Moore-Thuente (1994) |
[in] | g_0 | initial function gradiant, in More-Thuente (1994) |
[in] | mu | the step length, constant in Equation 1.1 [More, Thuente 1994] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives | ( | Eigen::Matrix< double, 6, 1 > & | p, |
bool | compute_hessian = true |
||
) | [protected] |
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.
[out] | score_gradient | the gradient vector of the probability function w.r.t. the transformation vector |
[out] | hessian | the hessian matrix of the probability function w.r.t. the transformation vector |
[in] | trans_cloud | transformed point cloud |
[in] | p | the current transform vector |
[in] | compute_hessian | flag to calculate hessian, unnessissary for step calculation. |
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.
[out] | hessian | the hessian matrix of the probability function w.r.t. the transformation vector |
[in] | trans_cloud | transformed point cloud |
[in] | p | the current transform vector |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives | ( | Eigen::Vector3d & | x, |
bool | compute_hessian = true |
||
) | [protected] |
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.
[in] | x | initial transformation vector, in Equation 1.3 (Moore, Thuente 1994) and in Algorithm 2 [Magnusson 2009] |
[in] | step_dir | descent direction, in Equation 1.3 (Moore, Thuente 1994) and normalized in Algorithm 2 [Magnusson 2009] |
[in] | step_init | initial step length estimate, in Moore-Thuente (1994) and the noramal of in Algorithm 2 [Magnusson 2009] |
[in] | step_max | maximum step length, in Moore-Thuente (1994) |
[in] | step_min | minimum step length, in Moore-Thuente (1994) |
[out] | score | final score function value, in Equation 1.3 (Moore, Thuente 1994) and in Algorithm 2 [Magnusson 2009] |
[in,out] | score_gradient | gradient of score function w.r.t. transformation vector, in Moore-Thuente (1994) and in Algorithm 2 [Magnusson 2009] |
[out] | hessian | hessian of score function w.r.t. transformation vector, in Moore-Thuente (1994) and in Algorithm 2 [Magnusson 2009] |
[in,out] | trans_cloud | transformed point cloud, transformed by in Algorithm 2 [Magnusson 2009] |
virtual void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output | ) | [inline, protected, virtual] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, |
const Eigen::Matrix4f & | guess | ||
) | [protected, virtual] |
static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform | ( | const Eigen::Matrix< double, 6, 1 > & | x, |
Eigen::Affine3f & | trans | ||
) | [inline, static] |
static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform | ( | const Eigen::Matrix< double, 6, 1 > & | x, |
Eigen::Matrix4f & | trans | ||
) | [inline, static] |
int pcl::NormalDistributionsTransform< PointSource, PointTarget >::getFinalNumIteration | ( | ) | const [inline] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getOulierRatio | ( | ) | const [inline] |
float pcl::NormalDistributionsTransform< PointSource, PointTarget >::getResolution | ( | ) | const [inline] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getStepSize | ( | ) | const [inline] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getTransformationProbability | ( | ) | const [inline] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::init | ( | ) | [inline, protected] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setInputTarget | ( | const PointCloudTargetConstPtr & | cloud | ) | [inline] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setOulierRatio | ( | double | outlier_ratio | ) | [inline] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setResolution | ( | float | resolution | ) | [inline] |
void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setStepSize | ( | double | step_size | ) | [inline] |
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.
[in] | a_l | first endpoint of interval , in Moore-Thuente (1994) |
[in] | f_l | value at first endpoint, in Moore-Thuente (1994) |
[in] | g_l | derivative at first endpoint, in Moore-Thuente (1994) |
[in] | a_u | second endpoint of interval , in Moore-Thuente (1994) |
[in] | f_u | value at second endpoint, in Moore-Thuente (1994) |
[in] | g_u | derivative at second endpoint, in Moore-Thuente (1994) |
[in] | a_t | previous trial value, in Moore-Thuente (1994) |
[in] | f_t | value at previous trial value, in Moore-Thuente (1994) |
[in] | g_t | derivative at previous trial value, in Moore-Thuente (1994) |
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.
[in,out] | score_gradient | the gradient vector of the probability function w.r.t. the transformation vector |
[in,out] | hessian | the hessian matrix of the probability function w.r.t. the transformation vector |
[in] | x_trans | transformed point minus mean of occupied covariance voxel |
[in] | c_inv | covariance of occupied covariance voxel |
[in] | compute_hessian | flag to calculate hessian, unnessissary for step calculation. |
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.
[in,out] | hessian | the hessian matrix of the probability function w.r.t. the transformation vector |
[in] | x_trans | transformed point minus mean of occupied covariance voxel |
[in] | c_inv | covariance of occupied covariance voxel |
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, in More-Thuente (1994)
[in,out] | a_l | first endpoint of interval , in Moore-Thuente (1994) |
[in,out] | f_l | value at first endpoint, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
[in,out] | g_l | derivative at first endpoint, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
[in,out] | a_u | second endpoint of interval , in Moore-Thuente (1994) |
[in,out] | f_u | value at second endpoint, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
[in,out] | g_u | derivative at second endpoint, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
[in] | a_t | trial value, in Moore-Thuente (1994) |
[in] | f_t | value at trial value, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
[in] | g_t | derivative at trial value, in Moore-Thuente (1994), for Update Algorithm and for Modified Update Algorithm |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_ [protected] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_ [protected] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_ [protected] |
Eigen::Matrix<double, 3, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_ [protected] |
Eigen::Matrix<double, 18, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_ [protected] |
float pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_ [protected] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_ [protected] |
TargetGrid pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_ [protected] |
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::trans_probability_ [protected] |