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>
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_ |
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:
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 ();
Definition at line 94 of file registration/include/pcl/registration/icp.h.
typedef boost::shared_ptr<const IterativeClosestPoint<PointSource, PointTarget, Scalar> > pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::ConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, and pcl::IterativeClosestPointNonLinear< PointSource, PointTarget, Scalar >.
Definition at line 109 of file registration/include/pcl/registration/icp.h.
typedef Registration<PointSource, PointTarget, Scalar>::Matrix4 pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::Matrix4 |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >, and pcl::IterativeClosestPointNonLinear< PointSource, PointTarget, Scalar >.
Definition at line 135 of file registration/include/pcl/registration/icp.h.
typedef Registration<PointSource, PointTarget, Scalar>::PointCloudSource pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSource |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >, and pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 97 of file registration/include/pcl/registration/icp.h.
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 99 of file registration/include/pcl/registration/icp.h.
typedef PointCloudSource::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudSourcePtr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 98 of file registration/include/pcl/registration/icp.h.
typedef Registration<PointSource, PointTarget, Scalar>::PointCloudTarget pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTarget |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >, and pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 101 of file registration/include/pcl/registration/icp.h.
typedef PointCloudTarget::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 103 of file registration/include/pcl/registration/icp.h.
typedef PointCloudTarget::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointCloudTargetPtr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 102 of file registration/include/pcl/registration/icp.h.
typedef PointIndices::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointIndicesConstPtr |
Reimplemented from pcl::PCLBase< PointSource >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 106 of file registration/include/pcl/registration/icp.h.
typedef PointIndices::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::PointIndicesPtr |
Reimplemented from pcl::PCLBase< PointSource >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 105 of file registration/include/pcl/registration/icp.h.
typedef boost::shared_ptr<IterativeClosestPoint<PointSource, PointTarget, Scalar> > pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::Ptr |
Reimplemented from pcl::Registration< PointSource, PointTarget, Scalar >.
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, and pcl::IterativeClosestPointNonLinear< PointSource, PointTarget, Scalar >.
Definition at line 108 of file registration/include/pcl/registration/icp.h.
pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::IterativeClosestPoint | ( | ) | [inline] |
Empty constructor.
Definition at line 138 of file registration/include/pcl/registration/icp.h.
virtual pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::~IterativeClosestPoint | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 156 of file registration/include/pcl/registration/icp.h.
void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::computeTransformation | ( | PointCloudSource & | output, |
const Matrix4 & | guess | ||
) | [protected, virtual] |
Rigid transformation computation method with initial guess.
output | the transformed input point cloud dataset using the rigid transformation found |
guess | the initial guess of the transformation to compute |
Implements pcl::Registration< PointSource, PointTarget, Scalar >.
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.
[out] | Pointer | to the IterativeClosestPoint's DefaultConvergenceCriteria. |
Definition at line 167 of file registration/include/pcl/registration/icp.h.
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.
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)
[in] | cloud | the input point cloud source |
Definition at line 178 of file registration/include/pcl/registration/icp.h.
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)
[in] | cloud | the input point cloud target |
Definition at line 213 of file registration/include/pcl/registration/icp.h.
void pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::setUseReciprocalCorrespondences | ( | bool | use_reciprocal_correspondence | ) | [inline] |
Set whether to use reciprocal correspondence or not.
[in] | use_reciprocal_correspondence | whether to use reciprocal correspondence or not |
Definition at line 234 of file registration/include/pcl/registration/icp.h.
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.
[in] | input | the input point cloud |
[out] | output | the resultant output point cloud |
[in] | transform | a 4x4 rigid transformation |
Reimplemented in pcl::IterativeClosestPointWithNormals< PointSource, PointTarget, Scalar >.
pcl::registration::DefaultConvergenceCriteria<Scalar>::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::convergence_criteria_ |
Definition at line 134 of file registration/include/pcl/registration/icp.h.
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.
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::ny_idx_offset_ [protected] |
Definition at line 271 of file registration/include/pcl/registration/icp.h.
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::nz_idx_offset_ [protected] |
Definition at line 271 of file registration/include/pcl/registration/icp.h.
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.
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.
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.
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.
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::y_idx_offset_ [protected] |
Definition at line 268 of file registration/include/pcl/registration/icp.h.
size_t pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >::z_idx_offset_ [protected] |
Definition at line 268 of file registration/include/pcl/registration/icp.h.