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

CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which have minimum distance to normals computed on the input cloud More...

#include <correspondence_estimation_normal_shooting.h>

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

List of all members.

Public Types

typedef pcl::KdTree< PointTarget > KdTree
typedef pcl::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef pcl::PointCloud
< NormalT >::Ptr 
NormalsPtr
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

 CorrespondenceEstimationNormalShooting ()
 Empty constructor.
void determineCorrespondences (pcl::Correspondences &correspondences, float max_distance=std::numeric_limits< float >::max())
 Determine the correspondences between input and target cloud.
void getKSearch () const
 Get the number of nearest neighbours considered in the target point cloud for computing correspondence.
NormalsPtr getSourceNormals () const
 Get the normals of the input point cloud.
void setKSearch (unsigned int k)
 Set the number of nearest neighbours to be considered in the target point cloud.
void setSourceNormals (const NormalsPtr &normals)
 Set the normals computed on the input point cloud.

Private Attributes

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

Detailed Description

template<typename PointSource, typename PointTarget, typename NormalT>
class pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >

CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which have minimum distance to normals computed on the input cloud

Author:
Aravindhan K Krishnan

Definition at line 55 of file correspondence_estimation_normal_shooting.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename NormalT>
typedef pcl::KdTree<PointTarget> pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::KdTree
template<typename PointSource, typename PointTarget, typename NormalT>
typedef pcl::KdTree<PointTarget>::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::KdTreePtr
template<typename PointSource, typename PointTarget, typename NormalT>
typedef pcl::PointCloud<NormalT>::Ptr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::NormalsPtr

Definition at line 76 of file correspondence_estimation_normal_shooting.h.

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

Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 79 of file correspondence_estimation_normal_shooting.h.


Member Function Documentation

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

Reimplemented from pcl::registration::CorrespondenceEstimation< PointSource, PointTarget >.

Definition at line 45 of file correspondence_estimation_normal_shooting.hpp.

template<typename PointSource, typename PointTarget, typename NormalT>
void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::getKSearch ( ) const [inline]

Get the number of nearest neighbours considered in the target point cloud for computing correspondence.

Definition at line 113 of file correspondence_estimation_normal_shooting.h.

template<typename PointSource, typename PointTarget, typename NormalT>
NormalsPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::getSourceNormals ( ) const [inline]

Get the normals of the input point cloud.

Definition at line 93 of file correspondence_estimation_normal_shooting.h.

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

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

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

Definition at line 108 of file correspondence_estimation_normal_shooting.h.

template<typename PointSource, typename PointTarget, typename NormalT>
void pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::setSourceNormals ( const NormalsPtr normals) [inline]

Set the normals computed on the input point cloud.

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

Definition at line 88 of file correspondence_estimation_normal_shooting.h.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename NormalT>
unsigned int pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::k_ [private]

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

Definition at line 127 of file correspondence_estimation_normal_shooting.h.

template<typename PointSource, typename PointTarget, typename NormalT>
NormalsPtr pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT >::source_normals_ [private]

The normals computed at each point in the input cloud.

Definition at line 124 of file correspondence_estimation_normal_shooting.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