CorrespondenceRejectorFeatures implements a correspondence rejection method based on a set of feature descriptors. Given an input feature space, the method checks if each feature in the source cloud has a correspondence in the target cloud, either by checking the first K (given) point correspondences, or by defining a tolerance threshold via a radius in feature space. More...
#include <correspondence_rejection_features.h>
Classes | |
class | FeatureContainer |
An inner class containing pointers to the source and target feature clouds 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 FeatureT --- these methods can thus be called from a pointer to FeatureContainerInterface without casting to the derived class. More... | |
class | FeatureContainerInterface |
Public Types | |
typedef boost::shared_ptr < const CorrespondenceRejectorFeatures > | ConstPtr |
typedef boost::shared_ptr < CorrespondenceRejectorFeatures > | Ptr |
Public Member Functions | |
CorrespondenceRejectorFeatures () | |
Empty constructor. | |
void | getRemainingCorrespondences (const pcl::Correspondences &original_correspondences, pcl::Correspondences &remaining_correspondences) |
Get a list of valid correspondences after rejection from the original set of correspondences. | |
template<typename FeatureT > | |
pcl::PointCloud< FeatureT > ::ConstPtr | getSourceFeature (const std::string &key) |
Get a pointer to the source cloud's feature descriptors, specified by the given key. | |
template<typename FeatureT > | |
pcl::PointCloud< FeatureT > ::ConstPtr | getTargetFeature (const std::string &key) |
Get a pointer to the source cloud's feature descriptors, specified by the given key. | |
bool | hasValidFeatures () |
Test that all features are valid (i.e., does each key have a valid source cloud, target cloud, and search method) | |
template<typename FeatureT > | |
void | setDistanceThreshold (double thresh, const std::string &key) |
Set a hard distance threshold in the feature FeatureT space, between source and target features. Any feature correspondence that is above this threshold will be considered bad and will be filtered out. | |
template<typename FeatureT > | |
void | setFeatureRepresentation (const typename pcl::PointRepresentation< FeatureT >::ConstPtr &fr, const std::string &key) |
Provide a boost shared pointer to a PointRepresentation to be used when comparing features. | |
template<typename FeatureT > | |
void | setSourceFeature (const typename pcl::PointCloud< FeatureT >::ConstPtr &source_feature, const std::string &key) |
Provide a pointer to a cloud of feature descriptors associated with the source point cloud. | |
template<typename FeatureT > | |
void | setTargetFeature (const typename pcl::PointCloud< FeatureT >::ConstPtr &target_feature, const std::string &key) |
Provide a pointer to a cloud of feature descriptors associated with the target point cloud. | |
virtual | ~CorrespondenceRejectorFeatures () |
Empty destructor. | |
Protected Types | |
typedef boost::unordered_map < std::string, boost::shared_ptr < FeatureContainerInterface > > | FeaturesMap |
Protected Member Functions | |
void | applyRejection (pcl::Correspondences &correspondences) |
Apply the rejection algorithm. | |
Protected Attributes | |
FeaturesMap | features_map_ |
An STL map containing features to use when performing the correspondence search. | |
float | max_distance_ |
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 alignment process. |
CorrespondenceRejectorFeatures implements a correspondence rejection method based on a set of feature descriptors. Given an input feature space, the method checks if each feature in the source cloud has a correspondence in the target cloud, either by checking the first K (given) point correspondences, or by defining a tolerance threshold via a radius in feature space.
Definition at line 60 of file correspondence_rejection_features.h.
typedef boost::shared_ptr<const CorrespondenceRejectorFeatures> pcl::registration::CorrespondenceRejectorFeatures::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Definition at line 68 of file correspondence_rejection_features.h.
typedef boost::unordered_map<std::string, boost::shared_ptr<FeatureContainerInterface> > pcl::registration::CorrespondenceRejectorFeatures::FeaturesMap [protected] |
Definition at line 164 of file correspondence_rejection_features.h.
typedef boost::shared_ptr<CorrespondenceRejectorFeatures> pcl::registration::CorrespondenceRejectorFeatures::Ptr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Definition at line 67 of file correspondence_rejection_features.h.
Empty constructor.
Definition at line 71 of file correspondence_rejection_features.h.
virtual pcl::registration::CorrespondenceRejectorFeatures::~CorrespondenceRejectorFeatures | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 77 of file correspondence_rejection_features.h.
void pcl::registration::CorrespondenceRejectorFeatures::applyRejection | ( | pcl::Correspondences & | correspondences | ) | [inline, protected, virtual] |
Apply the rejection algorithm.
[out] | correspondences | the set of resultant correspondences. |
Implements pcl::registration::CorrespondenceRejector.
Definition at line 144 of file correspondence_rejection_features.h.
void pcl::registration::CorrespondenceRejectorFeatures::getRemainingCorrespondences | ( | const pcl::Correspondences & | original_correspondences, |
pcl::Correspondences & | remaining_correspondences | ||
) | [virtual] |
Get a list of valid correspondences after rejection from the original set of correspondences.
[in] | original_correspondences | the set of initial correspondences given |
[out] | remaining_correspondences | the resultant filtered set of remaining correspondences |
Implements pcl::registration::CorrespondenceRejector.
Definition at line 44 of file correspondence_rejection_features.cpp.
pcl::PointCloud< FeatureT >::ConstPtr pcl::registration::CorrespondenceRejectorFeatures::getSourceFeature | ( | const std::string & | key | ) | [inline] |
Get a pointer to the source cloud's feature descriptors, specified by the given key.
[in] | key | a string that uniquely identifies the feature (must match the key provided by setSourceFeature) |
Definition at line 55 of file correspondence_rejection_features.hpp.
pcl::PointCloud< FeatureT >::ConstPtr pcl::registration::CorrespondenceRejectorFeatures::getTargetFeature | ( | const std::string & | key | ) | [inline] |
Get a pointer to the source cloud's feature descriptors, specified by the given key.
[in] | key | a string that uniquely identifies the feature (must match the key provided by setTargetFeature) |
Definition at line 75 of file correspondence_rejection_features.hpp.
bool pcl::registration::CorrespondenceRejectorFeatures::hasValidFeatures | ( | ) | [inline] |
Test that all features are valid (i.e., does each key have a valid source cloud, target cloud, and search method)
Definition at line 70 of file correspondence_rejection_features.cpp.
void pcl::registration::CorrespondenceRejectorFeatures::setDistanceThreshold | ( | double | thresh, |
const std::string & | key | ||
) | [inline] |
Set a hard distance threshold in the feature FeatureT space, between source and target features. Any feature correspondence that is above this threshold will be considered bad and will be filtered out.
[in] | thresh | the distance threshold |
[in] | key | a string that uniquely identifies the feature |
Definition at line 85 of file correspondence_rejection_features.hpp.
void pcl::registration::CorrespondenceRejectorFeatures::setFeatureRepresentation | ( | const typename pcl::PointRepresentation< FeatureT >::ConstPtr & | fr, |
const std::string & | key | ||
) | [inline] |
Provide a boost shared pointer to a PointRepresentation to be used when comparing features.
[in] | key | a string that uniquely identifies the feature |
[in] | fr | the point feature representation to be used |
Definition at line 97 of file correspondence_rejection_features.hpp.
void pcl::registration::CorrespondenceRejectorFeatures::setSourceFeature | ( | const typename pcl::PointCloud< FeatureT >::ConstPtr & | source_feature, |
const std::string & | key | ||
) | [inline] |
Provide a pointer to a cloud of feature descriptors associated with the source point cloud.
[in] | source_feature | a cloud of feature descriptors associated with the source point cloud |
[in] | key | a string that uniquely identifies the feature |
Definition at line 45 of file correspondence_rejection_features.hpp.
void pcl::registration::CorrespondenceRejectorFeatures::setTargetFeature | ( | const typename pcl::PointCloud< FeatureT >::ConstPtr & | target_feature, |
const std::string & | key | ||
) | [inline] |
Provide a pointer to a cloud of feature descriptors associated with the target point cloud.
[in] | target_feature | a cloud of feature descriptors associated with the target point cloud |
[in] | key | a string that uniquely identifies the feature |
Definition at line 65 of file correspondence_rejection_features.hpp.
An STL map containing features to use when performing the correspondence search.
Definition at line 167 of file correspondence_rejection_features.h.
float pcl::registration::CorrespondenceRejectorFeatures::max_distance_ [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 alignment process.
Definition at line 152 of file correspondence_rejection_features.h.