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

Public Types | |
| typedef boost::shared_ptr < const NormalDistributionsTransform2D < PointSource, PointTarget > > | ConstPtr |
| typedef boost::shared_ptr < NormalDistributionsTransform2D < PointSource, PointTarget > > | Ptr |
Public Member Functions | |
| NormalDistributionsTransform2D () | |
| Empty constructor. | |
| virtual void | setGridCentre (const Eigen::Vector2f ¢re) |
| centre of the ndt grid (target coordinate system) | |
| virtual void | setGridExtent (const Eigen::Vector2f &extent) |
| NDT Grid extent (in either direction from the grid centre) | |
| virtual void | setGridStep (const Eigen::Vector2f &step) |
| Grid spacing (step) of the NDT grid. | |
| 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. | |
| virtual | ~NormalDistributionsTransform2D () |
| Empty destructor. | |
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_extent_ |
| Eigen::Vector2f | grid_step_ |
| Eigen::Vector3d | newton_lambda_ |
Private Types | |
| typedef Registration < PointSource, PointTarget > ::PointCloudSource | PointCloudSource |
| typedef PointCloudSource::ConstPtr | PointCloudSourceConstPtr |
| typedef PointCloudSource::Ptr | PointCloudSourcePtr |
| typedef Registration < PointSource, PointTarget > ::PointCloudTarget | PointCloudTarget |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
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.
| typedef boost::shared_ptr< const NormalDistributionsTransform2D<PointSource, PointTarget> > pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::ConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointCloudSource [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::ConstPtr pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointCloudSourceConstPtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::Ptr pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointCloudSourcePtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointCloudTarget [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointIndices::ConstPtr pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointIndicesConstPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
typedef PointIndices::Ptr pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::PointIndicesPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
| typedef boost::shared_ptr< NormalDistributionsTransform2D<PointSource, PointTarget> > pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::Ptr |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
| pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::NormalDistributionsTransform2D | ( | ) | [inline] |
| virtual pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::~NormalDistributionsTransform2D | ( | ) | [inline, virtual] |
| void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, |
| const Eigen::Matrix4f & | guess | ||
| ) | [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.
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridCentre | ( | const Eigen::Vector2f & | centre | ) | [inline, virtual] |
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridExtent | ( | const Eigen::Vector2f & | extent | ) | [inline, virtual] |
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setGridStep | ( | const Eigen::Vector2f & | step | ) | [inline, virtual] |
| virtual void pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::setOptimizationStepSize | ( | const double & | lambda | ) | [inline, virtual] |
| 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.
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_centre_ [protected] |
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_extent_ [protected] |
Eigen::Vector2f pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::grid_step_ [protected] |
Eigen::Vector3d pcl::NormalDistributionsTransform2D< PointSource, PointTarget >::newton_lambda_ [protected] |