#include <correspondence_estimation.h>
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 | |
CorrespondenceEstimation () | |
Empty constructor. | |
virtual void | determineCorrespondences (std::vector< pcl::registration::Correspondence > &correspondences, float max_distance=std::numeric_limits< float >::max()) |
Determine the correspondences between input and target cloud. | |
virtual void | determineReciprocalCorrespondences (std::vector< pcl::registration::Correspondence > &correspondences) |
Determine the correspondences between input and target cloud. | |
PointCloudTargetConstPtr const | getInputTarget () |
Get a pointer to the input point cloud dataset target. | |
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. | |
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. | |
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. | |
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 | 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. | |
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. | |
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). | |
Protected Attributes | |
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. | |
std::string | corr_name_ |
The correspondence estimation method name. (TODO: does this make sense, will we have other correspondence estimators derived from this one?). | |
PointCloudTargetConstPtr | target_ |
The input point cloud dataset target. | |
KdTreePtr | tree_ |
A pointer to the spatial search object. | |
Private Attributes | |
FeaturesMap | features_map_ |
An STL map containing features to use when performing the correspondence search. | |
PointRepresentationConstPtr | point_representation_ |
The point representation used (internal). |
CorrespondenceEstimation represents the base class for determining correspondences between target and query point sets/features.
Definition at line 57 of file correspondence_estimation.h.
typedef std::map<std::string, boost::shared_ptr<FeatureContainerInterface> > pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::FeaturesMap |
Definition at line 74 of file correspondence_estimation.h.
typedef pcl::KdTree<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::KdTree |
Definition at line 61 of file correspondence_estimation.h.
typedef pcl::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::KdTreePtr |
Definition at line 62 of file correspondence_estimation.h.
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSource |
Definition at line 64 of file correspondence_estimation.h.
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSourceConstPtr |
Definition at line 66 of file correspondence_estimation.h.
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSourcePtr |
Definition at line 65 of file correspondence_estimation.h.
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTarget |
Definition at line 68 of file correspondence_estimation.h.
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTargetConstPtr |
Definition at line 70 of file correspondence_estimation.h.
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTargetPtr |
Definition at line 69 of file correspondence_estimation.h.
typedef KdTree::PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointRepresentationConstPtr |
Definition at line 72 of file correspondence_estimation.h.
pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::CorrespondenceEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 78 of file correspondence_estimation.h.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::determineCorrespondences | ( | std::vector< pcl::registration::Correspondence > & | correspondences, | |
float | max_distance = std::numeric_limits<float>::max() | |||
) | [inline, virtual] |
Determine the correspondences between input and target cloud.
brief Deterime the correspondences for the points in a given cloud (closest nearest neighbor). param cloud the point cloud dataset to use for nearest neighbor search param correspondences the found correspondences (index of query point, index of target point, distance) brief Deterime the correspondences for the points in a given cloud (closest nearest neighbor). param cloud the point cloud dataset to use for nearest neighbor search param indices indices of the points for which correspondences should be determined param correspondences the found correspondences (index of query point, index of target point, distance)
correspondences | the found correspondences (index of query point, index of target point, distance) | |
max_distance | maximum distance between correspondences |
Definition at line 202 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::determineReciprocalCorrespondences | ( | std::vector< pcl::registration::Correspondence > & | correspondences | ) | [inline, virtual] |
Determine the correspondences between input and target cloud.
correspondences | the found correspondences (index of query point, index of target point, distance) |
Definition at line 239 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< 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.
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 164 of file correspondence_estimation.hpp.
const std::string& pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getClassName | ( | ) | const [inline, protected] |
Abstract class get name method.
Definition at line 275 of file correspondence_estimation.h.
PointCloudTargetConstPtr const pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getInputTarget | ( | ) | [inline] |
Get a pointer to the input point cloud dataset target.
Definition at line 91 of file correspondence_estimation.h.
double pcl::registration::CorrespondenceEstimation< 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 147 of file correspondence_estimation.h.
pcl::PointCloud< FeatureType >::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getSourceFeature | ( | std::string | key | ) | [inline] |
Get a pointer to the source cloud's feature descriptors, specified by the given key.
key | a string that uniquely identifies the feature (must match the key provided by setSourceFeature) |
Definition at line 74 of file correspondence_estimation.hpp.
pcl::PointCloud< FeatureType >::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getTargetFeature | ( | std::string | key | ) | [inline] |
Get a pointer to the source cloud's feature descriptors, specified by the given key.
key | a string that uniquely identifies the feature (must match the key provided by setTargetFeature) |
Definition at line 102 of file correspondence_estimation.hpp.
bool pcl::registration::CorrespondenceEstimation< 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 145 of file correspondence_estimation.hpp.
bool pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::searchForNeighbors | ( | const PointCloudSource & | cloud, | |
int | index, | |||
std::vector< int > & | indices, | |||
std::vector< float > & | distances | |||
) | [inline] |
Search for the closest nearest neighbor of a given point.
cloud | the point cloud dataset to use for nearest neighbor search | |
index | the index of the query point | |
indices | the resultant vector of indices representing the k-nearest neighbors | |
distances | the resultant distances from the query point to the k-nearest neighbors |
Definition at line 165 of file correspondence_estimation.h.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::setInputTarget | ( | const PointCloudTargetConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to).
cloud | the input point cloud target |
Definition at line 41 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< 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.
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 133 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::setMaxCorrespondenceDistance | ( | double | distance_threshold | ) | [inline] |
Set the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.
distance_threshold | the maximum distance threshold between a point and its nearest neighbor correspondent in order to be considered in the alignment process |
Definition at line 142 of file correspondence_estimation.h.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::setPointRepresentation | ( | const PointRepresentationConstPtr & | point_representation | ) | [inline] |
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
point_representation | the PointRepresentation to be used by the k-D tree |
Definition at line 153 of file correspondence_estimation.h.
void pcl::registration::CorrespondenceEstimation< 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.
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 120 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< 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.
source_feature | a cloud of feature descriptors associated with the source point cloud | |
key | a string that uniquely identifies the feature |
Definition at line 61 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< 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.
target_feature | a cloud of feature descriptors associated with the target point cloud | |
key | a string that uniquely identifies the feature |
Definition at line 89 of file correspondence_estimation.hpp.
double pcl::registration::CorrespondenceEstimation< 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 260 of file correspondence_estimation.h.
std::string pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::corr_name_ [protected] |
The correspondence estimation method name. (TODO: does this make sense, will we have other correspondence estimators derived from this one?).
Definition at line 249 of file correspondence_estimation.h.
FeaturesMap pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::features_map_ [private] |
An STL map containing features to use when performing the correspondence search.
Definition at line 283 of file correspondence_estimation.h.
PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::point_representation_ [private] |
The point representation used (internal).
Definition at line 280 of file correspondence_estimation.h.
PointCloudTargetConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::target_ [protected] |
The input point cloud dataset target.
Definition at line 255 of file correspondence_estimation.h.
KdTreePtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 252 of file correspondence_estimation.h.