Public Member Functions | Protected Member Functions | Private Types
pcl::IterativeClosestPoint< PointSource, PointTarget > Class Template Reference

IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm. The transformation is estimated based on Singular Value Decomposition (SVD). More...

#include <icp.h>

Inheritance diagram for pcl::IterativeClosestPoint< PointSource, PointTarget >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 IterativeClosestPoint ()
 Empty constructor.

Protected Member Functions

virtual void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
 Rigid transformation computation method with initial guess.

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

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::IterativeClosestPoint< PointSource, PointTarget >

IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm. The transformation is estimated based on Singular Value Decomposition (SVD).

The algorithm has several termination criteria:

  1. Number of iterations has reached the maximum user imposed number of iterations (via setMaximumIterations)
  2. The epsilon (difference) between the previous transformation and the current estimated transformation is smaller than an user imposed value (via setTransformationEpsilon)
  3. The sum of Euclidean squared errors is smaller than a user defined threshold (via setEuclideanFitnessEpsilon)

Usage example:

 IterativeClosestPoint<PointXYZ, PointXYZ> icp;
 // Set the input source and target
 icp.setInputCloud (cloud_source);
 icp.setInputTarget (cloud_target);

 // Set the max correspondence distance to 5cm (e.g., correspondences with higher distances will be ignored)
 icp.setMaxCorrespondenceDistance (0.05);
 // Set the maximum number of iterations (criterion 1)
 icp.setMaximumIterations (50);
 // Set the transformation epsilon (criterion 2)
 icp.setTransformationEpsilon (1e-8);
 // Set the euclidean distance difference epsilon (criterion 3)
 icp.setEuclideanFitnessEpsilon (1);

 // Perform the alignment
 icp.align (cloud_source_registered);

 // Obtain the transformation that aligned cloud_source to cloud_source_registered
 Eigen::Matrix4f transformation = icp.getFinalTransformation ();
Author:
Radu Bogdan Rusu, Michael Dixon

Definition at line 88 of file icp.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSource [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSourceConstPtr [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSourcePtr [private]
template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudTarget [private]
template<typename PointSource, typename PointTarget>
typedef PointIndices::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointIndicesConstPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.

Definition at line 97 of file icp.h.

template<typename PointSource, typename PointTarget>
typedef PointIndices::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointIndicesPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.

Definition at line 96 of file icp.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget>
pcl::IterativeClosestPoint< PointSource, PointTarget >::IterativeClosestPoint ( ) [inline]

Empty constructor.

Definition at line 101 of file icp.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void pcl::IterativeClosestPoint< PointSource, PointTarget >::computeTransformation ( PointCloudSource output,
const Eigen::Matrix4f &  guess 
) [protected, virtual]

Rigid transformation computation method with initial guess.

Parameters:
outputthe transformed input point cloud dataset using the rigid transformation found
guessthe initial guess of the transformation to compute

Implements pcl::Registration< PointSource, PointTarget >.

Definition at line 45 of file icp.hpp.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30