A 3D Normal Distribution Transform registration implementation for point cloud data. More...
#include <pcl/registration/ndt.h>


Public Types | |
| typedef boost::shared_ptr < NormalDistributionsTransform < PointSource, PointTarget > > | Ptr |
| typedef boost::shared_ptr < const NormalDistributionsTransform < PointSource, PointTarget > > | ConstPtr |
Public Member Functions | |
| NormalDistributionsTransform () | |
| Constructor. | |
| virtual | ~NormalDistributionsTransform () |
| Empty destructor. | |
| 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 | 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. | |
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::Ptr | PointCloudSourcePtr |
| typedef PointCloudSource::ConstPtr | PointCloudSourceConstPtr |
| typedef Registration < PointSource, PointTarget > ::PointCloudTarget | PointCloudTarget |
| typedef PointCloudTarget::Ptr | PointCloudTargetPtr |
| typedef PointCloudTarget::ConstPtr | PointCloudTargetConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
| typedef VoxelGridCovariance < PointTarget > | TargetGrid |
| Typename of searchable voxel grid containing mean and covariance. | |
| typedef TargetGrid * | TargetGridPtr |
| Typename of pointer to searchable voxel grid. | |
| 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. | |
Protected Member Functions | |
| 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 | 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. | |
| 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. | |
| void | computeAngleDerivatives (Eigen::Matrix< double, 6, 1 > &p, bool compute_hessian=true) |
| Precompute anglular components of derivatives. | |
| void | computePointDerivatives (Eigen::Vector3d &x, bool compute_hessian=true) |
| Compute point derivatives. | |
| 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. | |
| 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. | |
| 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. | |
| 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). | |
| 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 | 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. | |
| 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. | |
Protected Attributes | |
| TargetGrid | target_cells_ |
| The voxel grid generated from target cloud containing point means and covariances. | |
| 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_ |
| 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_ |
| 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::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. | |
A 3D Normal Distribution Transform registration implementation for point cloud data.
Definition at line 63 of file ndt.h.
| 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 | ( | ) | [inline] |
Constructor.
Sets outlier_ratio_ to 0.35, step_size_ to 0.05 and resolution_ to 1.0
Definition at line 46 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_, pcl::Registration< PointSource, PointTarget >::max_iterations_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_, pcl::Registration< PointSource, PointTarget >::reg_name_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_, and pcl::Registration< PointSource, PointTarget >::transformation_epsilon_.
| 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.
, derivative of Equation 1.6 (Moore, Thuente 1994) | [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] |
Definition at line 412 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT().
| 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 Equation 1.6 (Moore, Thuente 1994) | [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] |
Definition at line 399 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives | ( | Eigen::Matrix< double, 6, 1 > & | p, | |
| bool | compute_hessian = true | |||
| ) | [inline, protected] |
Precompute anglular components of derivatives.
| [in] | p | the current transform vector |
| [in] | compute_hessian | flag to calculate hessian, unnessissary for step calculation. |
Definition at line 233 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives().
| 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 | |||
| ) | [inline, 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. |
Definition at line 176 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives(), pcl::PCLBase< PointSource >::input_, pcl::VoxelGridCovariance< PointT >::radiusSearch(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateDerivatives().
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian | ( | Eigen::Matrix< double, 6, 6 > & | hessian, | |
| PointCloudSource & | trans_cloud, | |||
| Eigen::Matrix< double, 6, 1 > & | p | |||
| ) | [inline, 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 |
Definition at line 397 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives(), pcl::PCLBase< PointSource >::input_, pcl::VoxelGridCovariance< PointT >::radiusSearch(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian().
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives | ( | Eigen::Vector3d & | x, | |
| bool | compute_hessian = true | |||
| ) | [inline, protected] |
Compute point derivatives.
| [in] | x | point from the input cloud |
| [in] | compute_hessian | flag to calculate hessian, unnessissary for step calculation. |
Definition at line 310 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian().
| 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 | |||
| ) | [inline, 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] |
Definition at line 604 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::auxilaryFunction_dPsiMT(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::auxilaryFunction_PsiMT(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian(), pcl::Registration< PointSource, PointTarget >::final_transformation_, pcl::PCLBase< PointSource >::input_, pcl::transformPointCloud(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::trialValueSelectionMT(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateIntervalMT().
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, | |
| const Eigen::Matrix4f & | guess | |||
| ) | [inline, protected, virtual] |
Estimate the transformation and returns the transformed source (input) as output.
| [out] | output | the resultant input transfomed point cloud dataset |
| [in] | guess | the initial gross estimation of the transformation |
Definition at line 77 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT(), pcl::Registration< PointSource, PointTarget >::converged_, pcl::Registration< PointSource, PointTarget >::final_transformation_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_, pcl::PCLBase< PointSource >::input_, pcl::Registration< PointSource, PointTarget >::max_iterations_, pcl::Registration< PointSource, PointTarget >::nr_iterations_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_, pcl::Registration< PointSource, PointTarget >::previous_transformation_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_, pcl::Registration< PointSource, PointTarget >::target_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::trans_probability_, pcl::Registration< PointSource, PointTarget >::transformation_, pcl::Registration< PointSource, PointTarget >::transformation_epsilon_, pcl::transformPointCloud(), and pcl::Registration< PointSource, PointTarget >::update_visualizer_.
| virtual void pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output | ) | [inline, protected, virtual] |
| static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform | ( | const Eigen::Matrix< double, 6, 1 > & | x, | |
| Eigen::Matrix4f & | trans | |||
| ) | [inline, static] |
Convert 6 element transformation vector to transformation matrix.
| [in] | x | transformation vector of the form [x, y, z, roll, pitch, yaw] |
| [out] | trans | 4x4 transformation matrix corresponding to given transfomation vector |
Definition at line 208 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform().
| static void pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform | ( | const Eigen::Matrix< double, 6, 1 > & | x, | |
| Eigen::Affine3f & | trans | |||
| ) | [inline, static] |
Convert 6 element transformation vector to affine transformation.
| [in] | x | transformation vector of the form [x, y, z, roll, pitch, yaw] |
| [out] | trans | affine transform corresponding to given transfomation vector |
Definition at line 195 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::convertTransform().
| int pcl::NormalDistributionsTransform< PointSource, PointTarget >::getFinalNumIteration | ( | ) | const [inline] |
Get the number of iterations required to calculate alignment.
Definition at line 185 of file ndt.h.
References pcl::Registration< PointSource, PointTarget >::nr_iterations_.
| double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getOulierRatio | ( | ) | const [inline] |
Get the point cloud outlier ratio.
Definition at line 158 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_.
| float pcl::NormalDistributionsTransform< PointSource, PointTarget >::getResolution | ( | ) | const [inline] |
Get voxel grid resolution.
Definition at line 131 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_.
| double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getStepSize | ( | ) | const [inline] |
Get the newton line search maximum step length.
Definition at line 140 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_.
| double pcl::NormalDistributionsTransform< PointSource, PointTarget >::getTransformationProbability | ( | ) | const [inline] |
Get the registration alignment probability.
Definition at line 176 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::trans_probability_.
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::init | ( | ) | [inline, protected] |
Initiate covariance voxel structure.
Definition at line 252 of file ndt.h.
References pcl::VoxelGridCovariance< PointT >::filter(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_, pcl::PCLBase< PointT >::setInputCloud(), pcl::VoxelGrid< PointT >::setLeafSize(), pcl::Registration< PointSource, PointTarget >::target_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::setInputTarget(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::setResolution().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setInputTarget | ( | const PointCloudTargetConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to).
| [in] | cloud | the input point cloud target |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
Definition at line 106 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::init().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setOulierRatio | ( | double | outlier_ratio | ) | [inline] |
Set/change the point cloud outlier ratio.
| [in] | outlier_ratio | outlier ratio |
Definition at line 167 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_.
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setResolution | ( | float | resolution | ) | [inline] |
Set/change the voxel grid resolution.
| [in] | resolution | side length of voxels |
Definition at line 116 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::init(), pcl::PCLBase< PointSource >::input_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_.
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::setStepSize | ( | double | step_size | ) | [inline] |
Set/change the newton line search maximum step length.
| [in] | step_size | maximum step length |
Definition at line 149 of file ndt.h.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_.
| 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 | |||
| ) | [inline, protected] |
Select new trial value for More-Thuente method.
is used for
and
until some value satifies the test
and
then
is used from then on. | [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) |
Definition at line 521 of file ndt.hpp.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT().
| 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 | |||
| ) | [inline, 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. |
Definition at line 351 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives().
| void pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian | ( | Eigen::Matrix< double, 6, 6 > & | hessian, | |
| Eigen::Vector3d & | x_trans, | |||
| Eigen::Matrix3d & | c_inv | |||
| ) | [inline, 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 |
Definition at line 449 of file ndt.hpp.
References pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_, pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_, and pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian().
| 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 | |||
| ) | [inline, protected] |
Update interval of possible step lengths for More-Thuente method,
in More-Thuente (1994).
and
and Modified Updating Algorithm from then on [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 |
Definition at line 480 of file ndt.hpp.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeStepLengthMT().
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d1_ [protected] |
The normalization constants used fit the point distribution to a normal distribution, Equation 6.8 [Magnusson 2009].
Definition at line 432 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian().
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::gauss_d2_ [protected] |
Definition at line 432 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a2_ [protected] |
Precomputed Angular Hessian.
The precomputed angular derivatives for the hessian of a transformation vector, Equation 6.19 [Magnusson 2009].
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_a3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b2_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_b3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c2_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_c3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d1_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d2_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_d3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e1_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e2_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_e3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f1_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f2_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::h_ang_f3_ [protected] |
Definition at line 447 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_a_ [protected] |
Precomputed Angular Gradient.
The precomputed angular derivatives for the jacobian of a transformation vector, Equation 6.19 [Magnusson 2009].
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_b_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_c_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_d_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_e_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_f_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_g_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
Eigen::Vector3d pcl::NormalDistributionsTransform< PointSource, PointTarget >::j_ang_h_ [protected] |
Definition at line 441 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeAngleDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives().
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::outlier_ratio_ [protected] |
The ratio of outliers of points w.r.t.
a normal distribution, Equation 6.7 [Magnusson 2009].
Definition at line 429 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::getOulierRatio(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::setOulierRatio().
Eigen::Matrix<double, 3, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_gradient_ [protected] |
The first order derivative of the transformation of a point w.r.t.
the transform vector,
in Equation 6.18 [Magnusson 2009].
Definition at line 455 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian().
Eigen::Matrix<double, 18, 6> pcl::NormalDistributionsTransform< PointSource, PointTarget >::point_hessian_ [protected] |
The second order derivative of the transformation of a point w.r.t.
the transform vector,
in Equation 6.20 [Magnusson 2009].
Definition at line 458 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computePointDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateDerivatives(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::updateHessian().
float pcl::NormalDistributionsTransform< PointSource, PointTarget >::resolution_ [protected] |
The side length of voxels.
Definition at line 423 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::getResolution(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::init(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::NormalDistributionsTransform(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::setResolution().
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::step_size_ [protected] |
The maximum step length.
Definition at line 426 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::getStepSize(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::setStepSize().
TargetGrid pcl::NormalDistributionsTransform< PointSource, PointTarget >::target_cells_ [protected] |
The voxel grid generated from target cloud containing point means and covariances.
Definition at line 418 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::init().
double pcl::NormalDistributionsTransform< PointSource, PointTarget >::trans_probability_ [protected] |
The probability score of the transform applied to the input cloud, Equation 6.9 and 6.10 [Magnusson 2009].
Definition at line 435 of file ndt.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeTransformation(), and pcl::NormalDistributionsTransform< PointSource, PointTarget >::getTransformationProbability().