pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT > Class Template Reference

SampleConsensusInitialAlignment is an implementation of the initial alignment algorithm described in section IV of "Fast Point Feature Histograms (FPFH) for 3D Registration," Rusu et al. More...

#include <ia_ransac.h>

Inheritance diagram for pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

float getMinSampleDistance ()
 Get the minimum distances between samples, as set by the user.
int getNumberOfSamples ()
 Set the number of samples to use during each iteration, as set by the user.
FeatureCloudConstPtr const getSourceFeatures ()
 Get a pointer to the source point cloud's features.
FeatureCloudConstPtr const getTargetFeatures ()
 Get a pointer to the target point cloud's features.
 SampleConsensusInitialAlignment ()
 Constructor.
void setMinSampleDistance (float min_sample_distance)
 Set the minimum distances between samples.
void setNumberOfSamples (int nr_samples)
 Set the number of samples to use during each iteration.
void setSourceFeatures (const FeatureCloudConstPtr &features)
 Provide a boost shared pointer to the source point cloud's feature descriptors.
void setTargetFeatures (const FeatureCloudConstPtr &features)
 Provide a boost shared pointer to the target point cloud's feature descriptors.

Protected Member Functions

virtual void computeTransformation (PointCloudSource &output)
 Rigid transformation computation method.

Protected Attributes

FeatureKdTreePtr feature_tree_
 The KdTree used to compare feature descriptors.
FeatureCloudConstPtr input_features_
 The source point cloud's feature descriptors.
float min_sample_distance_
 The minimum distances between samples.
int nr_samples_
 The number of samples to use during each iteration.
FeatureCloudConstPtr target_features_
 The target point cloud's feature descriptors.

Private Types

typedef pcl::PointCloud< FeatureT > FeatureCloud
typedef FeatureCloud::ConstPtr FeatureCloudConstPtr
typedef FeatureCloud::Ptr FeatureCloudPtr
typedef KdTreeFLANN< FeatureT >
::Ptr 
FeatureKdTreePtr
typedef Registration
< PointSource, PointTarget >
::PointCloudSource 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef Registration
< PointSource, PointTarget >
::PointCloudTarget 
PointCloudTarget
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Private Member Functions

float computeErrorMetric (const PointCloudSource &cloud, float threshold)
 An error metric for that computes the quality of the alignment between the given cloud and the target.
void findSimilarFeatures (const FeatureCloud &input_features, const std::vector< int > &sample_indices, std::vector< int > &corresponding_indices)
 For each of the sample points, find a list of points in the target cloud whose features are similar to the sample points' features. From these, select one randomly which will be considered that sample point's correspondence.
int getRandomIndex (int n)
 Choose a random index between 0 and n-1.
void selectSamples (const PointCloudSource &cloud, int nr_samples, float min_sample_distance, std::vector< int > &sample_indices)
 Select nr_samples sample points from cloud while making sure that their pairwise distances are greater than a user-defined minimum distance, min_sample_distance.

Detailed Description

template<typename PointSource, typename PointTarget, typename FeatureT>
class pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >

SampleConsensusInitialAlignment is an implementation of the initial alignment algorithm described in section IV of "Fast Point Feature Histograms (FPFH) for 3D Registration," Rusu et al.

Author:
Radu Bogdan Rusu, Michael Dixon

Definition at line 52 of file ia_ransac.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef pcl::PointCloud<FeatureT> pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::FeatureCloud [private]

Definition at line 75 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef FeatureCloud::ConstPtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::FeatureCloudConstPtr [private]

Definition at line 77 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef FeatureCloud::Ptr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::FeatureCloudPtr [private]

Definition at line 76 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef KdTreeFLANN<FeatureT>::Ptr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::FeatureKdTreePtr [private]

