pcl::Registration< PointSource, PointTarget > Class Template Reference

Registration represents the base registration class. All 3D registration methods should inherit from this class. More...

#include <registration.h>

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

List of all members.

Classes

class  FeatureContainer
 An inner class containing pointers to the source and target feature clouds along with the KdTree and the parameters needed to perform the correspondence search. This class extends FeatureContainerInterface, which contains abstract methods for any methods that do not depend on the FeatureType --- these methods can thus be called from a pointer to FeatureContainerInterface without casting to the derived class. More...
class  FeatureContainerInterface

Public Types

typedef std::map< std::string,
boost::shared_ptr
< FeatureContainerInterface > > 
FeaturesMap
typedef pcl::KdTree< PointTarget > KdTree
typedef pcl::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef pcl::PointCloud
< PointSource > 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef
KdTree::PointRepresentationConstPtr 
PointRepresentationConstPtr

Public Member Functions

void align (PointCloudSource &output)
 Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
Eigen::Matrix4f getFinalTransformation ()
 Get the final transformation matrix estimated by the registration method.
double getFitnessScore (double max_range=std::numeric_limits< double >::max())
 Obtain the fitness score (e.g., sum of squared distances from the source to the target).
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target.
Eigen::Matrix4f getLastIncrementalTransformation ()
 Get the last incremental transformation matrix estimated by the registration method.
double getMaxCorrespondenceDistance ()
 Get the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.
int getMaximumIterations ()
 Get the maximum number of iterations the internal optimization should run for, as set by the user.
double getRANSACOutlierRejectionThreshold ()
 Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
template<typename FeatureType >
pcl::PointCloud< FeatureType >
::ConstPtr 
getSourceFeature (std::string key)
 Get a pointer to the source cloud's feature descriptors, specified by the given key.
template<typename FeatureType >
pcl::PointCloud< FeatureType >
::ConstPtr 
getTargetFeature (std::string key)
 Get a pointer to the source cloud's feature descriptors, specified by the given key.
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.
 Registration ()
 Empty constructor.
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).
template<typename FeatureType >
void setKSearch (const typename pcl::KdTree< FeatureType >::Ptr &tree, int k, std::string key)
 Use k-nearest-neighbors as the search method when finding correspondences for the feature associated with the provided key.
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.
template<typename FeatureType >
void setRadiusSearch (const typename pcl::KdTree< FeatureType >::Ptr &tree, float r, std::string key)
 Use radius-search as the search method when finding correspondences for the feature associated with the provided key.
void setRANSACOutlierRejectionThreshold (double inlier_threshold)
 Set the inlier distance threshold for the internal RANSAC outlier rejection loop.
template<typename FeatureType >
void setSourceFeature (const typename pcl::PointCloud< FeatureType >::ConstPtr &source_feature, std::string key)
 Provide a pointer to a cloud of feature descriptors associated with the source point cloud.
template<typename FeatureType >
void setTargetFeature (const typename pcl::PointCloud< FeatureType >::ConstPtr &target_feature, std::string key)
 Provide a pointer to a cloud of feature descriptors associated with the target point 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.

Protected Member Functions

void findFeatureCorrespondences (int index, std::vector< int > &correspondence_indices)
 Find the indices of the points in the target cloud whose features correspond with the features of the given point in the source cloud.
const std::string & getClassName () const
 Abstract class get name method.
bool hasValidFeatures ()
 Test that all features are valid (i.e., does each key have a valid source cloud, target cloud, and search method).
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 not be ignored in the alignement process.
Eigen::Matrix4f final_transformation_
 The final transformation matrix estimated by the registration method after N iterations.
double inlier_threshold_
 The inlier distance threshold for the internal RANSAC outlier rejection loop. The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold.
int max_iterations_
 The maximum number of iterations the internal optimization should run for.
int min_number_correspondences_
 The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.
int nr_iterations_
 The number of iterations the internal optimization ran for (used internally).
Eigen::Matrix4f previous_transformation_
 The previous transformation matrix estimated by the registration method (used internally).
std::string reg_name_
 The registration method name.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.
Eigen::Matrix4f transformation_
 The transformation matrix estimated by the registration method.
double transformation_epsilon_
 The maximum difference between two consecutive transformations in order to consider convergence (user defined).
KdTreePtr tree_
 A pointer to the spatial search object.

Private Member Functions

virtual void computeTransformation (PointCloudSource &output)=0
 Abstract transformation computation method.

Private Attributes

FeaturesMap features_map_
 An STL map containing features to use when performing the correspondence search.
PointRepresentationConstPtr point_representation_
 The number of K nearest neighbors to use for each point.

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::Registration< PointSource, PointTarget >

Registration represents the base registration class. All 3D registration methods should inherit from this class.

