Point Cloud Library (PCL)  1.8.1-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::Registration< PointSource, PointTarget, Scalar > Class Template Referenceabstract

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

#include <pcl/registration/registration.h>

+ Inheritance diagram for pcl::Registration< PointSource, PointTarget, Scalar >:

Public Types

typedef Eigen::Matrix< Scalar, 4, 4 > Matrix4
 
typedef boost::shared_ptr
< Registration< PointSource,
PointTarget, Scalar > > 
Ptr
 
typedef boost::shared_ptr
< const Registration
< PointSource, PointTarget,
Scalar > > 
ConstPtr
 
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 KdTreeReciprocal::Ptr KdTreeReciprocalPtr
 
typedef pcl::PointCloud
< PointSource > 
PointCloudSource
 
typedef PointCloudSource::Ptr PointCloudSourcePtr
 
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
 
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
 
typedef PointCloudTarget::Ptr PointCloudTargetPtr
 
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
 
typedef
KdTree::PointRepresentationConstPtr 
PointRepresentationConstPtr
 
typedef
pcl::registration::TransformationEstimation
< PointSource, PointTarget,
Scalar > 
TransformationEstimation
 
typedef
TransformationEstimation::Ptr 
TransformationEstimationPtr
 
typedef
TransformationEstimation::ConstPtr 
TransformationEstimationConstPtr
 
typedef
pcl::registration::CorrespondenceEstimationBase
< PointSource, PointTarget,
Scalar > 
CorrespondenceEstimation
 
typedef
CorrespondenceEstimation::Ptr 
CorrespondenceEstimationPtr
 
typedef
CorrespondenceEstimation::ConstPtr 
CorrespondenceEstimationConstPtr
 
- Public Types inherited from pcl::PCLBase< PointSource >
typedef pcl::PointCloud
< PointSource > 
PointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr
 
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
 

Public Member Functions

 Registration ()
 Empty constructor. More...
 
virtual ~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...
 
void setInputCloud (const PointCloudSourceConstPtr &cloud)
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target) More...
 
PointCloudSourceConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset target. 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...
 
PointCloudSourceConstPtr const 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...
 
PointCloudTargetConstPtr const 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...
 
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. More...
 
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) More...
 
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) More...
 
bool hasConverged ()
 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 initalization. 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 ()
 Destructor. More...
 
