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

CorrespondenceEstimationBackprojection computes correspondences as points in the target cloud which have minimum More...

#include <correspondence_estimation_backprojection.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceEstimationBackProjection
< PointSource, PointTarget,
NormalT, Scalar > > 
ConstPtr
typedef pcl::search::KdTree
< PointTarget > 
KdTree
typedef pcl::search::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef PointCloudNormals::ConstPtr NormalsConstPtr
typedef PointCloudNormals::Ptr NormalsPtr
typedef pcl::PointCloud< NormalTPointCloudNormals
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 boost::shared_ptr
< CorrespondenceEstimationBackProjection
< PointSource, PointTarget,
NormalT, Scalar > > 
Ptr

Public Member Functions

 CorrespondenceEstimationBackProjection ()
 Empty constructor.
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.
void getKSearch () const
 Get the number of nearest neighbours considered in the target point cloud for computing correspondences. By default we use k = 10 nearest neighbors.
NormalsConstPtr getSourceNormals () const
 Get the normals of the source point cloud.
NormalsConstPtr getTargetNormals () const
 Get the normals of the target point cloud.
void setKSearch (unsigned int k)
 Set the number of nearest neighbours to be considered in the target point cloud. By default, we use k = 10 nearest neighbors.
void setSourceNormals (const NormalsConstPtr &normals)
 Set the normals computed on the source point cloud.
void setTargetNormals (const NormalsConstPtr &normals)
 Set the normals computed on the target point cloud.
virtual ~CorrespondenceEstimationBackProjection ()
 Empty destructor.

Protected Member Functions

bool initCompute ()
 Internal computation initalization.

Private Attributes

unsigned int k_
 The number of neighbours to be considered in the target point cloud.
NormalsConstPtr source_normals_
 The normals computed at each point in the source cloud.
NormalsPtr source_normals_transformed_
 The normals computed at each point in the source cloud.
NormalsConstPtr target_normals_
 The normals computed at each point in the target cloud.

Detailed Description

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

CorrespondenceEstimationBackprojection computes correspondences as points in the target cloud which have minimum

Author:
Suat Gedikli

Definition at line 56 of file correspondence_estimation_backprojection.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef boost::shared_ptr<const CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> > pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::KdTree
template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::KdTreePtr
template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef PointCloudNormals::ConstPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::NormalsConstPtr

Definition at line 85 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef PointCloudNormals::Ptr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::NormalsPtr

Definition at line 84 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
typedef pcl::PointCloud<NormalT> pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::PointCloudNormals

Definition at line 83 of file correspondence_estimation_backprojection.h.

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

Constructor & Destructor Documentation

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

Empty constructor.

Note:
Sets the number of neighbors to be considered in the target point cloud (k_) to 10.

Definition at line 92 of file correspondence_estimation_backprojection.h.

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

Empty destructor.

Definition at line 102 of file correspondence_estimation_backprojection.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename NormalT , typename Scalar >
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, 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 distance between the normal on the source point cloud and the corresponding point in the target point cloud

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

Definition at line 57 of file correspondence_estimation_backprojection.hpp.

template<typename PointSource , typename PointTarget , typename NormalT , typename Scalar >
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, 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 158 of file correspondence_estimation_backprojection.hpp.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::getKSearch ( ) const [inline]

Get the number of nearest neighbours considered in the target point cloud for computing correspondences. By default we use k = 10 nearest neighbors.

Definition at line 159 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
NormalsConstPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::getSourceNormals ( ) const [inline]

Get the normals of the source point cloud.

Definition at line 113 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
NormalsConstPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::getTargetNormals ( ) const [inline]

Get the normals of the target point cloud.

Definition at line 124 of file correspondence_estimation_backprojection.h.

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

Internal computation initalization.

Reimplemented from pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >.

Definition at line 44 of file correspondence_estimation_backprojection.hpp.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::setKSearch ( unsigned int  k) [inline]

Set the number of nearest neighbours to be considered in the target point cloud. By default, we use k = 10 nearest neighbors.

Parameters:
[in]kthe number of nearest neighbours to be considered

Definition at line 152 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::setSourceNormals ( const NormalsConstPtr normals) [inline]

Set the normals computed on the source point cloud.

Parameters:
[in]normalsthe normals computed for the source cloud

Definition at line 108 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::setTargetNormals ( const NormalsConstPtr normals) [inline]

Set the normals computed on the target point cloud.

Parameters:
[in]normalsthe normals computed for the target cloud

Definition at line 119 of file correspondence_estimation_backprojection.h.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
unsigned int pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::k_ [private]

The number of neighbours to be considered in the target point cloud.

Definition at line 184 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
NormalsConstPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::source_normals_ [private]

The normals computed at each point in the source cloud.

Definition at line 175 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
NormalsPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::source_normals_transformed_ [private]

The normals computed at each point in the source cloud.

Definition at line 178 of file correspondence_estimation_backprojection.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
NormalsConstPtr pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >::target_normals_ [private]

The normals computed at each point in the target cloud.

Definition at line 181 of file correspondence_estimation_backprojection.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