Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar > 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, Scalar >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const IterativeClosestPoint
< PointSource, PointTarget,
Scalar > > 
ConstPtr
typedef Registration
< PointSource, PointTarget,
Scalar >::Matrix4 
Matrix4
typedef Registration
< PointSource, PointTarget,
Scalar >::PointCloudSource 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef Registration
< PointSource, PointTarget,
Scalar >::PointCloudTarget 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr
typedef boost::shared_ptr
< IterativeClosestPoint
< PointSource, PointTarget,
Scalar > > 
Ptr

Public Member Functions

pcl::registration::DefaultConvergenceCriteria
< Scalar >::Ptr 
getConvergeCriteria ()
 Returns a pointer to the DefaultConvergenceCriteria used by the IterativeClosestPoint class. This allows to check the convergence state after the align() method as well as to configure DefaultConvergenceCriteria's parameters not available through the ICP API before the align() method is called. Please note that the align method sets max_iterations_, euclidean_fitness_epsilon_ and transformation_epsilon_ and therefore overrides the default / set values of the DefaultConvergenceCriteria instance.
bool getUseReciprocalCorrespondences () const
 Obtain whether reciprocal correspondence are used or not.
 IterativeClosestPoint ()
 Empty constructor.
virtual void setInputSource (const PointCloudSourceConstPtr &cloud)
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
virtual void setInputTarget (const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target (e.g., the point cloud that we want to align to the target)
void setUseReciprocalCorrespondences (bool use_reciprocal_correspondence)
 Set whether to use reciprocal correspondence or not.
virtual ~IterativeClosestPoint ()
 Empty destructor.

Public Attributes

pcl::registration::DefaultConvergenceCriteria
< Scalar >::Ptr 
convergence_criteria_

Protected Member Functions

virtual void computeTransformation (PointCloudSource &output, const Matrix4 &guess)
 Rigid transformation computation method with initial guess.
virtual void transformCloud (const PointCloudSource &input, PointCloudSource &output, const Matrix4 &transform)
 Apply a rigid transform to a given dataset. Here we check whether whether the dataset has surface normals in addition to XYZ, and rotate normals as well.

Protected Attributes

size_t nx_idx_offset_
 Normal fields offset.
size_t ny_idx_offset_
size_t nz_idx_offset_
bool source_has_normals_
 Internal check whether source dataset has normals or not.
bool target_has_normals_
 Internal check whether target dataset has normals or not.
bool use_reciprocal_correspondence_
 The correspondence type used for correspondence estimation.
size_t x_idx_offset_
 XYZ fields offset.
size_t y_idx_offset_
size_t z_idx_offset_

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >

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 B. Rusu, Michael Dixon

Definition at line 94 of file registration/include/pcl/registration/icp.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<const IterativeClosestPoint<PointSource, PointTarget, Scalar> > pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Registration<PointSource, PointTarget, Scalar>::Matrix4 pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::Matrix4
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Registration<PointSource, PointTarget, Scalar>::PointCloudSource pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSource
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Registration<PointSource, PointTarget, Scalar>::PointCloudTarget pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTarget
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTargetPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointIndices::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointIndicesConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointIndices::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointIndicesPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<IterativeClosestPoint<PointSource, PointTarget, Scalar> > pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::Ptr

Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 138 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::~IterativeClosestPoint ( ) [inline, virtual]

Empty destructor.

Definition at line 156 of file registration/include/pcl/registration/icp.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation ( PointCloudSource output,
const Matrix4 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, Scalar >.

Definition at line 119 of file icp.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::registration::DefaultConvergenceCriteria<Scalar>::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::getConvergeCriteria ( ) [inline]

Returns a pointer to the DefaultConvergenceCriteria used by the IterativeClosestPoint class. This allows to check the convergence state after the align() method as well as to configure DefaultConvergenceCriteria's parameters not available through the ICP API before the align() method is called. Please note that the align method sets max_iterations_, euclidean_fitness_epsilon_ and transformation_epsilon_ and therefore overrides the default / set values of the DefaultConvergenceCriteria instance.

Parameters:
[out]Pointerto the IterativeClosestPoint's DefaultConvergenceCriteria.

Definition at line 167 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::getUseReciprocalCorrespondences ( ) const [inline]

Obtain whether reciprocal correspondence are used or not.

Definition at line 241 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::setInputSource ( const PointCloudSourceConstPtr cloud) [inline, virtual]

Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud source

Definition at line 178 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::setInputTarget ( const PointCloudTargetConstPtr cloud) [inline, virtual]

Provide a pointer to the input target (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud target

Definition at line 213 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::setUseReciprocalCorrespondences ( bool  use_reciprocal_correspondence) [inline]

Set whether to use reciprocal correspondence or not.

Parameters:
[in]use_reciprocal_correspondencewhether to use reciprocal correspondence or not

Definition at line 234 of file registration/include/pcl/registration/icp.h.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::transformCloud ( const PointCloudSource input,
PointCloudSource output,
const Matrix4 transform 
) [protected, virtual]

Apply a rigid transform to a given dataset. Here we check whether whether the dataset has surface normals in addition to XYZ, and rotate normals as well.

Parameters:
[in]inputthe input point cloud
[out]outputthe resultant output point cloud
[in]transforma 4x4 rigid transformation
Note:
Can be used with cloud_in equal to cloud_out

Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >.

Definition at line 49 of file icp.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::registration::DefaultConvergenceCriteria<Scalar>::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::convergence_criteria_

Definition at line 134 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::nx_idx_offset_ [protected]

Normal fields offset.

Definition at line 271 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::ny_idx_offset_ [protected]

Definition at line 271 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::nz_idx_offset_ [protected]

Definition at line 271 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::source_has_normals_ [protected]

Internal check whether source dataset has normals or not.

Definition at line 277 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::target_has_normals_ [protected]

Internal check whether target dataset has normals or not.

Definition at line 279 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::use_reciprocal_correspondence_ [protected]

The correspondence type used for correspondence estimation.

Definition at line 274 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::x_idx_offset_ [protected]

XYZ fields offset.

Definition at line 268 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::y_idx_offset_ [protected]

Definition at line 268 of file registration/include/pcl/registration/icp.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::z_idx_offset_ [protected]

Definition at line 268 of file registration/include/pcl/registration/icp.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:59