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 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 |
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 ();
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSource [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSourceConstPtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
typedef PointCloudSource::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudSourcePtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPoint< PointSource, PointTarget >::PointCloudTarget [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
typedef PointIndices::ConstPtr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointIndicesConstPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
typedef PointIndices::Ptr pcl::IterativeClosestPoint< PointSource, PointTarget >::PointIndicesPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
pcl::IterativeClosestPoint< PointSource, PointTarget >::IterativeClosestPoint | ( | ) | [inline] |
void pcl::IterativeClosestPoint< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, |
const Eigen::Matrix4f & | 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 >.