Registration represents the base registration class. All 3D registration methods should inherit from this class. More...
#include <registration.h>
Public Types | |
typedef boost::shared_ptr < const Registration < PointSource, PointTarget > > | ConstPtr |
typedef pcl::KdTree< PointTarget > | KdTree |
typedef pcl::KdTree < PointTarget >::Ptr | KdTreePtr |
typedef pcl::PointCloud < PointSource > | PointCloudSource |
typedef PointCloudSource::ConstPtr | PointCloudSourceConstPtr |
typedef PointCloudSource::Ptr | PointCloudSourcePtr |
typedef pcl::PointCloud < PointTarget > | PointCloudTarget |
typedef PointCloudTarget::ConstPtr | PointCloudTargetConstPtr |
typedef PointCloudTarget::Ptr | PointCloudTargetPtr |
typedef KdTree::PointRepresentationConstPtr | PointRepresentationConstPtr |
typedef boost::shared_ptr < Registration< PointSource, PointTarget > > | Ptr |
typedef pcl::registration::TransformationEstimation < PointSource, PointTarget > | TransformationEstimation |
typedef TransformationEstimation::ConstPtr | TransformationEstimationConstPtr |
typedef TransformationEstimation::Ptr | TransformationEstimationPtr |
Public Member Functions | |
void | align (PointCloudSource &output) |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. | |
void | align (PointCloudSource &output, const Eigen::Matrix4f &guess) |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. | |
const std::string & | getClassName () const |
Abstract class get name method. | |
double | getEuclideanFitnessEpsilon () |
Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user. See setEuclideanFitnessEpsilon. | |
Eigen::Matrix4f | getFinalTransformation () |
Get the final transformation matrix estimated by the registration method. | |
double | getFitnessScore (double max_range=std::numeric_limits< double >::max()) |
Obtain the Euclidean fitness score (e.g., sum of squared distances from the source to the target) | |
double | getFitnessScore (const std::vector< float > &distances_a, const std::vector< float > &distances_b) |
Obtain the Euclidean fitness score (e.g., sum of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points) | |
PointCloudTargetConstPtr const | getInputTarget () |
Get a pointer to the input point cloud dataset target. | |
Eigen::Matrix4f | getLastIncrementalTransformation () |
Get the last incremental transformation matrix estimated by the registration method. | |
double | getMaxCorrespondenceDistance () |
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. | |
int | getMaximumIterations () |
Get the maximum number of iterations the internal optimization should run for, as set by the user. | |
double | getRANSACIterations () |
Get the number of iterations RANSAC should run for, as set by the user. | |
double | getRANSACOutlierRejectionThreshold () |
Get the inlier distance threshold for the internal outlier rejection loop as set by the user. | |
double | getTransformationEpsilon () |
Get the transformation epsilon (maximum allowable difference between two consecutive transformations) as set by the user. | |
bool | hasConverged () |
Return the state of convergence after the last align run. | |
template<typename FunctionSignature > | |
bool | registerVisualizationCallback (boost::function< FunctionSignature > &visualizerCallback) |
Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration. | |
Registration () | |
Empty constructor. | |
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. The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences. | |
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) | |
void | setMaxCorrespondenceDistance (double distance_threshold) |
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. | |
void | setMaximumIterations (int nr_iterations) |
Set the maximum number of iterations the internal optimization should run for. | |
void | setPointRepresentation (const PointRepresentationConstPtr &point_representation) |
Provide a boost shared pointer to the PointRepresentation to be used when comparing points. | |
void | setRANSACIterations (int ransac_iterations) |
Set the number of iterations RANSAC should run for. | |
void | setRANSACOutlierRejectionThreshold (double inlier_threshold) |
Set the inlier distance threshold for the internal RANSAC outlier rejection loop. | |
void | setTransformationEpsilon (double epsilon) |
Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. | |
void | setTransformationEstimation (const TransformationEstimationPtr &te) |
Provide a pointer to the transformation estimation object. (e.g., SVD, point to plane etc.) | |
virtual | ~Registration () |
destructor. | |
Protected Member Functions | |
bool | searchForNeighbors (const PointCloudSource &cloud, int index, std::vector< int > &indices, std::vector< float > &distances) |
Search for the closest nearest neighbor of a given point. | |
Protected Attributes | |
bool | converged_ |
Holds internal convergence state, given user parameters. | |
double | corr_dist_threshold_ |
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 alignement process. | |
std::vector< float > | correspondence_distances_ |
A set of distances between the points in the source cloud and their correspondences in the target. | |
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. The error is estimated as the sum of the differences between correspondences in an Euclidean sense, divided by the number of correspondences. | |
Eigen::Matrix4f | final_transformation_ |
The final transformation matrix estimated by the registration method after N iterations. | |
double | inlier_threshold_ |
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. | |
int | max_iterations_ |
The maximum number of iterations the internal optimization should run for. The default value is 10. | |
int | min_number_correspondences_ |
The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation. The default value is 3. | |
int | nr_iterations_ |
The number of iterations the internal optimization ran for (used internally). | |
Eigen::Matrix4f | previous_transformation_ |
The previous transformation matrix estimated by the registration method (used internally). | |
int | ransac_iterations_ |
The number of iterations RANSAC should run for. | |
std::string | reg_name_ |
The registration method name. | |
PointCloudTargetConstPtr | target_ |
The input point cloud dataset target. | |
Eigen::Matrix4f | transformation_ |
The transformation matrix estimated by the registration method. | |
double | transformation_epsilon_ |
The maximum difference between two consecutive transformations in order to consider convergence (user defined). | |
TransformationEstimationPtr | transformation_estimation_ |
A TransformationEstimation object, used to calculate the 4x4 rigid transformation. | |
KdTreePtr | tree_ |
A pointer to the spatial search object. | |
boost::function< void(const pcl::PointCloud< PointSource > &cloud_src, const std::vector < int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector < int > &indices_tgt)> | update_visualizer_ |
Callback function to update intermediate source point cloud position during it's registration to the target point cloud. | |
Private Member Functions | |
virtual void | computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)=0 |
Abstract transformation computation method with initial guess. | |
Private Attributes | |
PointRepresentationConstPtr | point_representation_ |
The point representation used (internal). |
Registration represents the base registration class. All 3D registration methods should inherit from this class.
Definition at line 61 of file registration/include/pcl/registration/registration.h.
typedef boost::shared_ptr< const Registration<PointSource, PointTarget> > pcl::Registration< PointSource, PointTarget >::ConstPtr |
Definition at line 70 of file registration/include/pcl/registration/registration.h.
typedef pcl::KdTree<PointTarget> pcl::Registration< PointSource, PointTarget >::KdTree |
Definition at line 72 of file registration/include/pcl/registration/registration.h.
typedef pcl::KdTree<PointTarget>::Ptr pcl::Registration< PointSource, PointTarget >::KdTreePtr |
Definition at line 73 of file registration/include/pcl/registration/registration.h.
typedef pcl::PointCloud<PointSource> pcl::Registration< PointSource, PointTarget >::PointCloudSource |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::SampleConsensusInitialAlignment< pcl::PointXYZ, pcl::PointXYZ, pcl::FPFHSignature33 >.
Definition at line 75 of file registration/include/pcl/registration/registration.h.
typedef PointCloudSource::ConstPtr pcl::Registration< PointSource, PointTarget >::PointCloudSourceConstPtr |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::SampleConsensusInitialAlignment< pcl::PointXYZ, pcl::PointXYZ, pcl::FPFHSignature33 >.
Definition at line 77 of file registration/include/pcl/registration/registration.h.
typedef PointCloudSource::Ptr pcl::Registration< PointSource, PointTarget >::PointCloudSourcePtr |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::SampleConsensusInitialAlignment< pcl::PointXYZ, pcl::PointXYZ, pcl::FPFHSignature33 >.
Definition at line 76 of file registration/include/pcl/registration/registration.h.
typedef pcl::PointCloud<PointTarget> pcl::Registration< PointSource, PointTarget >::PointCloudTarget |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, pcl::IterativeClosestPoint< PointSource, PointTarget >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, and pcl::SampleConsensusInitialAlignment< pcl::PointXYZ, pcl::PointXYZ, pcl::FPFHSignature33 >.
Definition at line 79 of file registration/include/pcl/registration/registration.h.
typedef PointCloudTarget::ConstPtr pcl::Registration< PointSource, PointTarget >::PointCloudTargetConstPtr |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, and pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 81 of file registration/include/pcl/registration/registration.h.
typedef PointCloudTarget::Ptr pcl::Registration< PointSource, PointTarget >::PointCloudTargetPtr |
Reimplemented in pcl::PPFRegistration< PointSource, PointTarget >, and pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.
Definition at line 80 of file registration/include/pcl/registration/registration.h.
typedef KdTree::PointRepresentationConstPtr pcl::Registration< PointSource, PointTarget >::PointRepresentationConstPtr |
Definition at line 83 of file registration/include/pcl/registration/registration.h.
typedef boost::shared_ptr< Registration<PointSource, PointTarget> > pcl::Registration< PointSource, PointTarget >::Ptr |
Definition at line 69 of file registration/include/pcl/registration/registration.h.
typedef pcl::registration::TransformationEstimation<PointSource, PointTarget> pcl::Registration< PointSource, PointTarget >::TransformationEstimation |
Definition at line 85 of file registration/include/pcl/registration/registration.h.
typedef TransformationEstimation::ConstPtr pcl::Registration< PointSource, PointTarget >::TransformationEstimationConstPtr |
Definition at line 87 of file registration/include/pcl/registration/registration.h.
typedef TransformationEstimation::Ptr pcl::Registration< PointSource, PointTarget >::TransformationEstimationPtr |
Definition at line 86 of file registration/include/pcl/registration/registration.h.
pcl::Registration< PointSource, PointTarget >::Registration | ( | ) | [inline] |
Empty constructor.
Definition at line 90 of file registration/include/pcl/registration/registration.h.
virtual pcl::Registration< PointSource, PointTarget >::~Registration | ( | ) | [inline, virtual] |
destructor.
Definition at line 113 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::align | ( | PointCloudSource & | output | ) | [inline] |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
output | the resultant input transfomed point cloud dataset |
Definition at line 113 of file registration.hpp.
void pcl::Registration< PointSource, PointTarget >::align | ( | PointCloudSource & | output, |
const Eigen::Matrix4f & | guess | ||
) | [inline] |
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
output | the resultant input transfomed point cloud dataset |
guess | the initial gross estimation of the transformation |
Definition at line 120 of file registration.hpp.
virtual void pcl::Registration< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output, |
const Eigen::Matrix4f & | guess | ||
) | [private, pure virtual] |
Abstract transformation computation method with initial guess.
Implemented in pcl::PPFRegistration< PointSource, PointTarget >, pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >, pcl::IterativeClosestPoint< PointSource, PointTarget >, and RegistrationWrapper< PointSource, PointTarget >.
const std::string& pcl::Registration< PointSource, PointTarget >::getClassName | ( | ) | const [inline] |
Abstract class get name method.
Definition at line 280 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getEuclideanFitnessEpsilon | ( | ) | [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 217 of file registration/include/pcl/registration/registration.h.
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::getFinalTransformation | ( | ) | [inline] |
Get the final transformation matrix estimated by the registration method.
Definition at line 133 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getFitnessScore | ( | double | max_range = std::numeric_limits<double>::max () | ) | [inline] |
Obtain the Euclidean fitness score (e.g., sum of squared distances from the source to the target)
max_range | maximum allowable distance between a point and its correspondence in the target (default: double::max) |
Definition at line 72 of file registration.hpp.
double pcl::Registration< PointSource, PointTarget >::getFitnessScore | ( | const std::vector< float > & | distances_a, |
const std::vector< float > & | distances_b | ||
) | [inline] |
Obtain the Euclidean fitness score (e.g., sum 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 61 of file registration.hpp.
PointCloudTargetConstPtr const pcl::Registration< PointSource, PointTarget >::getInputTarget | ( | ) | [inline] |
Get a pointer to the input point cloud dataset target.
Definition at line 129 of file registration/include/pcl/registration/registration.h.
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::getLastIncrementalTransformation | ( | ) | [inline] |
Get the last incremental transformation matrix estimated by the registration method.
Definition at line 137 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getMaxCorrespondenceDistance | ( | ) | [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 185 of file registration/include/pcl/registration/registration.h.
int pcl::Registration< PointSource, PointTarget >::getMaximumIterations | ( | ) | [inline] |
Get the maximum number of iterations the internal optimization should run for, as set by the user.
Definition at line 147 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getRANSACIterations | ( | ) | [inline] |
Get the number of iterations RANSAC should run for, as set by the user.
Definition at line 157 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getRANSACOutlierRejectionThreshold | ( | ) | [inline] |
Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
Definition at line 171 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::getTransformationEpsilon | ( | ) | [inline] |
Get the transformation epsilon (maximum allowable difference between two consecutive transformations) as set by the user.
Definition at line 200 of file registration/include/pcl/registration/registration.h.
bool pcl::Registration< PointSource, PointTarget >::hasConverged | ( | ) | [inline] |
Return the state of convergence after the last align run.
Definition at line 261 of file registration/include/pcl/registration/registration.h.
bool pcl::Registration< PointSource, PointTarget >::registerVisualizationCallback | ( | boost::function< FunctionSignature > & | visualizerCallback | ) | [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 233 of file registration/include/pcl/registration/registration.h.
bool pcl::Registration< PointSource, PointTarget >::searchForNeighbors | ( | const PointCloudSource & | cloud, |
int | index, | ||
std::vector< int > & | indices, | ||
std::vector< float > & | distances | ||
) | [inline, protected] |
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 365 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setEuclideanFitnessEpsilon | ( | double | epsilon | ) | [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.
epsilon | the maximum allowed distance error before the algorithm will be considered to have converged |
Definition at line 211 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setInputTarget | ( | const PointCloudTargetConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
cloud | the input point cloud target |
Definition at line 42 of file registration.hpp.
void pcl::Registration< PointSource, PointTarget >::setMaxCorrespondenceDistance | ( | double | distance_threshold | ) | [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.
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 179 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setMaximumIterations | ( | int | nr_iterations | ) | [inline] |
Set the maximum number of iterations the internal optimization should run for.
nr_iterations | the maximum number of iterations the internal optimization should run for |
Definition at line 143 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setPointRepresentation | ( | const PointRepresentationConstPtr & | point_representation | ) | [inline] |
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
point_representation | the PointRepresentation to be used by the k-D tree |
Definition at line 223 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setRANSACIterations | ( | int | ransac_iterations | ) | [inline] |
Set the number of iterations RANSAC should run for.
ransac_iterations | is the number of iterations RANSAC should run for |
Definition at line 153 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setRANSACOutlierRejectionThreshold | ( | double | inlier_threshold | ) | [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.
inlier_threshold | the inlier distance threshold for the internal RANSAC outlier rejection loop |
Definition at line 167 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setTransformationEpsilon | ( | double | epsilon | ) | [inline] |
Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.
epsilon | the transformation epsilon in order for an optimization to be considered as having converged to the final solution. |
Definition at line 194 of file registration/include/pcl/registration/registration.h.
void pcl::Registration< PointSource, PointTarget >::setTransformationEstimation | ( | const TransformationEstimationPtr & | te | ) | [inline] |
Provide a pointer to the transformation estimation object. (e.g., SVD, point to plane etc.)
te | is the pointer to the corresponding transformation estimation object |
Definition at line 119 of file registration/include/pcl/registration/registration.h.
bool pcl::Registration< PointSource, PointTarget >::converged_ [protected] |
Holds internal convergence state, given user parameters.
Definition at line 335 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::corr_dist_threshold_ [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 alignement process.
Definition at line 326 of file registration/include/pcl/registration/registration.h.
std::vector<float> pcl::Registration< PointSource, PointTarget >::correspondence_distances_ [protected] |
A set of distances between the points in the source cloud and their correspondences in the target.
Definition at line 345 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::euclidean_fitness_epsilon_ [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 321 of file registration/include/pcl/registration/registration.h.
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::final_transformation_ [protected] |
The final transformation matrix estimated by the registration method after N iterations.
Definition at line 304 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::inlier_threshold_ [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 332 of file registration/include/pcl/registration/registration.h.
int pcl::Registration< PointSource, PointTarget >::max_iterations_ [protected] |
The maximum number of iterations the internal optimization should run for. The default value is 10.
Definition at line 295 of file registration/include/pcl/registration/registration.h.
int pcl::Registration< PointSource, PointTarget >::min_number_correspondences_ [protected] |
The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation. The default value is 3.
Definition at line 340 of file registration/include/pcl/registration/registration.h.
int pcl::Registration< PointSource, PointTarget >::nr_iterations_ [protected] |
The number of iterations the internal optimization ran for (used internally).
Definition at line 290 of file registration/include/pcl/registration/registration.h.
PointRepresentationConstPtr pcl::Registration< PointSource, PointTarget >::point_representation_ [private] |
The point representation used (internal).
Definition at line 381 of file registration/include/pcl/registration/registration.h.
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::previous_transformation_ [protected] |
The previous transformation matrix estimated by the registration method (used internally).
Definition at line 310 of file registration/include/pcl/registration/registration.h.
int pcl::Registration< PointSource, PointTarget >::ransac_iterations_ [protected] |
The number of iterations RANSAC should run for.
Definition at line 298 of file registration/include/pcl/registration/registration.h.
std::string pcl::Registration< PointSource, PointTarget >::reg_name_ [protected] |
The registration method name.
Definition at line 284 of file registration/include/pcl/registration/registration.h.
PointCloudTargetConstPtr pcl::Registration< PointSource, PointTarget >::target_ [protected] |
The input point cloud dataset target.
Definition at line 301 of file registration/include/pcl/registration/registration.h.
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::transformation_ [protected] |
The transformation matrix estimated by the registration method.
Definition at line 307 of file registration/include/pcl/registration/registration.h.
double pcl::Registration< PointSource, PointTarget >::transformation_epsilon_ [protected] |
The maximum difference between two consecutive transformations in order to consider convergence (user defined).
Definition at line 315 of file registration/include/pcl/registration/registration.h.
TransformationEstimationPtr pcl::Registration< PointSource, PointTarget >::transformation_estimation_ [protected] |
A TransformationEstimation object, used to calculate the 4x4 rigid transformation.
Definition at line 348 of file registration/include/pcl/registration/registration.h.
KdTreePtr pcl::Registration< PointSource, PointTarget >::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 287 of file registration/include/pcl/registration/registration.h.
boost::function<void(const pcl::PointCloud<PointSource> &cloud_src, const std::vector<int> &indices_src, const pcl::PointCloud<PointTarget> &cloud_tgt, const std::vector<int> &indices_tgt)> pcl::Registration< PointSource, PointTarget >::update_visualizer_ [protected] |
Callback function to update intermediate source point cloud position during it's registration to the target point cloud.
Definition at line 356 of file registration/include/pcl/registration/registration.h.