Definition at line 79 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointCloudSource [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 66 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef PointCloudSource::ConstPtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointCloudSourceConstPtr [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 68 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef PointCloudSource::Ptr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointCloudSourcePtr [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 67 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointCloudTarget [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 70 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef PointIndices::ConstPtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointIndicesConstPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 73 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef PointIndices::Ptr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::PointIndicesPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 72 of file ia_ransac.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget, typename FeatureT>
pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::SampleConsensusInitialAlignment (  )  [inline]

Constructor.

Definition at line 84 of file ia_ransac.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename FeatureT >
float pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::computeErrorMetric ( const PointCloudSource cloud,
float  threshold 
) [inline, private]

An error metric for that computes the quality of the alignment between the given cloud and the target.

Parameters:
cloud the input cloud
threshold distances greater than this value are capped

Definition at line 147 of file ia_ransac.hpp.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::computeTransformation ( PointCloudSource output  )  [inline, protected, virtual]

Rigid transformation computation method.

Parameters:
output the transformed input point cloud dataset using the rigid transformation found

Implements pcl::Registration< PointSource, PointTarget >.

Definition at line 182 of file ia_ransac.hpp.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::findSimilarFeatures ( const FeatureCloud input_features,
const std::vector< int > &  sample_indices,
std::vector< int > &  corresponding_indices 
) [inline, private]

For each of the sample points, find a list of points in the target cloud whose features are similar to the sample points' features. From these, select one randomly which will be considered that sample point's correspondence.

Parameters:
input_features a cloud of feature descriptors
sample_indices the indices of each sample point
corresponding_indices the resulting indices of each sample's corresponding point in the target cloud

Definition at line 126 of file ia_ransac.hpp.

template<typename PointSource, typename PointTarget, typename FeatureT>
float pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::getMinSampleDistance (  )  [inline]

Get the minimum distances between samples, as set by the user.

Definition at line 118 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
int pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::getNumberOfSamples (  )  [inline]

Set the number of samples to use during each iteration, as set by the user.

Definition at line 128 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
int pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::getRandomIndex ( int  n  )  [inline, private]

Choose a random index between 0 and n-1.

Parameters:
n the number of possible indices to choose from

Definition at line 135 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
FeatureCloudConstPtr const pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::getSourceFeatures (  )  [inline]

Get a pointer to the source point cloud's features.

Definition at line 98 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
FeatureCloudConstPtr const pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::getTargetFeatures (  )  [inline]

Get a pointer to the target point cloud's features.

Definition at line 108 of file ia_ransac.h.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::selectSamples ( const PointCloudSource cloud,
int  nr_samples,
float  min_sample_distance,
std::vector< int > &  sample_indices 
) [inline, private]

Select nr_samples sample points from cloud while making sure that their pairwise distances are greater than a user-defined minimum distance, min_sample_distance.

Parameters:
cloud the input point cloud
nr_samples the number of samples to select
min_sample_distance the minimum distance between any two samples
sample_indices the resulting sample indices

Definition at line 67 of file ia_ransac.hpp.

template<typename PointSource, typename PointTarget, typename FeatureT>
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::setMinSampleDistance ( float  min_sample_distance  )  [inline]

Set the minimum distances between samples.

Parameters:
min_sample_distance the minimum distances between samples

Definition at line 114 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::setNumberOfSamples ( int  nr_samples  )  [inline]

Set the number of samples to use during each iteration.

Parameters:
nr_samples the number of samples to use during each iteration

Definition at line 124 of file ia_ransac.h.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::setSourceFeatures ( const FeatureCloudConstPtr features  )  [inline]

Provide a boost shared pointer to the source point cloud's feature descriptors.

Parameters:
features the source point cloud's features

Definition at line 40 of file ia_ransac.hpp.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::setTargetFeatures ( const FeatureCloudConstPtr features  )  [inline]

Provide a boost shared pointer to the target point cloud's feature descriptors.

Parameters:
features the target point cloud's features

Definition at line 53 of file ia_ransac.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename FeatureT>
FeatureKdTreePtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::feature_tree_ [protected]

The KdTree used to compare feature descriptors.

Definition at line 187 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
FeatureCloudConstPtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::input_features_ [protected]

The source point cloud's feature descriptors.

Definition at line 175 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
float pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::min_sample_distance_ [protected]

The minimum distances between samples.

Definition at line 184 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
int pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::nr_samples_ [protected]

The number of samples to use during each iteration.

Definition at line 181 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
FeatureCloudConstPtr pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::target_features_ [protected]

The target point cloud's feature descriptors.

Definition at line 178 of file ia_ransac.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:22 2013