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

Abstract CorrespondenceEstimationBase class. All correspondence estimation methods should inherit from this. More...

#include <correspondence_estimation.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceEstimationBase
< PointSource, PointTarget,
Scalar > > 
ConstPtr
typedef pcl::search::KdTree
< PointTarget > 
KdTree
typedef KdTree::Ptr KdTreePtr
typedef pcl::search::KdTree
< PointSource > 
KdTreeReciprocal
typedef KdTree::Ptr KdTreeReciprocalPtr
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
< CorrespondenceEstimationBase
< PointSource, PointTarget,
Scalar > > 
Ptr

Public Member Functions

 CorrespondenceEstimationBase ()
 Empty constructor.
virtual void determineCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max())=0
 Determine the correspondences between input and target cloud.
virtual void determineReciprocalCorrespondences (pcl::Correspondences &correspondences, double max_distance=std::numeric_limits< double >::max())=0
 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.
IndicesPtr const getIndicesSource ()
 Get a pointer to the vector of indices used for the source dataset.
IndicesPtr const getIndicesTarget ()
 Get a pointer to the vector of indices used for the target dataset.
PointCloudSourceConstPtr const getInputSource ()
 Get a pointer to the input point cloud dataset target.
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target.
KdTreeReciprocalPtr getSearchMethodSource () const
 Get a pointer to the search method used to find correspondences in the source cloud.
