Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
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.

Classes

class  ErrorFunctor
class  HuberPenalty
class  TruncatedError

Public Types

typedef boost::shared_ptr
< const
SampleConsensusInitialAlignment
< PointSource, PointTarget,
FeatureT > > 
ConstPtr
typedef pcl::PointCloud< FeatureTFeatureCloud
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
typedef boost::shared_ptr
< SampleConsensusInitialAlignment
< PointSource, PointTarget,
FeatureT > > 
Ptr

Public Member Functions

int getCorrespondenceRandomness ()
 Get the number of neighbors used when selecting a random feature correspondence, as set by the user.
boost::shared_ptr< ErrorFunctorgetErrorFunction ()
 Get a shared pointer to the ErrorFunctor that is to be minimized.
float getMinSampleDistance ()
 Get the minimum distances between samples, as set by the user.
int getNumberOfSamples ()
 Get 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 setCorrespondenceRandomness (int k)
 Set the number of neighbors to use when selecting a random feature correspondence. A higher value will add more randomness to the feature matching.
void setErrorFunction (const boost::shared_ptr< ErrorFunctor > &error_functor)
 Specify the error function to minimize.
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

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.
virtual void computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
 Rigid transformation computation method.
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.

Protected Attributes

boost::shared_ptr< ErrorFunctorerror_functor_
FeatureKdTreePtr feature_tree_
 The KdTree used to compare feature descriptors.
FeatureCloudConstPtr input_features_
 The source point cloud's feature descriptors.
int k_correspondences_
 The number of neighbors to use when selecting a random feature correspondence.
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.

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:
Michael Dixon, Radu B. Rusu

Definition at line 54 of file ia_ransac.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef boost::shared_ptr<const SampleConsensusInitialAlignment<PointSource, PointTarget, FeatureT> > pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::ConstPtr

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

Definition at line 84 of file ia_ransac.h.

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

Definition at line 79 of file ia_ransac.h.

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

Definition at line 81 of file ia_ransac.h.

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

Definition at line 80 of file ia_ransac.h.

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

Definition at line 130 of file ia_ransac.h.

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

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

Definition at line 70 of file ia_ransac.h.

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

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

Definition at line 72 of file ia_ransac.h.

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

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

Definition at line 71 of file ia_ransac.h.

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

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

Definition at line 74 of file ia_ransac.h.

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

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 77 of file ia_ransac.h.

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

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 76 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
typedef boost::shared_ptr<SampleConsensusInitialAlignment<PointSource, PointTarget, FeatureT> > pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::Ptr

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

Definition at line 83 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 132 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 
) [protected]

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

Parameters:
cloudthe input cloud
thresholddistances greater than this value are capped

Definition at line 153 of file ia_ransac.hpp.

template<typename PointSource , typename PointTarget , typename FeatureT >
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::computeTransformation ( PointCloudSource output,
const Eigen::Matrix4f &  guess 
) [protected, virtual]

Rigid transformation computation method.

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

Definition at line 175 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 
) [protected]

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_featuresa cloud of feature descriptors
sample_indicesthe indices of each sample point
corresponding_indicesthe resulting indices of each sample's corresponding point in the target cloud

Definition at line 132 of file ia_ransac.hpp.

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

Get the number of neighbors used when selecting a random feature correspondence, as set by the user.

Definition at line 195 of file ia_ransac.h.

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

Get a shared pointer to the ErrorFunctor that is to be minimized.

Returns:
A shared pointer to a subclass of SampleConsensusInitialAlignment::ErrorFunctor

Definition at line 208 of file ia_ransac.h.

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 174 of file ia_ransac.h.

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

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

Definition at line 184 of file ia_ransac.h.

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

Choose a random index between 0 and n-1.

Parameters:
nthe number of possible indices to choose from

Definition at line 215 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 154 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 164 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 
) [protected]

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:
cloudthe input point cloud
nr_samplesthe number of samples to select
min_sample_distancethe minimum distance between any two samples
sample_indicesthe resulting sample indices

Definition at line 73 of file ia_ransac.hpp.

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

Set the number of neighbors to use when selecting a random feature correspondence. A higher value will add more randomness to the feature matching.

Parameters:
kthe number of neighbors to use when selecting a random feature correspondence.

Definition at line 191 of file ia_ransac.h.

template<typename PointSource, typename PointTarget, typename FeatureT>
void pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::setErrorFunction ( const boost::shared_ptr< ErrorFunctor > &  error_functor) [inline]

Specify the error function to minimize.

Note:
This call is optional. TruncatedError will be used by default
Parameters:
[in]error_functora shared pointer to a subclass of SampleConsensusInitialAlignment::ErrorFunctor

Definition at line 202 of file ia_ransac.h.

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_distancethe minimum distances between samples

Definition at line 170 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_samplesthe number of samples to use during each iteration

Definition at line 180 of file ia_ransac.h.

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

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

Parameters:
featuresthe source point cloud's features

Definition at line 48 of file ia_ransac.hpp.

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

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

Parameters:
featuresthe target point cloud's features

Definition at line 60 of file ia_ransac.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename FeatureT>
boost::shared_ptr<ErrorFunctor> pcl::SampleConsensusInitialAlignment< PointSource, PointTarget, FeatureT >::error_functor_ [protected]

Definition at line 271 of file ia_ransac.h.

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 268 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 253 of file ia_ransac.h.

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

The number of neighbors to use when selecting a random feature correspondence.

Definition at line 265 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 262 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 259 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 256 of file ia_ransac.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:34