Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
pcl::registration::CorrespondenceEstimation< PointSource, PointTarget > 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 >:
Inheritance graph
[legend]

List of all members.

Public Types

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 (pcl::Correspondences &correspondences, float max_distance=std::numeric_limits< float >::max())
 Determine the correspondences between input and target cloud.
virtual void determineReciprocalCorrespondences (pcl::Correspondences &correspondences)
 Determine the correspondences between input and target cloud.
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target.
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)
void setPointRepresentation (const PointRepresentationConstPtr &point_representation)
 Provide a boost shared pointer to the PointRepresentation to be used when comparing points.

Protected Member Functions

const std::string & getClassName () const
 Abstract class get name method.

Protected Attributes

std::string corr_name_
 The correspondence estimation method name.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.
KdTreePtr tree_
 A pointer to the spatial search object.

Private Attributes

PointRepresentationConstPtr point_representation_
 The point representation used (internal).

Detailed Description

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

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

Author:
Radu Bogdan Rusu, Michael Dixon, Dirk Holz

Definition at line 62 of file correspondence_estimation.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::KdTree
template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::KdTreePtr
template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSource
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTarget
template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTargetConstPtr
template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointCloudTargetPtr
template<typename PointSource, typename PointTarget>
typedef KdTree::PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::PointRepresentationConstPtr

Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 84 of file correspondence_estimation.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::determineCorrespondences ( pcl::Correspondences correspondences,
float  max_distance = std::numeric_limits<float>::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 distance between correspondences

Reimplemented in pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >.

Definition at line 60 of file correspondence_estimation.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::determineReciprocalCorrespondences ( pcl::Correspondences correspondences) [virtual]

Determine the correspondences between input and target cloud.

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

Definition at line 107 of file correspondence_estimation.hpp.

template<typename PointSource, typename PointTarget>
const std::string& pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getClassName ( ) const [inline, protected]

Abstract class get name method.

Definition at line 138 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget>
PointCloudTargetConstPtr const pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::getInputTarget ( ) [inline]

Get a pointer to the input point cloud dataset target.

Definition at line 101 of file correspondence_estimation.h.

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

Parameters:
[in]cloudthe input point cloud target

Definition at line 46 of file correspondence_estimation.hpp.

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

Parameters:
[in]point_representationthe PointRepresentation to be used by the k-D tree

Definition at line 107 of file correspondence_estimation.h.


Member Data Documentation

template<typename PointSource, typename PointTarget>
std::string pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::corr_name_ [protected]

The correspondence estimation method name.

Definition at line 128 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget>
PointRepresentationConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::point_representation_ [private]

The point representation used (internal).

Definition at line 142 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget>
PointCloudTargetConstPtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::target_ [protected]

The input point cloud dataset target.

Definition at line 134 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget>
KdTreePtr pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 131 of file correspondence_estimation.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:21