Author:
Radu Bogdan Rusu, Michael Dixon

Definition at line 97 of file registration.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef std::map<std::string, boost::shared_ptr<FeatureContainerInterface> > pcl::Registration< PointSource, PointTarget >::FeaturesMap

Definition at line 120 of file registration.h.

template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget> pcl::Registration< PointSource, PointTarget >::KdTree

Definition at line 107 of file registration.h.

template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget>::Ptr pcl::Registration< PointSource, PointTarget >::KdTreePtr

Definition at line 108 of file registration.h.

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> pcl::Registration< PointSource, PointTarget >::PointCloudSource
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::Registration< PointSource, PointTarget >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::Registration< PointSource, PointTarget >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> pcl::Registration< PointSource, PointTarget >::PointCloudTarget
template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::ConstPtr pcl::Registration< PointSource, PointTarget >::PointCloudTargetConstPtr

Definition at line 116 of file registration.h.

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

Definition at line 115 of file registration.h.

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

Definition at line 118 of file registration.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 123 of file registration.h.


Member Function Documentation

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

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

Parameters:
output the resultant input transfomed point cloud dataset

Definition at line 397 of file registration.hpp.

template<typename PointSource, typename PointTarget>
virtual void pcl::Registration< PointSource, PointTarget >::computeTransformation ( PointCloudSource output  )  [private, pure virtual]
template<typename PointSource , typename PointTarget >
void pcl::Registration< PointSource, PointTarget >::findFeatureCorrespondences ( int  index,
std::vector< int > &  correspondence_indices 
) [inline, protected]

Find the indices of the points in the target cloud whose features correspond with the features of the given point in the source cloud.

Parameters:
index the index of the query point (in the source cloud)
correspondence_indices the resultant vector of indices representing the query's corresponding features (in the target cloud)

Definition at line 318 of file registration.hpp.

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

Abstract class get name method.

Definition at line 356 of file registration.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::getFinalTransformation (  )  [inline]

Get the final transformation matrix estimated by the registration method.

Definition at line 190 of file registration.h.

template<typename PointSource , typename PointTarget >
double pcl::Registration< PointSource, PointTarget >::getFitnessScore ( double  max_range = std::numeric_limits<double>::max ()  )  [inline]

Obtain the fitness score (e.g., sum of squared distances from the source to the target).

Parameters:
max_range maximum allowable distance between a point and its correspondent neighbor in the target (default: double::max)

Definition at line 356 of file registration.hpp.

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

Get a pointer to the input point cloud dataset target.

Definition at line 142 of file registration.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::getLastIncrementalTransformation (  )  [inline]

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

Definition at line 194 of file registration.h.

template<typename PointSource, typename PointTarget>
double pcl::Registration< PointSource, PointTarget >::getMaxCorrespondenceDistance (  )  [inline]

Get the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.

Definition at line 232 of file registration.h.

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

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

Definition at line 204 of file registration.h.

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

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

Definition at line 218 of file registration.h.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
pcl::PointCloud< FeatureType >::ConstPtr pcl::Registration< PointSource, PointTarget >::getSourceFeature ( std::string  key  )  [inline]

Get a pointer to the source cloud's feature descriptors, specified by the given key.

Parameters:
key a string that uniquely identifies the feature (must match the key provided by setSourceFeature)

Definition at line 228 of file registration.hpp.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
pcl::PointCloud< FeatureType >::ConstPtr pcl::Registration< PointSource, PointTarget >::getTargetFeature ( std::string  key  )  [inline]

Get a pointer to the source cloud's feature descriptors, specified by the given key.

Parameters:
key a string that uniquely identifies the feature (must match the key provided by setTargetFeature)

Definition at line 256 of file registration.hpp.

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

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

Definition at line 246 of file registration.h.

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

Return the state of convergence after the last align run.

Definition at line 266 of file registration.h.

template<typename PointSource , typename PointTarget >
bool pcl::Registration< PointSource, PointTarget >::hasValidFeatures (  )  [inline, protected]

Test that all features are valid (i.e., does each key have a valid source cloud, target cloud, and search method).

Definition at line 299 of file registration.hpp.

template<typename PointSource, typename PointTarget>
bool pcl::Registration< PointSource, PointTarget >::searchForNeighbors ( const PointCloudSource cloud,
int  index,
std::vector< int > &  indices,
std::vector< float > &  distances 
) [inline, protected]

Search for the closest nearest neighbor of a given point.

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

Definition at line 331 of file registration.h.

template<typename PointSource , typename PointTarget >
void pcl::Registration< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr cloud  )  [inline, virtual]

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

Parameters:
cloud the input point cloud target

Definition at line 195 of file registration.hpp.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
void pcl::Registration< PointSource, PointTarget >::setKSearch ( const typename pcl::KdTree< FeatureType >::Ptr &  tree,
int  k,
std::string  key 
) [inline]

