Public Types | Public Member Functions
pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar > Class Template Reference

CorrespondenceEstimation represents the base class for determining correspondences between target and query point sets/features. More...

#include <correspondence_estimation.h>

Inheritance diagram for pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

template<typename PointSource, typename PointTarget, typename Scalar = float>
class pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >

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);
Author:
Radu B. Rusu, Michael Dixon, Dirk Holz

Definition at line 347 of file correspondence_estimation.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::KdTree
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::KdTreePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSource
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTarget
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTargetConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointCloudTargetPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::PointRepresentationConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::Ptr

Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::CorrespondenceEstimation ( ) [inline]

Empty constructor.

Definition at line 382 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >::~CorrespondenceEstimation ( ) [inline, virtual]

Empty destructor.

Definition at line 388 of file correspondence_estimation.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename Scalar >
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.

Parameters:
[out]correspondencesthe found correspondences (index of query point, index of target point, distance)
[in]max_distancemaximum allowed distance between correspondences

Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 127 of file correspondence_estimation.hpp.

template<typename PointSource , typename PointTarget , typename Scalar >
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.

Parameters:
[out]correspondencesthe found correspondences (index of query and target point, distance)
[in]max_distancemaximum allowed distance between correspondences

Implements pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 188 of file correspondence_estimation.hpp.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:53