PointCloudConstPtr const 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 (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointSource & operator[] (size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

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. 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...
 
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. 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...
 

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.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

Definition at line 73 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimation

Definition at line 96 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef CorrespondenceEstimation::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationConstPtr

Definition at line 98 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef CorrespondenceEstimation::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceEstimationPtr

Definition at line 97 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::CorrespondenceRejector::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::CorrespondenceRejectorPtr

Definition at line 75 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::Registration< PointSource, PointTarget, Scalar >::KdTree

Definition at line 76 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::KdTreePtr

Definition at line 77 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointSource> pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocal

Definition at line 79 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTreeReciprocal::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr

Definition at line 80 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Eigen::Matrix<Scalar, 4, 4> pcl::Registration< PointSource, PointTarget, Scalar >::Matrix4

Definition at line 65 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointSource> pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSource

Definition at line 82 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr

Definition at line 84 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourcePtr

Definition at line 83 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointTarget> pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTarget

Definition at line 86 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr

Definition at line 88 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudTargetPtr

Definition at line 87 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::PointRepresentationConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr

Definition at line 90 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr< Registration<PointSource, PointTarget, Scalar> > pcl::Registration< PointSource, PointTarget, Scalar >::Ptr

Definition at line 72 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::registration::TransformationEstimation<PointSource, PointTarget, Scalar> pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimation

Definition at line 92 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef TransformationEstimation::ConstPtr pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationConstPtr

Definition at line 94 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef TransformationEstimation::Ptr pcl::Registration< PointSource, PointTarget, Scalar >::TransformationEstimationPtr

Definition at line 93 of file registration.h.

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.h.

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

destructor.

Definition at line 133 of file 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 464 of file 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 169 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 176 of file registration.hpp.

References pcl::PointCloud< T >::header, pcl::PointCloud< T >::height, pcl::PointCloud< T >::is_dense, pcl::PointCloud< T >::points, and pcl::PointCloud< T >::width.

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 490 of file registration.h.

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

Abstract transformation computation method with initial guess.

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

template<typename PointSource, typename PointTarget, typename Scalar = float>
const std::string& pcl::Registration< PointSource, PointTarget, Scalar >::getClassName ( ) const
inline
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 471 of file 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 374 of file 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 276 of file 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.

References pcl::PointCloud< T >::points, and pcl::transformPointCloud().

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 >
pcl::Registration< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr const pcl::Registration< PointSource, PointTarget, Scalar >::getInputCloud ( )

Get a pointer to the input point cloud dataset target.

Definition at line 51 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 205 of file 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 215 of file 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 280 of file 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 328 of file 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 290 of file 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 300 of file 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 314 of file 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 269 of file 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 241 of file registration.h.

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

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

Definition at line 343 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
double pcl::Registration< PointSource, PointTarget, Scalar >::getTransformationRotationEpsilon ( )
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 358 of file 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 418 of file registration.h.

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

Internal computation initalization.

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.

Referenced by pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >::computeTransformation().

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 390 of file registration.h.

Referenced by pcl::RegistrationVisualizer< PointSource, PointTarget >::setRegistration().

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 480 of file 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 
)
inlineprotected

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 606 of file 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 175 of file 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 368 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::Registration< PointSource, PointTarget, Scalar >::setInputCloud ( const PointCloudSourceConstPtr cloud)
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 from pcl::PCLBase< PointSource >.

Definition at line 43 of file registration.hpp.

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

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::IterativeClosestPoint< PointSource, PointTarget, Scalar >, pcl::GeneralizedIterativeClosestPoint< PointSource, PointTarget >, and pcl::JointIterativeClosestPoint< PointSource, PointTarget, Scalar >.

Definition at line 197 of file registration.h.

Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget >::setInputSource().

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::Registration< PointSource, PointTarget, Scalar >::setInputTarget ( const PointCloudTargetConstPtr cloud)
inlinevirtual
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 322 of file 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 286 of file 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 380 of file 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 296 of file 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 310 of file 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 254 of file 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 226 of file 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 translation squared 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 337 of file 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 151 of file registration.h.

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

Parameters
[in]epsilonthe 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 352 of file 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 556 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::hasConverged().

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 547 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getMaxCorrespondenceDistance(), and pcl::Registration< PointSource, PointTarget >::setMaxCorrespondenceDistance().

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 570 of file registration.h.

Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget >::IterativeClosestPoint(), and pcl::Registration< PointSource, PointTarget >::setCorrespondenceEstimation().

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::vector<CorrespondenceRejectorPtr> pcl::Registration< PointSource, PointTarget, Scalar >::correspondence_rejectors_
protected
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 564 of file registration.h.

Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget >::IterativeClosestPoint().

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 542 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getEuclideanFitnessEpsilon(), and pcl::Registration< PointSource, PointTarget >::setEuclideanFitnessEpsilon().

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 520 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getFinalTransformation().

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 585 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodTarget().

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 589 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().

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 553 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getRANSACOutlierRejectionThreshold(), and pcl::Registration< PointSource, PointTarget >::setRANSACOutlierRejectionThreshold().

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 511 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getMaximumIterations(), and pcl::Registration< PointSource, PointTarget >::setMaximumIterations().

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 561 of file registration.h.

Referenced by pcl::IterativeClosestPointNonLinear< PointSource, PointTarget, Scalar >::IterativeClosestPointNonLinear().

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 506 of file registration.h.

Referenced by pcl::IterativeClosestPoint< PointSource, PointTarget >::IterativeClosestPoint().

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 526 of file registration.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
int pcl::Registration< PointSource, PointTarget, Scalar >::ransac_iterations_
protected
template<typename PointSource, typename PointTarget, typename Scalar = float>
std::string pcl::Registration< PointSource, PointTarget, Scalar >::reg_name_
protected
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 582 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::setInputSource(), and pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().

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 517 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getInputTarget().

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 578 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::setSearchMethodTarget().

template<typename PointSource, typename PointTarget, typename Scalar = float>
Matrix4 pcl::Registration< PointSource, PointTarget, Scalar >::transformation_
protected
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 531 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getTransformationEpsilon(), and pcl::Registration< PointSource, PointTarget >::setTransformationEpsilon().

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

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

Definition at line 536 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getTransformationRotationEpsilon(), and pcl::Registration< PointSource, PointTarget >::setTransformationRotationEpsilon().

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreePtr pcl::Registration< PointSource, PointTarget, Scalar >::tree_
protected
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 503 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::getSearchMethodSource(), and pcl::Registration< PointSource, PointTarget >::setSearchMethodSource().

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 597 of file registration.h.

Referenced by pcl::Registration< PointSource, PointTarget >::registerVisualizationCallback().


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