Public Types | Public Member Functions | Protected Member Functions | Private Attributes
pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > Class Template Reference

GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point cloud dataset containing points and labels. More...

#include <gfpfh.h>

Inheritance diagram for pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const GFPFHEstimation
< PointInT, PointLT, PointOutT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< GFPFHEstimation< PointInT,
PointLT, PointOutT > > 
Ptr

Public Member Functions

void compute (PointCloudOut &output)
 Overloaded computed method from pcl::Feature.
int descriptorSize () const
 Return the size of the descriptor.
uint32_t emptyLabel () const
 Return the empty label value.
uint32_t getNumberOfClasses () const
 Return the number of different classes.
double getOctreeLeafSize ()
 Get the sphere radius used for determining the neighbors.
 GFPFHEstimation ()
 Empty constructor.
void setNumberOfClasses (uint32_t n)
 Set the number of different classes.
void setOctreeLeafSize (double size)
 Set the size of the octree leaves.

Protected Member Functions

void computeDistanceHistogram (const std::vector< float > &distances, std::vector< float > &histogram)
 Compute the binned histogram of distance values.
void computeDistancesToMean (const std::vector< std::vector< int > > &transition_histograms, std::vector< float > &distances)
 Compute the distance of each transition histogram to the mean.
void computeFeature (PointCloudOut &output)
 Estimate the Point Feature Histograms (PFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
float computeHIKDistance (const std::vector< int > &histogram, const std::vector< float > &mean_histogram)
 Return the Intersection Kernel distance between two histograms.
void computeMeanHistogram (const std::vector< std::vector< int > > &histograms, std::vector< float > &mean_histogram)
 Compute the mean histogram of the given set of histograms.
void computeTransitionHistograms (const std::vector< std::vector< int > > &label_histograms, std::vector< std::vector< int > > &transition_histograms)
 Compute the fixed-length histograms of transitions.
uint32_t getDominantLabel (const std::vector< int > &indices)
 Return the dominant label of a set of points.

Private Attributes

int descriptor_size_
 Dimension of the descriptors.
uint32_t number_of_classes_
 Number of possible classes/labels.
double octree_leaf_size_
 Size of octree leaves.

Detailed Description

template<typename PointInT, typename PointLT, typename PointOutT>
class pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >

GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point cloud dataset containing points and labels.

Note:
If you use this code in any academic work, please cite:
Author:
Radu B. Rusu

Definition at line 65 of file gfpfh.h.


Member Typedef Documentation

template<typename PointInT, typename PointLT, typename PointOutT>
typedef boost::shared_ptr<const GFPFHEstimation<PointInT, PointLT, PointOutT> > pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::ConstPtr

Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.

Definition at line 69 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::PointCloudIn

Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.

Definition at line 81 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::PointCloudOut

Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.

Definition at line 80 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
typedef boost::shared_ptr<GFPFHEstimation<PointInT, PointLT, PointOutT> > pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::Ptr

Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.

Definition at line 68 of file gfpfh.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointLT, typename PointOutT>
pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::GFPFHEstimation ( ) [inline]

Empty constructor.

Definition at line 84 of file gfpfh.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::compute ( PointCloudOut output)

Overloaded computed method from pcl::Feature.

Parameters:
[out]outputthe resultant point cloud model dataset containing the estimated features

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 54 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeDistanceHistogram ( const std::vector< float > &  distances,
std::vector< float > &  histogram 
) [protected]

Compute the binned histogram of distance values.

Definition at line 197 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeDistancesToMean ( const std::vector< std::vector< int > > &  transition_histograms,
std::vector< float > &  distances 
) [protected]

Compute the distance of each transition histogram to the mean.

Definition at line 180 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]

Estimate the Point Feature Histograms (PFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Parameters:
outputthe resultant point cloud model dataset that contains the PFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 81 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
float pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeHIKDistance ( const std::vector< int > &  histogram,
const std::vector< float > &  mean_histogram 
) [protected]

Return the Intersection Kernel distance between two histograms.

Definition at line 238 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeMeanHistogram ( const std::vector< std::vector< int > > &  histograms,
std::vector< float > &  mean_histogram 
) [protected]

Compute the mean histogram of the given set of histograms.

Definition at line 222 of file gfpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeTransitionHistograms ( const std::vector< std::vector< int > > &  label_histograms,
std::vector< std::vector< int > > &  transition_histograms 
) [protected]

Compute the fixed-length histograms of transitions.

Definition at line 139 of file gfpfh.hpp.

template<typename PointInT, typename PointLT, typename PointOutT>
int pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::descriptorSize ( ) const [inline]

Return the size of the descriptor.

Definition at line 117 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::emptyLabel ( ) const [inline]

Return the empty label value.

Definition at line 103 of file gfpfh.h.

template<typename PointInT , typename PointNT , typename PointOutT >
boost::uint32_t pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::getDominantLabel ( const std::vector< int > &  indices) [protected]

Return the dominant label of a set of points.

Definition at line 253 of file gfpfh.hpp.

template<typename PointInT, typename PointLT, typename PointOutT>
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::getNumberOfClasses ( ) const [inline]

Return the number of different classes.

Definition at line 107 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
double pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::getOctreeLeafSize ( ) [inline]

Get the sphere radius used for determining the neighbors.

Definition at line 99 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
void pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::setNumberOfClasses ( uint32_t  n) [inline]

Set the number of different classes.

Parameters:
nnumber of different classes.

Definition at line 113 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
void pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::setOctreeLeafSize ( double  size) [inline]

Set the size of the octree leaves.

Definition at line 95 of file gfpfh.h.


Member Data Documentation

template<typename PointInT, typename PointLT, typename PointOutT>
int pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::descriptor_size_ [private]

Dimension of the descriptors.

Definition at line 171 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::number_of_classes_ [private]

Number of possible classes/labels.

Definition at line 168 of file gfpfh.h.

template<typename PointInT, typename PointLT, typename PointOutT>
double pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::octree_leaf_size_ [private]

Size of octree leaves.

Definition at line 165 of file gfpfh.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:22