Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
pcl::ihs::ICP Class Reference

Iterative Closest Point registration. More...

#include <icp.h>

List of all members.

Public Types

typedef pcl::PointCloud
< PointXYZRGBNormal
CloudXYZRGBNormal
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr
typedef pcl::ihs::Mesh Mesh
typedef pcl::ihs::MeshConstPtr MeshConstPtr
typedef pcl::ihs::MeshPtr MeshPtr
typedef pcl::PointXYZRGBNormal PointXYZRGBNormal

Public Member Functions

bool findTransformation (const MeshConstPtr &mesh_model, const CloudXYZRGBNormalConstPtr &cloud_data, const Eigen::Matrix4f &T_init, Eigen::Matrix4f &T_final)
 Find the transformation that aligns the data cloud (source) to the model mesh (target).
 ICP ()
 Constructor.
void setEpsilon (const float epsilon)
 Convergence is detected when the change of the fitness between the current and previous iteration becomes smaller than the given epsilon (set in cm^2). The fitness is the mean squared euclidean distance between corresponding points.
float getEpsilon () const
void setMaxIterations (const unsigned int max_iter)
 The registration fails if the number of iterations exceeds the maximum number of iterations.
unsigned int getMaxIterations () const
void setMinOverlap (const float overlap)
 The registration fails at the state of convergence if the overlap between the model and data shape is smaller than a minimum overlap. The overlap is the fraction of correspondences (after rejection) to the initial number of data points.
float getMinOverlap () const
void setMaxFitness (const float fitness)
 The registration fails at the state of convergence if the fitness is bigger than this threshold (set in cm^2)
float getMaxFitness () const
void setCorrespondenceRejectionFactor (const float factor)
 Correspondences are rejected if the squared distance is above a threshold. This threshold is initialized with infinity (all correspondences are accepted in the first iteration). The threshold of the next iterations is set to the fitness of the current iteration multiplied by the factor set by this method.
float getCorrespondenceRejectionFactor () const
void setMaxAngle (const float angle)
 Correspondences are rejected if the angle between the normals is bigger than this threshold. Set in degrees.
float getMaxAngle () const

Private Types

typedef pcl::PointCloud
< PointNormal
CloudNormal
typedef CloudNormal::ConstPtr CloudNormalConstPtr
typedef CloudNormal::Ptr CloudNormalPtr
typedef pcl::KdTree< PointNormalKdTree
typedef boost::shared_ptr
< const KdTree
KdTreeConstPtr
typedef boost::shared_ptr< KdTreeKdTreePtr
typedef pcl::PointNormal PointNormal

Private Member Functions

bool minimizePointPlane (const CloudNormal &cloud_source, const CloudNormal &cloud_target, Eigen::Matrix4f &T) const
 Finds the transformation that minimizes the point to plane distance from the source to the target cloud. The input clouds must be arranged to have one to one correspondences (point 0 in source corresponds to point 0 in target, point 1 in source to point 1 in target and so on).
CloudNormalConstPtr selectDataPoints (const CloudXYZRGBNormalConstPtr &cloud_data) const
 Selects the valid data points. The input cloud is organized -> contains nans which are removed.
CloudNormalConstPtr selectModelPoints (const MeshConstPtr &mesh_model, const Eigen::Matrix4f &T_inv) const
 Selects the model points that are pointing towards to the camera (data coordinate system = camera coordinate system).

Private Attributes

float epsilon_
float factor_
KdTreePtr kd_tree_
float max_angle_
float max_fitness_
unsigned int max_iterations_
float min_overlap_

Detailed Description

Iterative Closest Point registration.

Author:
Martin Saelzle

Definition at line 71 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.


Member Typedef Documentation

typedef boost::shared_ptr<const KdTree> pcl::ihs::ICP::KdTreeConstPtr [private]
typedef boost::shared_ptr<KdTree> pcl::ihs::ICP::KdTreePtr [private]
typedef pcl::ihs::MeshConstPtr pcl::ihs::ICP::MeshConstPtr

Constructor & Destructor Documentation

Constructor.

Definition at line 56 of file apps/in_hand_scanner/src/icp.cpp.


Member Function Documentation

bool pcl::ihs::ICP::findTransformation ( const MeshConstPtr mesh_model,
const CloudXYZRGBNormalConstPtr cloud_data,
const Eigen::Matrix4f &  T_init,
Eigen::Matrix4f &  T_final 
)

Find the transformation that aligns the data cloud (source) to the model mesh (target).

Parameters:
[in]mesh_modelModel mesh (target).
[in]cloud_dataData cloud (source).
[in]T_initInitial guess for the transformation. [out] T_final The computed transformation.
Returns:
true if success.

