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_ |
Iterative Closest Point registration.
Definition at line 71 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef pcl::PointCloud<PointNormal> pcl::ihs::ICP::CloudNormal [private] |
Definition at line 169 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef CloudNormal::ConstPtr pcl::ihs::ICP::CloudNormalConstPtr [private] |
Definition at line 171 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef CloudNormal::Ptr pcl::ihs::ICP::CloudNormalPtr [private] |
Definition at line 170 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Definition at line 76 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Definition at line 78 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Definition at line 77 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef pcl::KdTree<PointNormal> pcl::ihs::ICP::KdTree [private] |
Definition at line 173 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef boost::shared_ptr<const KdTree> pcl::ihs::ICP::KdTreeConstPtr [private] |
Definition at line 175 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef boost::shared_ptr<KdTree> pcl::ihs::ICP::KdTreePtr [private] |
Definition at line 174 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef pcl::ihs::Mesh pcl::ihs::ICP::Mesh |
Definition at line 80 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef pcl::ihs::MeshConstPtr pcl::ihs::ICP::MeshConstPtr |
Definition at line 82 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Definition at line 81 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
typedef pcl::PointNormal pcl::ihs::ICP::PointNormal [private] |
Definition at line 168 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Definition at line 75 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
Constructor.
Definition at line 56 of file apps/in_hand_scanner/src/icp.cpp.
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. |
Definition at line 156 of file apps/in_hand_scanner/src/icp.cpp.
float pcl::ihs::ICP::getCorrespondenceRejectionFactor | ( | ) | const |
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.
float pcl::ihs::ICP::getMaxFitness | ( | ) | const |
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.
float pcl::ihs::ICP::getMinOverlap | ( | ) | const |
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).
[in] | cloud_source | Source cloud (data). |
[in] | cloud_target | Target cloud (model). |
[out] | T | The computed transformation. |
Definition at line 426 of file apps/in_hand_scanner/src/icp.cpp.
pcl::ihs::ICP::CloudNormalConstPtr pcl::ihs::ICP::selectDataPoints | ( | const CloudXYZRGBNormalConstPtr & | cloud_data | ) | const [private] |
Selects the valid data points. The input cloud is organized -> contains nans which are removed.
[in] | cloud_data | Input cloud. |
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).
[in] | mesh_model | Input mesh. |
[in] | T_inv | Transformation that brings the model mesh into the camera coordinate system. |
Definition at line 374 of file apps/in_hand_scanner/src/icp.cpp.
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.
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.
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.
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)
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.
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.
Definition at line 100 of file apps/in_hand_scanner/src/icp.cpp.
float pcl::ihs::ICP::epsilon_ [private] |
Definition at line 211 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
float pcl::ihs::ICP::factor_ [private] |
Definition at line 219 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
KdTreePtr pcl::ihs::ICP::kd_tree_ [private] |
Definition at line 208 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
float pcl::ihs::ICP::max_angle_ [private] |
Definition at line 220 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
float pcl::ihs::ICP::max_fitness_ [private] |
Definition at line 216 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
unsigned int pcl::ihs::ICP::max_iterations_ [private] |
Definition at line 214 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.
float pcl::ihs::ICP::min_overlap_ [private] |
Definition at line 215 of file apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h.