GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point cloud dataset containing points and labels. More...
#include <gfpfh.h>
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. |
GFPFHEstimation estimates the Global Fast Point Feature Histogram (GFPFH) descriptor for a given point cloud dataset containing points and labels.
typedef boost::shared_ptr<const GFPFHEstimation<PointInT, PointLT, PointOutT> > pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::ConstPtr |
Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::PointCloudIn |
Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::PointCloudOut |
Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.
typedef boost::shared_ptr<GFPFHEstimation<PointInT, PointLT, PointOutT> > pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::Ptr |
Reimplemented from pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >.
pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::GFPFHEstimation | ( | ) | [inline] |
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::compute | ( | PointCloudOut & | output | ) |
Overloaded computed method from pcl::Feature.
[out] | output | the resultant point cloud model dataset containing the estimated features |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeDistanceHistogram | ( | const std::vector< float > & | distances, |
std::vector< float > & | histogram | ||
) | [protected] |
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeDistancesToMean | ( | const std::vector< std::vector< int > > & | transition_histograms, |
std::vector< float > & | distances | ||
) | [protected] |
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 ()
output | the resultant point cloud model dataset that contains the PFH feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
float pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeHIKDistance | ( | const std::vector< int > & | histogram, |
const std::vector< float > & | mean_histogram | ||
) | [protected] |
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeMeanHistogram | ( | const std::vector< std::vector< int > > & | histograms, |
std::vector< float > & | mean_histogram | ||
) | [protected] |
void pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::computeTransitionHistograms | ( | const std::vector< std::vector< int > > & | label_histograms, |
std::vector< std::vector< int > > & | transition_histograms | ||
) | [protected] |
int pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::descriptorSize | ( | ) | const [inline] |
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::emptyLabel | ( | ) | const [inline] |
boost::uint32_t pcl::GFPFHEstimation< PointInT, PointNT, PointOutT >::getDominantLabel | ( | const std::vector< int > & | indices | ) | [protected] |
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::getNumberOfClasses | ( | ) | const [inline] |
double pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::getOctreeLeafSize | ( | ) | [inline] |
void pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::setNumberOfClasses | ( | uint32_t | n | ) | [inline] |
void pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::setOctreeLeafSize | ( | double | size | ) | [inline] |
int pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::descriptor_size_ [private] |
uint32_t pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::number_of_classes_ [private] |
double pcl::GFPFHEstimation< PointInT, PointLT, PointOutT >::octree_leaf_size_ [private] |