Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
pcl::Registration< PointSource, PointTarget, Scalar > Class Template Reference

Registration represents the base registration class for general purpose, ICP-like methods. More...

#include <registration.h>

Inheritance diagram for pcl::Registration< PointSource, PointTarget, Scalar >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const Registration
< PointSource, PointTarget,
Scalar > > 
ConstPtr
typedef
pcl::registration::CorrespondenceEstimationBase
< PointSource, PointTarget,
Scalar
CorrespondenceEstimation
typedef
CorrespondenceEstimation::ConstPtr 
CorrespondenceEstimationConstPtr
typedef
CorrespondenceEstimation::Ptr 
CorrespondenceEstimationPtr
typedef
pcl::registration::CorrespondenceRejector::Ptr 
CorrespondenceRejectorPtr
typedef pcl::search::KdTree
< PointTarget > 
KdTree
typedef pcl::search::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef pcl::search::KdTree
< PointSource > 
KdTreeReciprocal
typedef KdTree::Ptr KdTreeReciprocalPtr
typedef Eigen::Matrix< Scalar, 4, 4 > Matrix4
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, Scalar > > 
Ptr
typedef
pcl::registration::TransformationEstimation
< PointSource, PointTarget,
Scalar
TransformationEstimation
typedef
TransformationEstimation::ConstPtr 
TransformationEstimationConstPtr
typedef
TransformationEstimation::Ptr 
TransformationEstimationPtr

Public Member Functions

void addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector)
 Add a new correspondence rejector to the list.
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 Matrix4 &guess)
 Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
void clearCorrespondenceRejectors ()
 Clear the list of correspondence rejectors.
const std::stringgetClassName () const
 Abstract class get name method.
std::vector
< CorrespondenceRejectorPtr
getCorrespondenceRejectors ()
 Get the list of correspondence rejectors.
double getEuclideanFitnessEpsilon ()
 Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user. See setEuclideanFitnessEpsilon.
Matrix4 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)
PointCloudSourceConstPtr const getInputSource ()
 Get a pointer to the input point cloud dataset target.
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target.
Matrix4 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.
KdTreeReciprocalPtr getSearchMethodSource () const
 Get a pointer to the search method used to find correspondences in the source cloud.
KdTreePtr getSearchMethodTarget () const
 Get a pointer to the search method used to find correspondences in the target cloud.
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.
bool initCompute ()
 Internal computation initalization.
bool initComputeReciprocal ()
 Internal computation when reciprocal lookup is needed.
 PCL_DEPRECATED (void setInputCloud(const PointCloudSourceConstPtr &cloud),"[pcl::registration::Registration::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
 PCL_DEPRECATED (PointCloudSourceConstPtr const getInputCloud(),"[pcl::registration::Registration::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
 Get a pointer to the input point cloud dataset target.
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.
bool removeCorrespondenceRejector (unsigned int i)
 Remove the i-th correspondence rejector in the list.
void setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce)
 Provide a pointer to the correspondence estimation object. (e.g., regular, reciprocal, normal shooting etc.)
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 setInputSource (const PointCloudSourceConstPtr &cloud)
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
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 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).
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.
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

virtual void computeTransformation (PointCloudSource &output, const Matrix4 &guess)=0
 Abstract transformation computation method with initial guess.
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.
CorrespondenceEstimationPtr correspondence_estimation_
 A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud.
std::vector
< CorrespondenceRejectorPtr
correspondence_rejectors_
 The list of correspondence rejectors to use.
CorrespondencesPtr correspondences_
 The set of correspondences determined at this ICP step.
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.
Matrix4 final_transformation_
 The final transformation matrix estimated by the registration method after N iterations.
bool force_no_recompute_
 A flag which, if set, means the tree operating on the target cloud will never be recomputed.
bool force_no_recompute_reciprocal_
 A flag which, if set, means the tree operating on the source cloud will never be recomputed.
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).
Matrix4 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.
bool source_cloud_updated_
 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.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.
bool target_cloud_updated_
 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.
Matrix4 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.
KdTreeReciprocalPtr tree_reciprocal_
 A pointer to the spatial search object of the source.
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 Attributes

PointRepresentationConstPtr point_representation_
 The point representation used (internal).

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class pcl::Registration< PointSource, PointTarget, Scalar >

Registration represents the base registration class for general purpose, ICP-like methods.

Author:
Radu B. Rusu, Michael Dixon