Use k-nearest-neighbors as the search method when finding correspondences for the feature associated with the provided key.

Parameters:
tree the KdTree to use to compare features
k the number of nearest neighbors to return in the correspondence search
key a string that uniquely identifies the feature

Definition at line 287 of file registration.hpp.

template<typename PointSource, typename PointTarget>
void pcl::Registration< PointSource, PointTarget >::setMaxCorrespondenceDistance ( double  distance_threshold  )  [inline]

Set the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.

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

Definition at line 226 of file registration.h.

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

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

Parameters:
nr_iterations the maximum number of iterations the internal optimization should run for

Definition at line 200 of file registration.h.

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

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

Parameters:
point_representation the PointRepresentation to be used by the k-D tree

Definition at line 252 of file registration.h.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
void pcl::Registration< PointSource, PointTarget >::setRadiusSearch ( const typename pcl::KdTree< FeatureType >::Ptr &  tree,
float  r,
std::string  key 
) [inline]

Use radius-search as the search method when finding correspondences for the feature associated with the provided key.

Parameters:
tree the KdTree to use to compare features
r the radius to use when performing the correspondence search
key a string that uniquely identifies the feature

Definition at line 274 of file registration.hpp.

template<typename PointSource, typename PointTarget>
void pcl::Registration< PointSource, PointTarget >::setRANSACOutlierRejectionThreshold ( double  inlier_threshold  )  [inline]

Set the inlier distance threshold for the internal RANSAC outlier rejection loop.

The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold. The value is set by default to 0.05m.

Parameters:
inlier_threshold the inlier distance threshold for the internal RANSAC outlier rejection loop

Definition at line 214 of file registration.h.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
void pcl::Registration< PointSource, PointTarget >::setSourceFeature ( const typename pcl::PointCloud< FeatureType >::ConstPtr &  source_feature,
std::string  key 
) [inline]

Provide a pointer to a cloud of feature descriptors associated with the source point cloud.

Parameters:
source_feature a cloud of feature descriptors associated with the source point cloud
key a string that uniquely identifies the feature

Definition at line 215 of file registration.hpp.

template<typename PointSource , typename PointTarget >
template<typename FeatureType >
void pcl::Registration< PointSource, PointTarget >::setTargetFeature ( const typename pcl::PointCloud< FeatureType >::ConstPtr &  target_feature,
std::string  key 
) [inline]

Provide a pointer to a cloud of feature descriptors associated with the target point cloud.

Parameters:
target_feature a cloud of feature descriptors associated with the target point cloud
key a string that uniquely identifies the feature

Definition at line 243 of file registration.hpp.

template<typename PointSource, typename PointTarget>
void pcl::Registration< PointSource, PointTarget >::setTransformationEpsilon ( double  epsilon  )  [inline]

Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.

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

Definition at line 240 of file registration.h.


Member Data Documentation

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

Holds internal convergence state, given user parameters.

Definition at line 317 of file registration.h.

template<typename PointSource, typename PointTarget>
double pcl::Registration< PointSource, PointTarget >::corr_dist_threshold_ [protected]

The maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will not be ignored in the alignement process.

Definition at line 308 of file registration.h.

template<typename PointSource, typename PointTarget>
FeaturesMap pcl::Registration< PointSource, PointTarget >::features_map_ [private]

An STL map containing features to use when performing the correspondence search.

Definition at line 371 of file registration.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::final_transformation_ [protected]

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

Definition at line 292 of file registration.h.

template<typename PointSource, typename PointTarget>
double pcl::Registration< PointSource, PointTarget >::inlier_threshold_ [protected]

The inlier distance threshold for the internal RANSAC outlier rejection loop. The method considers a point to be an inlier, if the distance between the target data index and the transformed source index is smaller than the given inlier distance threshold.

Definition at line 314 of file registration.h.

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

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

Definition at line 286 of file registration.h.

template<typename PointSource, typename PointTarget>
int pcl::Registration< PointSource, PointTarget >::min_number_correspondences_ [protected]

The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.

Definition at line 322 of file registration.h.

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

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

Definition at line 283 of file registration.h.

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

The number of K nearest neighbors to use for each point.

The point representation used (internal).

Definition at line 368 of file registration.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::previous_transformation_ [protected]

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

Definition at line 298 of file registration.h.

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

The registration method name.

Definition at line 277 of file registration.h.

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

The input point cloud dataset target.

Definition at line 289 of file registration.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::Registration< PointSource, PointTarget >::transformation_ [protected]

The transformation matrix estimated by the registration method.

Definition at line 295 of file registration.h.

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

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

Definition at line 303 of file registration.h.

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

A pointer to the spatial search object.

Definition at line 280 of file registration.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:21 2013