KdTreePtr getSearchMethodTarget () const
 Get a pointer to the search method used to find correspondences in the target cloud.
 PCL_DEPRECATED (void setInputCloud(const PointCloudSourceConstPtr &cloud),"[pcl::registration::CorrespondenceEstimationBase::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
 PCL_DEPRECATED (PointCloudSourceConstPtr const getInputCloud(),"[pcl::registration::CorrespondenceEstimationBase::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.")
 Get a pointer to the input point cloud dataset target.
void setIndicesSource (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represent the input source point cloud.
void setIndicesTarget (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represent the input target point cloud.
void setInputSource (const PointCloudSourceConstPtr &cloud)
 Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
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 searching for nearest neighbors.
void setSearchMethodSource (const KdTreeReciprocalPtr &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding).
void setSearchMethodTarget (const KdTreePtr &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the target cloud.
virtual ~CorrespondenceEstimationBase ()
 Empty destructor.

Protected Member Functions

const std::stringgetClassName () const
 Abstract class get name method.
bool initCompute ()
 Internal computation initalization.
bool initComputeReciprocal ()
 Internal computation initalization for reciprocal correspondences.

Protected Attributes

std::string corr_name_
 The correspondence estimation method name.
bool force_no_recompute_
 A flag which, if set, means the tree operating on the target cloud will never be recomputed.
bool force_no_recompute_reciprocal_
 A flag which, if set, means the tree operating on the source cloud will never be recomputed.
std::vector< pcl::PCLPointFieldinput_fields_
 The types of input point fields available.
PointCloudTargetPtr input_transformed_
 The transformed input source point cloud dataset.
PointRepresentationConstPtr point_representation_
 The point representation used (internal).
bool source_cloud_updated_
 Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method is called.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.
bool target_cloud_updated_
 Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method is called.
IndicesPtr target_indices_
 The target point cloud dataset indices.
KdTreePtr tree_
 A pointer to the spatial search object used for the target dataset.
KdTreeReciprocalPtr tree_reciprocal_
 A pointer to the spatial search object used for the source dataset.

Detailed Description

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

Abstract CorrespondenceEstimationBase class. All correspondence estimation methods should inherit from this.

Author:
Radu B. Rusu

Definition at line 63 of file correspondence_estimation.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<const CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> > pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTree
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::Ptr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreePtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef pcl::search::KdTree<PointSource> pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeReciprocal

Definition at line 78 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef KdTree::Ptr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::KdTreeReciprocalPtr

Definition at line 79 of file correspondence_estimation.h.

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

Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 92 of file correspondence_estimation.h.

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

Empty destructor.

Definition at line 109 of file correspondence_estimation.h.


Member Function Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::determineCorrespondences ( pcl::Correspondences correspondences,
double  max_distance = std::numeric_limits< double >::max() 
) [pure 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

Implemented in pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >, pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >, pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >, and pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::determineReciprocalCorrespondences ( pcl::Correspondences correspondences,
double  max_distance = std::numeric_limits< double >::max() 
) [pure 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

Implemented in pcl::registration::CorrespondenceEstimation< PointSource, PointTarget, Scalar >, pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >, pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >, and pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >.

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

Abstract class get name method.

Definition at line 297 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
IndicesPtr const pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getIndicesSource ( ) [inline]

Get a pointer to the vector of indices used for the source dataset.

Definition at line 165 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
IndicesPtr const pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getIndicesTarget ( ) [inline]

Get a pointer to the vector of indices used for the target dataset.

Definition at line 179 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudSourceConstPtr const pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getInputSource ( ) [inline]

Get a pointer to the input point cloud dataset target.

Definition at line 137 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudTargetConstPtr const pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getInputTarget ( ) [inline]

Get a pointer to the input point cloud dataset target.

Definition at line 151 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreeReciprocalPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getSearchMethodSource ( ) const [inline]

Get a pointer to the search method used to find correspondences in the source cloud.

Definition at line 232 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreePtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::getSearchMethodTarget ( ) const [inline]

Get a pointer to the search method used to find correspondences in the target cloud.

Definition at line 204 of file correspondence_estimation.h.

template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::initCompute ( ) [protected]
template<typename PointSource , typename PointTarget , typename Scalar >
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::initComputeReciprocal ( ) [protected]

Internal computation initalization for reciprocal correspondences.

Definition at line 106 of file correspondence_estimation.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::PCL_DEPRECATED ( void   setInputCloudconst PointCloudSourceConstPtr &cloud,
" setInputCloud is deprecated. Please use setInputSource instead."  [pcl::registration::CorrespondenceEstimationBase::setInputCloud] 
)

Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud source
template<typename PointSource, typename PointTarget, typename Scalar = float>
pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::PCL_DEPRECATED ( PointCloudSourceConstPtr const   getInputCloud(),
" getInputCloud is deprecated. Please use getInputSource instead."  [pcl::registration::CorrespondenceEstimationBase::getInputCloud] 
)

Get a pointer to the input point cloud dataset target.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setIndicesSource ( const IndicesPtr indices) [inline]

Provide a pointer to the vector of indices that represent the input source point cloud.

Parameters:
[in]indicesa pointer to the vector of indices

Definition at line 158 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setIndicesTarget ( const IndicesPtr indices) [inline]

Provide a pointer to the vector of indices that represent the input target point cloud.

Parameters:
[in]indicesa pointer to the vector of indices

Definition at line 171 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setInputSource ( const PointCloudSourceConstPtr cloud) [inline]

Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)

Parameters:
[in]cloudthe input point cloud source

Definition at line 128 of file correspondence_estimation.h.

template<typename PointSource , typename PointTarget , typename Scalar >
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setInputTarget ( const PointCloudTargetConstPtr cloud) [inline]

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 62 of file correspondence_estimation.hpp.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setPointRepresentation ( const PointRepresentationConstPtr point_representation) [inline]

Provide a boost shared pointer to the PointRepresentation to be used when searching for nearest neighbors.

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

Definition at line 263 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setSearchMethodSource ( const KdTreeReciprocalPtr tree,
bool  force_no_recompute = false 
) [inline]

Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding).

Parameters:
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf set to true, this tree will NEVER be recomputed, regardless of calls to setInputSource. Only use if you are extremely confident that the tree will be set correctly.

Definition at line 217 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setSearchMethodTarget ( const KdTreePtr tree,
bool  force_no_recompute = false 
) [inline]

Provide a pointer to the search object used to find correspondences in the target cloud.

Parameters:
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf 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 189 of file correspondence_estimation.h.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::string pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::corr_name_ [protected]

The correspondence estimation method name.

Definition at line 270 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::force_no_recompute_ [protected]

A flag which, if set, means the tree operating on the target cloud will never be recomputed.

Definition at line 317 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::force_no_recompute_reciprocal_ [protected]

A flag which, if set, means the tree operating on the source cloud will never be recomputed.

Definition at line 321 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
std::vector<pcl::PCLPointField> pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::input_fields_ [protected]

The types of input point fields available.

Definition at line 293 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudTargetPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::input_transformed_ [protected]

The transformed input source point cloud dataset.

Definition at line 290 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointRepresentationConstPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::point_representation_ [protected]

The point representation used (internal).

Definition at line 287 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::source_cloud_updated_ [protected]

Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the source cloud every time the determineCorrespondences () method is called.

Definition at line 314 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
PointCloudTargetConstPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::target_ [protected]

The input point cloud dataset target.

Definition at line 281 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
bool pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::target_cloud_updated_ [protected]

Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. This way, we avoid rebuilding the kd-tree for the target cloud every time the determineCorrespondences () method is called.

Definition at line 310 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
IndicesPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::target_indices_ [protected]

The target point cloud dataset indices.

Definition at line 284 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreePtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::tree_ [protected]

A pointer to the spatial search object used for the target dataset.

Definition at line 273 of file correspondence_estimation.h.

template<typename PointSource, typename PointTarget, typename Scalar = float>
KdTreeReciprocalPtr pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::tree_reciprocal_ [protected]

A pointer to the spatial search object used for the source dataset.

Definition at line 276 of file correspondence_estimation.h.


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


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