NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algorithm for scan matching. More...
#include <pcl/registration/ndt_2d.h>


Public Types | |
| typedef boost::shared_ptr < NormalDistributionsTransform2D < PointSource, PointTarget > > | Ptr |
| typedef boost::shared_ptr < const NormalDistributionsTransform2D < PointSource, PointTarget > > | ConstPtr |
Public Member Functions | |
| NormalDistributionsTransform2D () | |
| Empty constructor. | |
| virtual | ~NormalDistributionsTransform2D () |
| Empty destructor. | |
| virtual void | setGridCentre (const Eigen::Vector2f ¢re) |
| centre of the ndt grid (target coordinate system) | |
| virtual void | setGridStep (const Eigen::Vector2f &step) |
| Grid spacing (step) of the NDT grid. | |
| virtual void | setGridExtent (const Eigen::Vector2f &extent) |
| NDT Grid extent (in either direction from the grid centre). | |
| virtual void | setOptimizationStepSize (const double &lambda) |
| NDT Newton optimisation step size parameter. | |
| virtual void | setOptimizationStepSize (const Eigen::Vector3d &lambda) |
| NDT Newton optimisation step size parameter. | |
Protected Member Functions | |
| virtual void | computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) |
| Rigid transformation computation method with initial guess. | |
Protected Attributes | |
| Eigen::Vector2f | grid_centre_ |
| Eigen::Vector2f | grid_step_ |
| Eigen::Vector2f | grid_extent_ |
| Eigen::Vector3d | newton_lambda_ |
NormalDistributionsTransform2D provides an implementation of the Normal Distributions Transform algorithm for scan matching.
This implementation is intended to match the definition: Peter Biber and Wolfgang Straßer. The normal distributions transform: A new approach to laser scan matching. In Proceedings of the IEEE In- ternational Conference on Intelligent Robots and Systems (IROS), pages 2743–2748, Las Vegas, USA, October 2003.
Definition at line 60 of file ndt_2d.h.
| typedef boost::shared_ptr< const NormalDistributionsTransform2D<PointSource, PointTarget> > pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::ConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
| typedef boost::shared_ptr< NormalDistributionsTransform2D<PointSource, PointTarget> > pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::Ptr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
| pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::NormalDistributionsTransform2D | ( | ) | [inline] |
Empty constructor.
Definition at line 77 of file ndt_2d.h.
References pcl::Registration< PointSource, PointTarget >::reg_name_.
| virtual pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::~NormalDistributionsTransform2D | ( | ) | [inline, virtual] |
| void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, | |
| const Eigen::Matrix4f & | guess | |||
| ) | [inline, protected, virtual] |
Rigid transformation computation method with initial guess.
| [out] | output | the transformed input point cloud dataset using the rigid transformation found |
| [in] | guess | the initial guess of the transformation to compute |
Definition at line 376 of file ndt_2d.hpp.
References pcl::Registration< PointSource, PointTarget >::converged_, pcl::Registration< PointSource, PointTarget >::final_transformation_, pcl::ndt2d::ValueAndDerivatives< N, T >::grad, pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_centre_, pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_extent_, pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_step_, pcl::ndt2d::ValueAndDerivatives< N, T >::hessian, pcl::PCLBase< PointSource >::indices_, pcl::Registration< PointSource, PointTarget >::max_iterations_, pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::newton_lambda_, pcl::Registration< PointSource, PointTarget >::nr_iterations_, pcl::Registration< PointSource, PointTarget >::previous_transformation_, pcl::Registration< PointSource, PointTarget >::target_, pcl::ndt2d::NDT2D< PointT >::test(), pcl::Registration< PointSource, PointTarget >::transformation_, pcl::Registration< PointSource, PointTarget >::transformation_epsilon_, pcl::transformPointCloud(), pcl::Registration< PointSource, PointTarget >::update_visualizer_, and pcl::ndt2d::ValueAndDerivatives< N, T >::value.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridCentre | ( | const Eigen::Vector2f & | centre | ) | [inline, virtual] |
centre of the ndt grid (target coordinate system)
| centre | value to set |
Definition at line 91 of file ndt_2d.h.
References pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_centre_.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridExtent | ( | const Eigen::Vector2f & | extent | ) | [inline, virtual] |
NDT Grid extent (in either direction from the grid centre).
| [in] | extent | value to set |
Definition at line 103 of file ndt_2d.h.
References pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_extent_.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridStep | ( | const Eigen::Vector2f & | step | ) | [inline, virtual] |
Grid spacing (step) of the NDT grid.
| [in] | step | value to set |
Definition at line 97 of file ndt_2d.h.
References pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_step_.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setOptimizationStepSize | ( | const Eigen::Vector3d & | lambda | ) | [inline, virtual] |
NDT Newton optimisation step size parameter.
| [in] | lambda | step size: (1,1,1) is simple newton optimisation, smaller values may improve convergence, or elements may be set to zero to prevent optimisation over some parameters |
This overload allows control of updates to the individual (x, y, theta) free parameters in the optimisation. If, for example, theta is believed to be close to the correct value a small value of lambda[2] should be used.
Definition at line 122 of file ndt_2d.h.
References pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::newton_lambda_.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setOptimizationStepSize | ( | const double & | lambda | ) | [inline, virtual] |
NDT Newton optimisation step size parameter.
| [in] | lambda | step size: 1 is simple newton optimisation, smaller values may improve convergence |
Definition at line 109 of file ndt_2d.h.
References pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::newton_lambda_.
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_centre_ [protected] |
Definition at line 144 of file ndt_2d.h.
Referenced by pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), and pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridCentre().
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_extent_ [protected] |
Definition at line 146 of file ndt_2d.h.
Referenced by pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), and pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridExtent().
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_step_ [protected] |
Definition at line 145 of file ndt_2d.h.
Referenced by pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), and pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridStep().
Eigen::Vector3d pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::newton_lambda_ [protected] |
Definition at line 147 of file ndt_2d.h.
Referenced by pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation(), and pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setOptimizationStepSize().