CorrespondenceEstimation represents the base class for determining correspondences between target and query point sets/features. More...
#include <correspondence_estimation.h>
Public Types | |
typedef boost::shared_ptr < const CorrespondenceEstimation < PointSource, PointTarget, Scalar > > | ConstPtr |
typedef pcl::search::KdTree < PointTarget > | KdTree |
typedef pcl::search::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 |
typedef boost::shared_ptr < CorrespondenceEstimation < PointSource, PointTarget, Scalar > > | Ptr |
Public Member Functions | |
CorrespondenceEstimation () | |
Empty constructor. | |
virtual void | determineCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) |
Determine the correspondences between input and target cloud. | |
virtual void | determineReciprocalCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max()) |
Determine the reciprocal correspondences between input and target cloud. A correspondence is considered reciprocal if both Src_i has Tgt_i as a correspondence, and Tgt_i has Src_i as one. | |
virtual | ~CorrespondenceEstimation () |
Empty destructor. |
CorrespondenceEstimation represents the base class for determining correspondences between target and query point sets/features.
Code example:
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr source, target; // ... read or fill in source and target pcl::CorrespondenceEstimation<pcl::PointXYZ, pcl::PointXYZ> est; est.setInputSource (source); est.setInputTarget (target); pcl::Correspondences all_correspondences; // Determine all reciprocal correspondences est.determineReciprocalCorrespondences (all_correspondences);
Definition at line 347 of file correspondence_estimation.h.
typedef boost::shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 351 of file correspondence_estimation.h.
typedef pcl::search::KdTree<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::KdTree |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 368 of file correspondence_estimation.h.
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::KdTreePtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 369 of file correspondence_estimation.h.
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSource |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 371 of file correspondence_estimation.h.
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 373 of file correspondence_estimation.h.
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSourcePtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 372 of file correspondence_estimation.h.
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTarget |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 375 of file correspondence_estimation.h.
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 377 of file correspondence_estimation.h.
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTargetPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 376 of file correspondence_estimation.h.
typedef KdTree::PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 379 of file correspondence_estimation.h.
typedef boost::shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::Ptr |
Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 350 of file correspondence_estimation.h.
pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::CorrespondenceEstimation | ( | ) | [inline] |
Empty constructor.
Definition at line 382 of file correspondence_estimation.h.
virtual pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::~CorrespondenceEstimation | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 388 of file correspondence_estimation.h.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineCorrespondences | ( | pcl::Correspondences & | correspondences, |
double | max_distance = std::numeric_limits<double>::max () |
||
) | [virtual] |
Determine the correspondences between input and target cloud.
[out] | correspondences | the found correspondences (index of query point, index of target point, distance) |
[in] | max_distance | maximum allowed distance between correspondences |
Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 127 of file correspondence_estimation.hpp.
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences | ( | pcl::Correspondences & | correspondences, |
double | max_distance = std::numeric_limits<double>::max () |
||
) | [virtual] |
Determine the reciprocal correspondences between input and target cloud. A correspondence is considered reciprocal if both Src_i has Tgt_i as a correspondence, and Tgt_i has Src_i as one.
[out] | correspondences | the found correspondences (index of query and target point, distance) |
[in] | max_distance | maximum allowed distance between correspondences |
Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.
Definition at line 188 of file correspondence_estimation.hpp.