#include <correspondence_rejection_distance.h>
Public Types | |
typedef boost::shared_ptr < const CorrespondenceRejectorDistance > | ConstPtr |
typedef boost::shared_ptr < CorrespondenceRejectorDistance > | Ptr |
Public Member Functions | |
CorrespondenceRejectorDistance () | |
Empty constructor. | |
float | getMaximumDistance () |
Get the maximum distance used for thresholding in correspondence rejection. | |
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 PointT > | |
void | setInputCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud) |
Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. | |
template<typename PointT > | |
void | setInputSource (const typename pcl::PointCloud< PointT >::ConstPtr &cloud) |
Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. | |
template<typename PointT > | |
void | setInputTarget (const typename pcl::PointCloud< PointT >::ConstPtr &target) |
Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance. | |
virtual void | setMaximumDistance (float distance) |
Set the maximum distance used for thresholding in correspondence rejection. | |
template<typename PointT > | |
void | setSearchMethodTarget (const boost::shared_ptr< pcl::search::KdTree< PointT > > &tree, bool force_no_recompute=false) |
Provide a pointer to the search object used to find correspondences in the target cloud. | |
virtual | ~CorrespondenceRejectorDistance () |
Empty destructor. | |
Protected Types | |
typedef boost::shared_ptr < DataContainerInterface > | DataContainerPtr |
Protected Member Functions | |
void | applyRejection (pcl::Correspondences &correspondences) |
Apply the rejection algorithm. | |
Protected Attributes | |
DataContainerPtr | data_container_ |
A pointer to the DataContainer object containing the input and target point clouds. | |
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. |
CorrespondenceRejectorDistance implements a simple correspondence rejection method based on thresholding the distances between the correspondences.
Definition at line 61 of file correspondence_rejection_distance.h.
typedef boost::shared_ptr<const CorrespondenceRejectorDistance> pcl::registration::CorrespondenceRejectorDistance::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Definition at line 69 of file correspondence_rejection_distance.h.
typedef boost::shared_ptr<DataContainerInterface> pcl::registration::CorrespondenceRejectorDistance::DataContainerPtr [protected] |
Definition at line 170 of file correspondence_rejection_distance.h.
typedef boost::shared_ptr<CorrespondenceRejectorDistance> pcl::registration::CorrespondenceRejectorDistance::Ptr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Definition at line 68 of file correspondence_rejection_distance.h.
Empty constructor.
Definition at line 72 of file correspondence_rejection_distance.h.
virtual pcl::registration::CorrespondenceRejectorDistance::~CorrespondenceRejectorDistance | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 79 of file correspondence_rejection_distance.h.
void pcl::registration::CorrespondenceRejectorDistance::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 160 of file correspondence_rejection_distance.h.
float pcl::registration::CorrespondenceRejectorDistance::getMaximumDistance | ( | ) | [inline] |
Get the maximum distance used for thresholding in correspondence rejection.
Definition at line 99 of file correspondence_rejection_distance.h.
void pcl::registration::CorrespondenceRejectorDistance::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_distance.cpp.
void pcl::registration::CorrespondenceRejectorDistance::setInputCloud | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloud | ) | [inline] |
Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
[in] | cloud | a cloud containing XYZ data |
Definition at line 106 of file correspondence_rejection_distance.h.
void pcl::registration::CorrespondenceRejectorDistance::setInputSource | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | cloud | ) | [inline] |
Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
[in] | cloud | a cloud containing XYZ data |
Definition at line 119 of file correspondence_rejection_distance.h.
void pcl::registration::CorrespondenceRejectorDistance::setInputTarget | ( | const typename pcl::PointCloud< PointT >::ConstPtr & | target | ) | [inline] |
Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
[in] | target | a cloud containing XYZ data |
Definition at line 131 of file correspondence_rejection_distance.h.
virtual void pcl::registration::CorrespondenceRejectorDistance::setMaximumDistance | ( | float | distance | ) | [inline, virtual] |
Set the maximum distance used for thresholding in correspondence rejection.
[in] | distance | Distance to be used as maximum distance between correspondences. Correspondences with larger distances are rejected. |
Definition at line 95 of file correspondence_rejection_distance.h.
void pcl::registration::CorrespondenceRejectorDistance::setSearchMethodTarget | ( | const boost::shared_ptr< pcl::search::KdTree< PointT > > & | tree, |
bool | force_no_recompute = false |
||
) | [inline] |
Provide a pointer to the search object used to find correspondences in the target cloud.
[in] | tree | a pointer to the spatial search object. |
[in] | force_no_recompute | If 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 146 of file correspondence_rejection_distance.h.
A pointer to the DataContainer object containing the input and target point clouds.
Definition at line 173 of file correspondence_rejection_distance.h.
float pcl::registration::CorrespondenceRejectorDistance::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 168 of file correspondence_rejection_distance.h.