Iterative Closest Point registration. More...
#include <icp.h>
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< PointNormal > | KdTree |
typedef boost::shared_ptr < const KdTree > | KdTreeConstPtr |
typedef boost::shared_ptr< KdTree > | KdTreePtr |
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_ |
typedef pcl::PointCloud<PointNormal> pcl::ihs::ICP::CloudNormal [private] |
typedef CloudNormal::ConstPtr pcl::ihs::ICP::CloudNormalConstPtr [private] |
typedef CloudNormal::Ptr pcl::ihs::ICP::CloudNormalPtr [private] |
typedef pcl::PointCloud<PointXYZRGBNormal> pcl::ihs::ICP::CloudXYZRGBNormal |
typedef CloudXYZRGBNormal::ConstPtr pcl::ihs::ICP::CloudXYZRGBNormalConstPtr |
typedef CloudXYZRGBNormal::Ptr pcl::ihs::ICP::CloudXYZRGBNormalPtr |
typedef pcl::KdTree<PointNormal> pcl::ihs::ICP::KdTree [private] |
typedef boost::shared_ptr<const KdTree> pcl::ihs::ICP::KdTreeConstPtr [private] |
typedef boost::shared_ptr<KdTree> pcl::ihs::ICP::KdTreePtr [private] |
typedef pcl::ihs::Mesh pcl::ihs::ICP::Mesh |
typedef pcl::ihs::MeshConstPtr pcl::ihs::ICP::MeshConstPtr |
typedef pcl::ihs::MeshPtr pcl::ihs::ICP::MeshPtr |
typedef pcl::PointNormal pcl::ihs::ICP::PointNormal [private] |
typedef pcl::PointXYZRGBNormal pcl::ihs::ICP::PointXYZRGBNormal |
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).
[in] | mesh_model | Model mesh (target). |
[in] | cloud_data | Data cloud (source). |
[in] | T_init | Initial guess for the transformation. [out] T_final The computed transformation. |
float pcl::ihs::ICP::getCorrespondenceRejectionFactor | ( | ) | const |
float pcl::ihs::ICP::getEpsilon | ( | ) | const |
float pcl::ihs::ICP::getMaxAngle | ( | ) | const |
float pcl::ihs::ICP::getMaxFitness | ( | ) | const |
unsigned int pcl::ihs::ICP::getMaxIterations | ( | ) | const |
float pcl::ihs::ICP::getMinOverlap | ( | ) | const |
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).
[in] | cloud_source | Source cloud (data). |
[in] | cloud_target | Target cloud (model). |
[out] | T | The computed transformation. |
pcl::ihs::ICP::CloudNormalConstPtr pcl::ihs::ICP::selectDataPoints | ( | const CloudXYZRGBNormalConstPtr & | cloud_data | ) | const [private] |
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).
[in] | mesh_model | Input mesh. |
[in] | T_inv | Transformation that brings the model mesh into the camera coordinate system. |
void pcl::ihs::ICP::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.
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.
void pcl::ihs::ICP::setMaxAngle | ( | const float | angle | ) |
void pcl::ihs::ICP::setMaxFitness | ( | const float | fitness | ) |
void pcl::ihs::ICP::setMaxIterations | ( | const unsigned int | max_iter | ) |
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.
float pcl::ihs::ICP::epsilon_ [private] |
float pcl::ihs::ICP::factor_ [private] |
KdTreePtr pcl::ihs::ICP::kd_tree_ [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] |