Registration represents the base registration class for general purpose, ICP-like methods. More...
#include <pcl/registration/registration.h>
Public Member Functions | |
Registration () | |
Empty constructor. More... |
|
~Registration () | |
destructor. More... |
|
void | setTransformationEstimation (const TransformationEstimationPtr &te) |
Provide a pointer to the transformation estimation object. More... |
|
void | setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce) |
Provide a pointer to the correspondence estimation object. More... |
|
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) More... |
|
const PointCloudSourceConstPtr | getInputSource () |
Get a pointer to the input point cloud dataset target. More... |
|
virtual void | setInputTarget (const PointCloudTargetConstPtr &cloud) |
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More... |
|
const PointCloudTargetConstPtr | getInputTarget () |
Get a pointer to the input point cloud dataset target. More... |
|
void | setSearchMethodTarget (const KdTreePtr &tree, bool force_no_recompute=false) |
Provide a pointer to the search object used to find correspondences in the target cloud. More... |
|
KdTreePtr | getSearchMethodTarget () const |
Get a pointer to the search method used to find correspondences in the target cloud. More... |
|
void | setSearchMethodSource (const KdTreeReciprocalPtr &tree, bool force_no_recompute=false) |
Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding). More... |
|
KdTreeReciprocalPtr | getSearchMethodSource () const |
Get a pointer to the search method used to find correspondences in the source cloud. More... |
|
Matrix4 | getFinalTransformation () |
Get the final transformation matrix estimated by the registration method. More... |
|
Matrix4 | getLastIncrementalTransformation () |
Get the last incremental transformation matrix estimated by the registration method. More... |
|
void | setMaximumIterations (int nr_iterations) |
Set the maximum number of iterations the internal optimization should run for. More... |
|
int | getMaximumIterations () |
Get the maximum number of iterations the internal optimization should run for, as set by the user. More... |
|
void | setRANSACIterations (int ransac_iterations) |
Set the number of iterations RANSAC should run for. More... |
|
double | getRANSACIterations () |
Get the number of iterations RANSAC should run for, as set by the user. More... |
|
void | setRANSACOutlierRejectionThreshold (double inlier_threshold) |
Set the inlier distance threshold for the internal RANSAC outlier rejection loop. More... |
|
double | getRANSACOutlierRejectionThreshold () |
Get the inlier distance threshold for the internal outlier rejection loop as set by the user. More... |
|
void | setMaxCorrespondenceDistance (double distance_threshold) |
Set the maximum distance threshold between two correspondent points in source <-> target. More... |
|
double | getMaxCorrespondenceDistance () |
Get the maximum distance threshold between two correspondent points in source <-> target. More... |
|
void | setTransformationEpsilon (double epsilon) |
Set the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More... |
|
double | getTransformationEpsilon () |
Get the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) as set by the user. More... |
|
void | setTransformationRotationEpsilon (double epsilon) |
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More... |
|
double | getTransformationRotationEpsilon () |
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transformations) as set by the user (epsilon is the cos(angle) in a axis-angle representation). More... |
|
void | setEuclideanFitnessEpsilon (double epsilon) |
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More... |
|
double | getEuclideanFitnessEpsilon () |
Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user. More... |
|
void | setPointRepresentation (const PointRepresentationConstPtr &point_representation) |
Provide a boost shared pointer to the PointRepresentation to be used when comparing points. More... |
|
bool | registerVisualizationCallback (std::function< UpdateVisualizerCallbackSignature > &visualizerCallback) |
Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration. More... |
|
double | getFitnessScore (double max_range=std::numeric_limits< double >::max()) |
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) More... |
|
double | getFitnessScore (const std::vector< float > &distances_a, const std::vector< float > &distances_b) |
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points) More... |
|
bool | hasConverged () const |
Return the state of convergence after the last align run. More... |
|
void | align (PointCloudSource &output) |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More... |
|
void | align (PointCloudSource &output, const Matrix4 &guess) |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More... |
|
const std::string & | getClassName () const |
Abstract class get name method. More... |
|
bool | initCompute () |
Internal computation initialization. More... |
|
bool | initComputeReciprocal () |
Internal computation when reciprocal lookup is needed. More... |
|
void | addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector) |
Add a new correspondence rejector to the list. More... |
|
std::vector< CorrespondenceRejectorPtr > | getCorrespondenceRejectors () |
Get the list of correspondence rejectors. More... |
|
bool | removeCorrespondenceRejector (unsigned int i) |
Remove the i-th correspondence rejector in the list. More... |
|
void | clearCorrespondenceRejectors () |
Clear the list of correspondence rejectors. More... |
|
Public Member Functions inherited from pcl::PCLBase< PointSource > | |
PCLBase () | |
Empty constructor. More... |
|
PCLBase (const PCLBase &base) | |
Copy constructor. More... |
|
virtual | ~PCLBase ()=default |
Destructor. More... |
|
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. More... |
|
const PointCloudConstPtr | getInputCloud () const |
Get a pointer to the input point cloud dataset. More... |
|
virtual void | setIndices (const IndicesPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... |
|
virtual void | setIndices (const IndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... |
|
virtual void | setIndices (const PointIndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... |
|
virtual void | setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols) |
Set the indices for the points laying within an interest region of the point cloud. More... |
|
IndicesPtr | getIndices () |
Get a pointer to the vector of indices used. More... |
|
const IndicesConstPtr | getIndices () const |
Get a pointer to the vector of indices used. More... |
|
const PointSource & | operator[] (std::size_t pos) const |
Override PointCloud operator[] to shorten code. More... |
|
Protected Member Functions | |
bool | searchForNeighbors (const PointCloudSource &cloud, int index, pcl::Indices &indices, std::vector< float > &distances) |
Search for the closest nearest neighbor of a given point. More... |
|
virtual void | computeTransformation (PointCloudSource &output, const Matrix4 &guess)=0 |
Abstract transformation computation method with initial guess. More... |
|
Protected Member Functions inherited from pcl::PCLBase< PointSource > | |
bool | initCompute () |
This method should get called before starting the actual computation. More... |
|
bool | deinitCompute () |
This method should get called after finishing the actual computation. More... |
|
Protected Attributes | |
std::string | reg_name_ |
The registration method name. More... |
|
KdTreePtr | tree_ |
A pointer to the spatial search object. More... |
|
KdTreeReciprocalPtr | tree_reciprocal_ |
A pointer to the spatial search object of the source. More... |
|
int | nr_iterations_ |
The number of iterations the internal optimization ran for (used internally). More... |
|
int | max_iterations_ |
The maximum number of iterations the internal optimization should run for. More... |
|
int | ransac_iterations_ |
The number of iterations RANSAC should run for. More... |
|
PointCloudTargetConstPtr | target_ |
The input point cloud dataset target. More... |
|
Matrix4 | final_transformation_ |
The final transformation matrix estimated by the registration method after N iterations. More... |
|
Matrix4 | transformation_ |
The transformation matrix estimated by the registration method. More... |
|
Matrix4 | previous_transformation_ |
The previous transformation matrix estimated by the registration method (used internally). More... |
|
double | transformation_epsilon_ |
The maximum difference between two consecutive transformations in order to consider convergence (user defined). More... |
|
double | transformation_rotation_epsilon_ |
The maximum rotation difference between two consecutive transformations in order to consider convergence (user defined). More... |
|
double | euclidean_fitness_epsilon_ |
The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More... |
|
double | corr_dist_threshold_ |
The maximum distance threshold between two correspondent points in source <-> target. More... |
|
double | inlier_threshold_ |
The inlier distance threshold for the internal RANSAC outlier rejection loop. More... |
|
bool | converged_ |
Holds internal convergence state, given user parameters. More... |
|
int | min_number_correspondences_ |
The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation. More... |
|
CorrespondencesPtr | correspondences_ |
The set of correspondences determined at this ICP step. More... |
|
TransformationEstimationPtr | transformation_estimation_ |
A TransformationEstimation object, used to calculate the 4x4 rigid transformation. More... |
|
CorrespondenceEstimationPtr | correspondence_estimation_ |
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud. More... |
|
std::vector< CorrespondenceRejectorPtr > | correspondence_rejectors_ |
The list of correspondence rejectors to use. More... |
|
bool | target_cloud_updated_ |
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. More... |
|
bool | source_cloud_updated_ |
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. More... |
|
bool | force_no_recompute_ |
A flag which, if set, means the tree operating on the target cloud will never be recomputed. More... |
|
bool | force_no_recompute_reciprocal_ |
A flag which, if set, means the tree operating on the source cloud will never be recomputed. More... |
|
std::function< UpdateVisualizerCallbackSignature > | update_visualizer_ |
Callback function to update intermediate source point cloud position during it's registration to the target point cloud. More... |
|
Protected Attributes inherited from pcl::PCLBase< PointSource > | |
PointCloudConstPtr | input_ |
The input point cloud dataset. More... |
|
IndicesPtr | indices_ |
A pointer to the vector of point indices to use. More... |
|
bool | use_indices_ |
Set to true if point indices are used. More... |
|
bool | fake_indices_ |
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More... |
|
Registration represents the base registration class for general purpose, ICP-like methods.
Definition at line 57 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::ConstPtr = shared_ptr<const Registration<PointSource, PointTarget, Scalar> > |
Definition at line 67 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimation = pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> |
Definition at line 92 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationConstPtr = typename CorrespondenceEstimation::ConstPtr |
Definition at line 94 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationPtr = typename CorrespondenceEstimation::Ptr |
Definition at line 93 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceRejectorPtr = pcl::registration::CorrespondenceRejector::Ptr |
Definition at line 69 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTree = pcl::search::KdTree<PointTarget> |
Definition at line 70 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreePtr = typename KdTree::Ptr |
Definition at line 71 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocal = pcl::search::KdTree<PointSource> |
Definition at line 73 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr |
Definition at line 74 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::Matrix4 = Eigen::Matrix<Scalar, 4, 4> |
Definition at line 59 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSource = pcl::PointCloud<PointSource> |
Definition at line 76 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr |
Definition at line 78 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourcePtr = typename PointCloudSource::Ptr |
Definition at line 77 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTarget = pcl::PointCloud<PointTarget> |
Definition at line 80 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr |
Definition at line 82 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetPtr = typename PointCloudTarget::Ptr |
Definition at line 81 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr |
Definition at line 84 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::Ptr = shared_ptr<Registration<PointSource, PointTarget, Scalar> > |
Definition at line 66 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimation = typename pcl::registration:: TransformationEstimation<PointSource, PointTarget, Scalar> |
Definition at line 87 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationConstPtr = typename TransformationEstimation::ConstPtr |
Definition at line 89 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationPtr = typename TransformationEstimation::Ptr |
Definition at line 88 of file registration.h.
using pcl::Registration< PointSource, PointTarget, Scalar >::UpdateVisualizerCallbackSignature = void(const pcl::PointCloud<PointSource>&, const pcl::Indices&, const pcl::PointCloud<PointTarget>&, const pcl::Indices&) |
The callback signature to the function updating intermediate source point cloud position during it's registration to the target point cloud.
[in] | cloud_src | - the point cloud which will be updated to match target |
[in] | indices_src | - a selector of points in cloud_src |
[in] | cloud_tgt | - the point cloud we want to register against |
[in] | indices_tgt | - a selector of points in cloud_tgt |
Definition at line 106 of file registration.h.
| inline |
Empty constructor.
Definition at line 109 of file registration.h.
| inline |
destructor.
Definition at line 137 of file registration.h.
| inline |
Add a new correspondence rejector to the list.
[in] | rejector | the new correspondence rejector to concatenate |
Code example:
Definition at line 525 of file registration.h.
| inline |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
[out] | output | the resultant input transformed point cloud dataset |
Definition at line 166 of file registration.hpp.
| inline |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
[out] | output | the resultant input transformed point cloud dataset |
[in] | guess | the initial gross estimation of the transformation |
Definition at line 173 of file registration.hpp.
| inline |
Clear the list of correspondence rejectors.
Definition at line 551 of file registration.h.
| protectedpure virtual |
Abstract transformation computation method with initial guess.
| inline |
Abstract class get name method.
Definition at line 495 of file registration.h.
Referenced by pcl::RegistrationVisualizer< PointSource, PointTarget >::setRegistration().
| inline |
Get the list of correspondence rejectors.
Definition at line 532 of file registration.h.
| inline |
Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user.
See setEuclideanFitnessEpsilon
Definition at line 424 of file registration.h.
| inline |
Get the final transformation matrix estimated by the registration method.
Definition at line 271 of file registration.h.
| inline |
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points)
[in] | distances_a | the first set of distances between correspondences |
[in] | distances_b | the second set of distances between correspondences |
Definition at line 122 of file registration.hpp.
| inline |
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target)
[in] | max_range | maximum allowable distance between a point and its correspondence in the target (default: double::max) |
Definition at line 134 of file registration.hpp.
| inline |
Get a pointer to the input point cloud dataset target.
Definition at line 201 of file registration.h.
| inline |
Get a pointer to the input point cloud dataset target.
Definition at line 214 of file registration.h.
| inline |
Get the last incremental transformation matrix estimated by the registration method.
Definition at line 279 of file registration.h.
| inline |
Get the maximum distance threshold between two correspondent points in source <-> target.
If the distance is larger than this threshold, the points will be ignored in the alignment process.
Definition at line 358 of file registration.h.
| inline |
Get the maximum number of iterations the internal optimization should run for, as set by the user.
Definition at line 297 of file registration.h.
| inline |
Get the number of iterations RANSAC should run for, as set by the user.
Definition at line 313 of file registration.h.
| inline |
Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
Definition at line 336 of file registration.h.
| inline |
Get a pointer to the search method used to find correspondences in the source cloud.
Definition at line 263 of file registration.h.
| inline |
Get a pointer to the search method used to find correspondences in the target cloud.
Definition at line 238 of file registration.h.
| inline |
Get the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) as set by the user.
Definition at line 379 of file registration.h.
| inline |
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transformations) as set by the user (epsilon is the cos(angle) in a axis-angle representation).
Definition at line 402 of file registration.h.
| inline |
Return the state of convergence after the last align run.
Definition at line 473 of file registration.h.
bool pcl::Registration< PointSource, PointTarget, Scalar >::initCompute |
Internal computation initialization.
Definition at line 75 of file registration.hpp.
bool pcl::Registration< PointSource, PointTarget, Scalar >::initComputeReciprocal |
Internal computation when reciprocal lookup is needed.
Definition at line 105 of file registration.hpp.
| inline |
Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration.
[in] | visualizerCallback | reference of the user callback function |
Definition at line 444 of file registration.h.
Referenced by pcl::RegistrationVisualizer< PointSource, PointTarget >::setRegistration().
| inline |
Remove the i-th correspondence rejector in the list.
[in] | i | the position of the correspondence rejector in the list to remove |
Definition at line 541 of file registration.h.
| inlineprotected |
Search for the closest nearest neighbor of a given point.
cloud | the point cloud dataset to use for nearest neighbor search |
index | the index of the query point |
indices | the resultant vector of indices representing the k-nearest neighbors |
distances | the resultant distances from the query point to the k-nearest neighbors |
Definition at line 673 of file registration.h.
| inline |
Provide a pointer to the correspondence estimation object.
(e.g., regular, reciprocal, normal shooting etc.)
[in] | ce | is the pointer to the corresponding correspondence estimation object |
Code example:
Definition at line 186 of file registration.h.
| inline |
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged.
The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences.
[in] | epsilon | the maximum allowed distance error before the algorithm will be considered to have converged |
Definition at line 414 of file registration.h.
| inlinevirtual |
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 |
Reimplemented in pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >, pcl::IterativeClosestPoint< PointSource, PointTarget, float >, pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >, pcl::GeneralizedIterativeClosestPoint6D, and pcl::JointIterativeClosestPoint< PointSource, PointTarget, Scalar >.
Definition at line 47 of file registration.hpp.
Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget >::setInputSource().
| inlinevirtual |
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
[in] | cloud | the input point cloud target |
Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >, pcl::GeneralizedIterativeClosestPoint6D, pcl::PPFRegistration< PointSource, PointTarget >, pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >, pcl::IterativeClosestPoint< PointSource, PointTarget, float >, pcl::IterativeClosestPoint< PointXYZRGBA, PointXYZRGBA >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::NormalDistributionsTransform< PointSource, PointTarget >, and pcl::JointIterativeClosestPoint< PointSource, PointTarget, Scalar >.
Definition at line 61 of file registration.hpp.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::setInputTarget(), and pcl::IterativeClosestPoint< PointSource, PointTarget >::setInputTarget().
| inline |
Set the maximum distance threshold between two correspondent points in source <-> target.
If the distance is larger than this threshold, the points will be ignored in the alignment process.
[in] | distance_threshold | the maximum distance threshold between a point and its nearest neighbor correspondent in order to be considered in the alignment process |
Definition at line 348 of file registration.h.
| inline |
Set the maximum number of iterations the internal optimization should run for.
[in] | nr_iterations | the maximum number of iterations the internal optimization should run for |
Definition at line 289 of file registration.h.
| inline |
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
[in] | point_representation | the PointRepresentation to be used by the k-D tree |
Definition at line 434 of file registration.h.
| inline |
Set the number of iterations RANSAC should run for.
[in] | ransac_iterations | is the number of iterations RANSAC should run for |
Definition at line 306 of file registration.h.
| inline |
Set the inlier distance threshold for the internal RANSAC outlier rejection loop.
The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold. The value is set by default to 0.05m.
[in] | inlier_threshold | the inlier distance threshold for the internal RANSAC outlier rejection loop |
Definition at line 328 of file registration.h.
| inline |
Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding).
[in] | tree | a pointer to the spatial search object. |
[in] | force_no_recompute | If set to true, this tree will NEVER be recomputed, regardless of calls to setInputSource. Only use if you are extremely confident that the tree will be set correctly. |
Definition at line 251 of file registration.h.
| inline |
Provide a pointer to the search object used to find correspondences in the target cloud.
[in] | tree | a pointer to the spatial search object. |
[in] | force_no_recompute | If set to true, this tree will NEVER be recomputed, regardless of calls to setInputTarget. Only use if you are confident that the tree will be set correctly. |
Definition at line 227 of file registration.h.
| inline |
Set the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.
[in] | epsilon | the transformation epsilon in order for an optimization to be considered as having converged to the final solution. |
Definition at line 370 of file registration.h.
| inline |
Provide a pointer to the transformation estimation object.
(e.g., SVD, point to plane etc.)
[in] | te | is the pointer to the corresponding transformation estimation object |
Code example:
Definition at line 157 of file registration.h.
| inline |
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.
[in] | epsilon | the transformation rotation epsilon in order for an optimization to be considered as having converged to the final solution (epsilon is the cos(angle) in a axis-angle representation). |
Definition at line 392 of file registration.h.
| protected |
Holds internal convergence state, given user parameters.
Definition at line 623 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::hasConverged().
| protected |
The maximum distance threshold between two correspondent points in source <-> target.
If the distance is larger than this threshold, the points will be ignored in the alignment process.
Definition at line 613 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getMaxCorrespondenceDistance(), and pcl::Registration< PointSource, PointTarget >::setMaxCorrespondenceDistance().
| protected |
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud.
Definition at line 639 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setCorrespondenceEstimation().
| protected |
The list of correspondence rejectors to use.
Definition at line 642 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::addCorrespondenceRejector(), pcl::Registration< PointSource, PointTarget >::clearCorrespondenceRejectors(), pcl::Registration< PointSource, PointTarget >::getCorrespondenceRejectors(), and pcl::Registration< PointSource, PointTarget >::removeCorrespondenceRejector().
| protected |
The set of correspondences determined at this ICP step.
Definition at line 631 of file registration.h.
| protected |
The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged.
The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences.
Definition at line 607 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getEuclideanFitnessEpsilon(), and pcl::Registration< PointSource, PointTarget >::setEuclideanFitnessEpsilon().
| protected |
The final transformation matrix estimated by the registration method after N iterations.
Definition at line 583 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getFinalTransformation().
| protected |
A flag which, if set, means the tree operating on the target cloud will never be recomputed.
Definition at line 654 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodTarget().
| protected |
A flag which, if set, means the tree operating on the source cloud will never be recomputed.
Definition at line 658 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().
| protected |
The inlier distance threshold for the internal RANSAC outlier rejection loop.
The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold. The default value is 0.05.
Definition at line 620 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getRANSACOutlierRejectionThreshold(), and pcl::Registration< PointSource, PointTarget >::setRANSACOutlierRejectionThreshold().
| protected |
The maximum number of iterations the internal optimization should run for.
The default value is 10.
Definition at line 573 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getMaximumIterations(), and pcl::Registration< PointSource, PointTarget >::setMaximumIterations().
| protected |
The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.
The default value is 3.
Definition at line 628 of file registration.h.
| protected |
The number of iterations the internal optimization ran for (used internally).
Definition at line 568 of file registration.h.
| protected |
The previous transformation matrix estimated by the registration method (used internally).
Definition at line 590 of file registration.h.
| protected |
The number of iterations RANSAC should run for.
Definition at line 576 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getRANSACIterations(), and pcl::Registration< PointSource, PointTarget >::setRANSACIterations().
| protected |
The registration method name.
Definition at line 558 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getClassName().
| protected |
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again.
This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method is called.
Definition at line 651 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().
| protected |
The input point cloud dataset target.
Definition at line 579 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getInputTarget().
| protected |
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again.
This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method is called.
Definition at line 647 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodTarget().
| protected |
The transformation matrix estimated by the registration method.
Definition at line 586 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getLastIncrementalTransformation().
| protected |
The maximum difference between two consecutive transformations in order to consider convergence (user defined).
Definition at line 595 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getTransformationEpsilon(), and pcl::Registration< PointSource, PointTarget >::setTransformationEpsilon().
| protected |
A TransformationEstimation object, used to calculate the 4x4 rigid transformation.
Definition at line 635 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::setTransformationEstimation().
| protected |
The maximum rotation difference between two consecutive transformations in order to consider convergence (user defined).
Definition at line 600 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getTransformationRotationEpsilon(), and pcl::Registration< PointSource, PointTarget >::setTransformationRotationEpsilon().
| protected |
A pointer to the spatial search object.
Definition at line 561 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getSearchMethodTarget(), pcl::Registration< PointSource, PointTarget >::searchForNeighbors(), and pcl::Registration< PointSource, PointTarget >::setSearchMethodTarget().
| protected |
A pointer to the spatial search object of the source.
Definition at line 564 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::getSearchMethodSource(), and pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().
| protected |
Callback function to update intermediate source point cloud position during it's registration to the target point cloud.
Definition at line 663 of file registration.h.
Referenced by pcl::Registration< PointSource, PointTarget >::registerVisualizationCallback().
© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_registration.html