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

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceEstimationNormalShooting
< 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
< CorrespondenceEstimationNormalShooting
< PointSource, PointTarget,
NormalT, Scalar > > 
Ptr

Public Member Functions

 CorrespondenceEstimationNormalShooting ()
 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.
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.
virtual ~CorrespondenceEstimationNormalShooting ()
 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.

Detailed Description

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

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

Code example:

 pcl::PointCloud<pcl::PointNormal>::Ptr source, target;
 // ... read or fill in source and target
 pcl::CorrespondenceEstimationNormalShooting<pcl::PointNormal, pcl::PointNormal, pcl::PointNormal> est;
 est.setInputSource (source);
 est.setSourceNormals (source);

 est.setInputTarget (target);

 // Test the first 10 correspondences for each point in source, and return the best
 est.setKSearch (10);

 pcl::Correspondences all_correspondences;
 // Determine all correspondences
 est.determineCorrespondences (all_correspondences);
Author:
Aravindhan K. Krishnan, Radu B. Rusu

Definition at line 78 of file correspondence_estimation_normal_shooting.h.


Member Typedef Documentation

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

Definition at line 107 of file correspondence_estimation_normal_shooting.h.

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

Definition at line 106 of file correspondence_estimation_normal_shooting.h.

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

Definition at line 105 of file correspondence_estimation_normal_shooting.h.

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

Constructor & Destructor Documentation

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

Empty constructor.

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

Definition at line 114 of file correspondence_estimation_normal_shooting.h.

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

Empty destructor.

Definition at line 123 of file correspondence_estimation_normal_shooting.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename NormalT , typename Scalar >
void pcl::registration::CorrespondenceEstimationNormalShooting< 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 58 of file correspondence_estimation_normal_shooting.hpp.

template<typename PointSource , typename PointTarget , typename NormalT , typename Scalar >
void pcl::registration::CorrespondenceEstimationNormalShooting< 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 175 of file correspondence_estimation_normal_shooting.hpp.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationNormalShooting< 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 169 of file correspondence_estimation_normal_shooting.h.

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

Get the normals of the source point cloud.

Definition at line 134 of file correspondence_estimation_normal_shooting.h.

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

Internal computation initalization.

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

Definition at line 45 of file correspondence_estimation_normal_shooting.hpp.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationNormalShooting< 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 162 of file correspondence_estimation_normal_shooting.h.

template<typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
void pcl::registration::CorrespondenceEstimationNormalShooting< 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 129 of file correspondence_estimation_normal_shooting.h.


Member Data Documentation

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

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

Definition at line 191 of file correspondence_estimation_normal_shooting.h.

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

The normals computed at each point in the source cloud.

Definition at line 185 of file correspondence_estimation_normal_shooting.h.

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

The normals computed at each point in the source cloud.

Definition at line 188 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 Wed Aug 26 2015 15:45:00