Definition at line 156 of file apps/in_hand_scanner/src/icp.cpp.

Definition at line 134 of file apps/in_hand_scanner/src/icp.cpp.

float pcl::ihs::ICP::getEpsilon ( ) const

Definition at line 78 of file apps/in_hand_scanner/src/icp.cpp.

float pcl::ihs::ICP::getMaxAngle ( ) const

Definition at line 148 of file apps/in_hand_scanner/src/icp.cpp.

Definition at line 120 of file apps/in_hand_scanner/src/icp.cpp.

unsigned int pcl::ihs::ICP::getMaxIterations ( ) const

Definition at line 92 of file apps/in_hand_scanner/src/icp.cpp.

Definition at line 106 of file apps/in_hand_scanner/src/icp.cpp.

bool pcl::ihs::ICP::minimizePointPlane ( const CloudNormal cloud_source,
const CloudNormal cloud_target,
Eigen::Matrix4f &  T 
) const [private]

Finds the transformation that minimizes the point to plane distance from the source to the target cloud. The input clouds must be arranged to have one to one correspondences (point 0 in source corresponds to point 0 in target, point 1 in source to point 1 in target and so on).

Parameters:
[in]cloud_sourceSource cloud (data).
[in]cloud_targetTarget cloud (model).
[out]TThe computed transformation.
Returns:
true if success

Definition at line 426 of file apps/in_hand_scanner/src/icp.cpp.

Selects the valid data points. The input cloud is organized -> contains nans which are removed.

Parameters:
[in]cloud_dataInput cloud.
Returns:
Cloud containing the selected points.

Definition at line 402 of file apps/in_hand_scanner/src/icp.cpp.

pcl::ihs::ICP::CloudNormalConstPtr pcl::ihs::ICP::selectModelPoints ( const MeshConstPtr mesh_model,
const Eigen::Matrix4f &  T_inv 
) const [private]

Selects the model points that are pointing towards to the camera (data coordinate system = camera coordinate system).

Parameters:
[in]mesh_modelInput mesh.
[in]T_invTransformation that brings the model mesh into the camera coordinate system.
Returns:
Cloud containing the selected points (the connectivity information of the mesh is currently not used during the registration).

Definition at line 374 of file apps/in_hand_scanner/src/icp.cpp.

Correspondences are rejected if the squared distance is above a threshold. This threshold is initialized with infinity (all correspondences are accepted in the first iteration). The threshold of the next iterations is set to the fitness of the current iteration multiplied by the factor set by this method.

Note:
Must be greater or equal one. Smaller values are set to one.

Definition at line 128 of file apps/in_hand_scanner/src/icp.cpp.

void pcl::ihs::ICP::setEpsilon ( const float  epsilon)

Convergence is detected when the change of the fitness between the current and previous iteration becomes smaller than the given epsilon (set in cm^2). The fitness is the mean squared euclidean distance between corresponding points.

Note:
Only accepted if it is greater than 0.

Definition at line 72 of file apps/in_hand_scanner/src/icp.cpp.

void pcl::ihs::ICP::setMaxAngle ( const float  angle)

Correspondences are rejected if the angle between the normals is bigger than this threshold. Set in degrees.

Note:
Must be between 180 degrees and 0. Values outside this range are clamped to the nearest valid value.

Definition at line 142 of file apps/in_hand_scanner/src/icp.cpp.

void pcl::ihs::ICP::setMaxFitness ( const float  fitness)

The registration fails at the state of convergence if the fitness is bigger than this threshold (set in cm^2)

Note:
Must be greater than zero.

Definition at line 114 of file apps/in_hand_scanner/src/icp.cpp.

void pcl::ihs::ICP::setMaxIterations ( const unsigned int  max_iter)

The registration fails if the number of iterations exceeds the maximum number of iterations.

Note:
Must be greater than 0. Smaller values are set to 1.

Definition at line 86 of file apps/in_hand_scanner/src/icp.cpp.

void pcl::ihs::ICP::setMinOverlap ( const float  overlap)

The registration fails at the state of convergence if the overlap between the model and data shape is smaller than a minimum overlap. The overlap is the fraction of correspondences (after rejection) to the initial number of data points.

Note:
Must be between zero and one. Values outside this range are clamped to the nearest valid value.

Definition at line 100 of file apps/in_hand_scanner/src/icp.cpp.


Member Data Documentation

float pcl::ihs::ICP::epsilon_ [private]
float pcl::ihs::ICP::factor_ [private]
float pcl::ihs::ICP::max_angle_ [private]
float pcl::ihs::ICP::max_fitness_ [private]
unsigned int pcl::ihs::ICP::max_iterations_ [private]
float pcl::ihs::ICP::min_overlap_ [private]

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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:57