Definition at line 62 of file registration/include/pcl/registration/registration.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr< const Registration<PointSource, PointTarget, Scalar> > pcl::Registration< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimation
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef CorrespondenceEstimation::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef CorrespondenceEstimation::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::CorrespondenceRejector::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceRejectorPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::Registration< PointSource, PointTarget, Scalar >::KdTree
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::KdTreePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointSource> pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocal
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Eigen::Matrix<Scalar, 4, 4> pcl::Registration< PointSource, PointTarget, Scalar >::Matrix4
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointSource> pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSource
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointTarget> pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTarget
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::PointRepresentationConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr< Registration<PointSource, PointTarget, Scalar> > pcl::Registration< PointSource, PointTarget, Scalar >::Ptr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::TransformationEstimation<PointSource, PointTarget, Scalar> pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimation
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef TransformationEstimation::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef TransformationEstimation::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationPtr

Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::Registration< PointSource, PointTarget, Scalar >::Registration ( ) [inline]

Empty constructor.

Definition at line 101 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual pcl::Registration< PointSource, PointTarget, Scalar >::~Registration ( ) [inline, virtual]

destructor.

Definition at line 132 of file registration/include/pcl/registration/registration.h.


Member Function Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::addCorrespondenceRejector ( const CorrespondenceRejectorPtr rejector) [inline]

Add a new correspondence rejector to the list.

Parameters:
[in]rejectorthe new correspondence rejector to concatenate

Code example:

 CorrespondenceRejectorDistance rej;
 rej.setInputCloud<PointXYZ> (keypoints_src);
 rej.setInputTarget<PointXYZ> (keypoints_tgt);
 rej.setMaximumDistance (1);
 rej.setInputCorrespondences (all_correspondences);
 
 // or...

Definition at line 445 of file registration/include/pcl/registration/registration.h.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::align ( PointCloudSource output) [inline]

Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.

Parameters:
[out]outputthe resultant input transfomed point cloud dataset

Definition at line 184 of file registration.hpp.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::align ( PointCloudSource output,
const Matrix4 guess 
) [inline]

Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.

Parameters:
[out]outputthe resultant input transfomed point cloud dataset
[in]guessthe initial gross estimation of the transformation

Definition at line 191 of file registration.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::clearCorrespondenceRejectors ( ) [inline]

Clear the list of correspondence rejectors.

Definition at line 471 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::Registration< PointSource, PointTarget, Scalar >::computeTransformation ( PointCloudSource output,
const Matrix4 guess 
) [protected, pure virtual]

Abstract transformation computation method with initial guess.

Implemented in pcl::IterativeClosestPoint< PointSource, PointTarget, Scalar >.

template<typename PointSource, typename PointTarget, typename Scalar = float>
const std::string& pcl::Registration< PointSource, PointTarget, Scalar >::getClassName ( ) const [inline]

Abstract class get name method.

Definition at line 418 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::vector<CorrespondenceRejectorPtr> pcl::Registration< PointSource, PointTarget, Scalar >::getCorrespondenceRejectors ( ) [inline]

Get the list of correspondence rejectors.

Definition at line 452 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::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 355 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::getFinalTransformation ( ) [inline]

Get the final transformation matrix estimated by the registration method.

Definition at line 271 of file registration/include/pcl/registration/registration.h.

template<typename PointSource , typename PointTarget , typename Scalar >
double pcl::Registration< PointSource, PointTarget, Scalar >::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)

Parameters:
[in]max_rangemaximum allowable distance between a point and its correspondence in the target (default: double::max)

Definition at line 132 of file registration.hpp.

template<typename PointSource , typename PointTarget , typename Scalar >
double pcl::Registration< PointSource, PointTarget, Scalar >::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)

Parameters:
[in]distances_athe first set of distances between correspondences
[in]distances_bthe second set of distances between correspondences

Definition at line 120 of file registration.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudSourceConstPtr const pcl::Registration< PointSource, PointTarget, Scalar >::getInputSource ( ) [inline]

Get a pointer to the input point cloud dataset target.

Definition at line 200 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudTargetConstPtr const pcl::Registration< PointSource, PointTarget, Scalar >::getInputTarget ( ) [inline]

Get a pointer to the input point cloud dataset target.

Definition at line 210 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::getLastIncrementalTransformation ( ) [inline]

Get the last incremental transformation matrix estimated by the registration method.

Definition at line 275 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::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 323 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::getMaximumIterations ( ) [inline]

Get the maximum number of iterations the internal optimization should run for, as set by the user.

Definition at line 285 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getRANSACIterations ( ) [inline]

Get the number of iterations RANSAC should run for, as set by the user.

Definition at line 295 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getRANSACOutlierRejectionThreshold ( ) [inline]

Get the inlier distance threshold for the internal outlier rejection loop as set by the user.

Definition at line 309 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreeReciprocalPtr pcl::Registration< PointSource, PointTarget, Scalar >::getSearchMethodSource ( ) const [inline]

Get a pointer to the search method used to find correspondences in the source cloud.

Definition at line 264 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreePtr pcl::Registration< PointSource, PointTarget, Scalar >::getSearchMethodTarget ( ) const [inline]

Get a pointer to the search method used to find correspondences in the target cloud.

Definition at line 236 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationEpsilon ( ) [inline]

Get the transformation epsilon (maximum allowable difference between two consecutive transformations) as set by the user.

Definition at line 338 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::hasConverged ( ) [inline]

Return the state of convergence after the last align run.

Definition at line 399 of file registration/include/pcl/registration/registration.h.

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::Registration< PointSource, PointTarget, Scalar >::initCompute ( )

Internal computation initalization.

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 71 of file registration.hpp.

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::Registration< PointSource, PointTarget, Scalar >::initComputeReciprocal ( )

Internal computation when reciprocal lookup is needed.

Definition at line 102 of file registration.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::Registration< PointSource, PointTarget, Scalar >::PCL_DEPRECATED ( void   setInputCloudconst PointCloudSourceConstPtr &cloud,
" setInputCloud is deprecated. Please use setInputSource instead."  [pcl::registration::Registration::setInputCloud] 
)

Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud source
template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::Registration< PointSource, PointTarget, Scalar >::PCL_DEPRECATED ( PointCloudSourceConstPtr const   getInputCloud(),
" getInputCloud is deprecated. Please use getInputSource instead."  [pcl::registration::Registration::getInputCloud] 
)

Get a pointer to the input point cloud dataset target.

template<typename PointSource, typename PointTarget, typename Scalar = float>
template<typename FunctionSignature >
bool pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
[in]visualizerCallbackreference of the user callback function

Definition at line 371 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::removeCorrespondenceRejector ( unsigned int  i) [inline]

Remove the i-th correspondence rejector in the list.

Parameters:
[in]ithe position of the correspondence rejector in the list to remove

Definition at line 461 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
cloudthe point cloud dataset to use for nearest neighbor search
indexthe index of the query point
indicesthe resultant vector of indices representing the k-nearest neighbors
distancesthe resultant distances from the query point to the k-nearest neighbors

Definition at line 582 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setCorrespondenceEstimation ( const CorrespondenceEstimationPtr ce) [inline]

Provide a pointer to the correspondence estimation object. (e.g., regular, reciprocal, normal shooting etc.)

Parameters:
[in]ceis the pointer to the corresponding correspondence estimation object

Code example:

 CorrespondenceEstimation<PointXYZ, PointXYZ>::Ptr ce (new CorrespondenceEstimation<PointXYZ, PointXYZ>);
 ce->setInputSource (source);
 ce->setInputTarget (target);
 icp.setCorrespondenceEstimation (ce);
 // or...
 CorrespondenceEstimationNormalShooting<PointNormal, PointNormal, PointNormal>::Ptr cens (new CorrespondenceEstimationNormalShooting<PointNormal, PointNormal>);
 ce->setInputSource (source);
 ce->setInputTarget (target);
 ce->setSourceNormals (source);
 ce->setTargetNormals (target);
 icp.setCorrespondenceEstimation (cens);

Definition at line 174 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
[in]epsilonthe maximum allowed distance error before the algorithm will be considered to have converged

Definition at line 349 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::Registration< PointSource, PointTarget, Scalar >::setInputSource ( const PointCloudSourceConstPtr cloud) [inline, virtual]

Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud source

Reimplemented in pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >.

Definition at line 192 of file registration/include/pcl/registration/registration.h.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::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)

Parameters:
[in]cloudthe input point cloud target

Definition at line 58 of file registration.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
[in]distance_thresholdthe maximum distance threshold between a point and its nearest neighbor correspondent in order to be considered in the alignment process

Definition at line 317 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setMaximumIterations ( int  nr_iterations) [inline]

Set the maximum number of iterations the internal optimization should run for.

Parameters:
[in]nr_iterationsthe maximum number of iterations the internal optimization should run for

Definition at line 281 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setPointRepresentation ( const PointRepresentationConstPtr point_representation) [inline]

Provide a boost shared pointer to the PointRepresentation to be used when comparing points.

Parameters:
[in]point_representationthe PointRepresentation to be used by the k-D tree

Definition at line 361 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setRANSACIterations ( int  ransac_iterations) [inline]

Set the number of iterations RANSAC should run for.

Parameters:
[in]ransac_iterationsis the number of iterations RANSAC should run for

Definition at line 291 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
[in]inlier_thresholdthe inlier distance threshold for the internal RANSAC outlier rejection loop

Definition at line 305 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodSource ( const KdTreeReciprocalPtr tree,
bool  force_no_recompute = false 
) [inline]

Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding).

Parameters:
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf 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 249 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setSearchMethodTarget ( const KdTreePtr tree,
bool  force_no_recompute = false 
) [inline]

Provide a pointer to the search object used to find correspondences in the target cloud.

Parameters:
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf 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 221 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::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.

Parameters:
[in]epsilonthe transformation epsilon in order for an optimization to be considered as having converged to the final solution.

Definition at line 332 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setTransformationEstimation ( const TransformationEstimationPtr te) [inline]

Provide a pointer to the transformation estimation object. (e.g., SVD, point to plane etc.)

Parameters:
[in]teis the pointer to the corresponding transformation estimation object

Code example:

 TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>::Ptr trans_lls (new TransformationEstimationPointToPlaneLLS<PointXYZ, PointXYZ>);
 icp.setTransformationEstimation (trans_lls);
 // or...
 TransformationEstimationSVD<PointXYZ, PointXYZ>::Ptr trans_svd (new TransformationEstimationSVD<PointXYZ, PointXYZ>);
 icp.setTransformationEstimation (trans_svd);

Definition at line 150 of file registration/include/pcl/registration/registration.h.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::converged_ [protected]

Holds internal convergence state, given user parameters.

Definition at line 532 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::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 523 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
CorrespondenceEstimationPtr pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_estimation_ [protected]

A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud.

Definition at line 546 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::vector<CorrespondenceRejectorPtr> pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_ [protected]

The list of correspondence rejectors to use.

Definition at line 549 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
CorrespondencesPtr pcl::Registration< PointSource, PointTarget, Scalar >::correspondences_ [protected]

The set of correspondences determined at this ICP step.

Definition at line 540 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::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 518 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::final_transformation_ [protected]

The final transformation matrix estimated by the registration method after N iterations.

Definition at line 501 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_ [protected]

A flag which, if set, means the tree operating on the target cloud will never be recomputed.

Definition at line 561 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::force_no_recompute_reciprocal_ [protected]

A flag which, if set, means the tree operating on the source cloud will never be recomputed.

Definition at line 565 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::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 529 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::max_iterations_ [protected]

The maximum number of iterations the internal optimization should run for. The default value is 10.

Definition at line 492 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::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 537 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::nr_iterations_ [protected]

The number of iterations the internal optimization ran for (used internally).

Definition at line 487 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointRepresentationConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::point_representation_ [private]

The point representation used (internal).

Definition at line 597 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::previous_transformation_ [protected]

The previous transformation matrix estimated by the registration method (used internally).

Definition at line 507 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::ransac_iterations_ [protected]

The number of iterations RANSAC should run for.

Definition at line 495 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::string pcl::Registration< PointSource, PointTarget, Scalar >::reg_name_ [protected]

The registration method name.

Definition at line 478 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::source_cloud_updated_ [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 558 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudTargetConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::target_ [protected]

The input point cloud dataset target.

Definition at line 498 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::Registration< PointSource, PointTarget, Scalar >::target_cloud_updated_ [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 554 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::transformation_ [protected]

The transformation matrix estimated by the registration method.

Definition at line 504 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::transformation_epsilon_ [protected]

The maximum difference between two consecutive transformations in order to consider convergence (user defined).

Definition at line 512 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
TransformationEstimationPtr pcl::Registration< PointSource, PointTarget, Scalar >::transformation_estimation_ [protected]

A TransformationEstimation object, used to calculate the 4x4 rigid transformation.

Definition at line 543 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreePtr pcl::Registration< PointSource, PointTarget, Scalar >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 481 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreeReciprocalPtr pcl::Registration< PointSource, PointTarget, Scalar >::tree_reciprocal_ [protected]

A pointer to the spatial search object of the source.

Definition at line 484 of file registration/include/pcl/registration/registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
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, Scalar >::update_visualizer_ [protected]

Callback function to update intermediate source point cloud position during it's registration to the target point cloud.

Definition at line 573 of file registration/include/pcl/registration/registration.h.


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


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