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

VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud dataset containing points and normals. The default VFH implementation uses 45 binning subdivisions for each of the three extended FPFH values, plus another 45 binning subdivisions for the distances between each point and the centroid and 128 binning subdivisions for the viewpoint component, which results in a 308-byte array of float values. These are stored in a pcl::VFHSignature308 point type. A major difference between the PFH/FPFH descriptors and VFH, is that for a given point cloud dataset, only a single VFH descriptor will be estimated (vfhs->points.size() should be 1), while the resultant PFH/FPFH data will have the same number of entries as the number of points in the cloud. More...

#include <vfh.h>

Inheritance diagram for pcl::VFHEstimation< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const VFHEstimation
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< VFHEstimation< PointInT,
PointNT, PointOutT > > 
Ptr

Public Member Functions

void compute (PointCloudOut &output)
 Overloaded computed method from pcl::Feature.
void computePointSPFHSignature (const Eigen::Vector4f &centroid_p, const Eigen::Vector4f &centroid_n, const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const std::vector< int > &indices)
 Estimate the SPFH (Simple Point Feature Histograms) signatures of the angular (f1, f2, f3) and distance (f4) features for a given point from its neighborhood.
void getViewPoint (float &vpx, float &vpy, float &vpz)
 Get the viewpoint.
void setCentroidToUse (const Eigen::Vector3f &centroid)
 Set centroid_to_use_.
void setFillSizeComponent (bool fill_size)
 set size_component_
void setNormalizeBins (bool normalize)
 set normalize_bins_
void setNormalizeDistance (bool normalize)
 set normalize_distances_
void setNormalToUse (const Eigen::Vector3f &normal)
 Set the normal to use.
void setUseGivenCentroid (bool use)
 Set use_given_centroid_.
void setUseGivenNormal (bool use)
 Set use_given_normal_.
void setViewPoint (float vpx, float vpy, float vpz)
 Set the viewpoint.
 VFHEstimation ()
 Empty constructor.

Protected Member Functions

bool initCompute ()
 This method should get called before starting the actual computation.

Protected Attributes

Eigen::Vector4f centroid_to_use_
 Centroid to be used to computed VFH. Default, the centroid of the whole point cloud.
Eigen::VectorXf hist_f1_
 Placeholder for the f1 histogram.
Eigen::VectorXf hist_f2_
 Placeholder for the f2 histogram.
Eigen::VectorXf hist_f3_
 Placeholder for the f3 histogram.
Eigen::VectorXf hist_f4_
 Placeholder for the f4 histogram.
Eigen::VectorXf hist_vp_
 Placeholder for the vp histogram.
Eigen::Vector4f normal_to_use_
 Normal to be used to computed VFH. Default, the average normal of the whole point cloud.
bool normalize_bins_
 Normalize bins by the number the total number of points.
bool normalize_distances_
 Normalize the shape distribution component of VFH.
bool size_component_
 Activate or deactivate the size component of VFH.
bool use_given_centroid_
 Use the centroid_to_use_.
bool use_given_normal_
 Use the normal_to_use_.

Private Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the Viewpoint Feature Histograms (VFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Private Attributes

float d_pi_
 Float constant = 1.0 / (2.0 * M_PI)
int nr_bins_f1_
 The number of subdivisions for each feature interval.
int nr_bins_f2_
int nr_bins_f3_
int nr_bins_f4_
int nr_bins_vp_
float vpx_
 Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0.
float vpy_
float vpz_

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
class pcl::VFHEstimation< PointInT, PointNT, PointOutT >

VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud dataset containing points and normals. The default VFH implementation uses 45 binning subdivisions for each of the three extended FPFH values, plus another 45 binning subdivisions for the distances between each point and the centroid and 128 binning subdivisions for the viewpoint component, which results in a 308-byte array of float values. These are stored in a pcl::VFHSignature308 point type. A major difference between the PFH/FPFH descriptors and VFH, is that for a given point cloud dataset, only a single VFH descriptor will be estimated (vfhs->points.size() should be 1), while the resultant PFH/FPFH data will have the same number of entries as the number of points in the cloud.

Note:
If you use this code in any academic work, please cite:
Note:
The code is stateful as we do not expect this class to be multicore parallelized. Please look at FPFHEstimationOMP for an example of a parallel implementation of the FPFH (Fast Point Feature Histogram).
Author:
Radu B. Rusu

Definition at line 71 of file vfh.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef boost::shared_ptr<const VFHEstimation<PointInT, PointNT, PointOutT> > pcl::VFHEstimation< PointInT, PointNT, PointOutT >::ConstPtr

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 85 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::VFHEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 83 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
typedef boost::shared_ptr<VFHEstimation<PointInT, PointNT, PointOutT> > pcl::VFHEstimation< PointInT, PointNT, PointOutT >::Ptr

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 84 of file vfh.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
pcl::VFHEstimation< PointInT, PointNT, PointOutT >::VFHEstimation ( ) [inline]

Empty constructor.

Definition at line 89 of file vfh.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::VFHEstimation< 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 65 of file vfh.hpp.

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

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

Parameters:
[out]outputthe resultant point cloud model dataset that contains the VFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 182 of file vfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::computePointSPFHSignature ( const Eigen::Vector4f &  centroid_p,
const Eigen::Vector4f &  centroid_n,
const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
const std::vector< int > &  indices 
)

Estimate the SPFH (Simple Point Feature Histograms) signatures of the angular (f1, f2, f3) and distance (f4) features for a given point from its neighborhood.

Parameters:
[in]centroid_pthe centroid point
[in]centroid_nthe centroid normal
[in]cloudthe dataset containing the XYZ Cartesian coordinates of the two points
[in]normalsthe dataset containing the surface normals at each point in cloud
[in]indicesthe k-neighborhood point indices in the dataset

Definition at line 92 of file vfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::getViewPoint ( float &  vpx,
float &  vpy,
float &  vpz 
) [inline]

Get the viewpoint.

Definition at line 134 of file vfh.h.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::initCompute ( ) [protected, virtual]

This method should get called before starting the actual computation.

Reimplemented from pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >.

Definition at line 51 of file vfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setCentroidToUse ( const Eigen::Vector3f &  centroid) [inline]

Set centroid_to_use_.

Parameters:
[in]centroidCentroid to be used in the VFH computation. It is used to compute the distances from all points to this centroid.

Definition at line 174 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setFillSizeComponent ( bool  fill_size) [inline]

set size_component_

Parameters:
[in]fill_sizeTrue if the 4th component of VFH (shape distribution component) needs to be filled. Otherwise, it is set to zero.

Definition at line 203 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setNormalizeBins ( bool  normalize) [inline]

set normalize_bins_

Parameters:
[in]normalizeIf true, the VFH bins are normalized using the total number of points

Definition at line 183 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setNormalizeDistance ( bool  normalize) [inline]

set normalize_distances_

Parameters:
[in]normalizeIf true, the 4th component of VFH (shape distribution component) get normalized by the maximum size between the centroid and the point cloud

Definition at line 193 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setNormalToUse ( const Eigen::Vector3f &  normal) [inline]

Set the normal to use.

Parameters:
[in]normalSets the normal to be used in the VFH computation. It is is used to build the Darboux Coordinate system.

Definition at line 155 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setUseGivenCentroid ( bool  use) [inline]

Set use_given_centroid_.

Parameters:
[in]useSet to true if you want to use the centroid passed through setCentroidToUse(centroid)

Definition at line 164 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setUseGivenNormal ( bool  use) [inline]

Set use_given_normal_.

Parameters:
[in]useSet to true if you want to use the normal passed to setNormalUse(normal)

Definition at line 145 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setViewPoint ( float  vpx,
float  vpy,
float  vpz 
) [inline]

Set the viewpoint.

Parameters:
[in]vpxthe X coordinate of the viewpoint
[in]vpythe Y coordinate of the viewpoint
[in]vpzthe Z coordinate of the viewpoint

Definition at line 125 of file vfh.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::Vector4f pcl::VFHEstimation< PointInT, PointNT, PointOutT >::centroid_to_use_ [protected]

Centroid to be used to computed VFH. Default, the centroid of the whole point cloud.

Definition at line 251 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::VFHEstimation< PointInT, PointNT, PointOutT >::d_pi_ [private]

Float constant = 1.0 / (2.0 * M_PI)

Definition at line 268 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::VectorXf pcl::VFHEstimation< PointInT, PointNT, PointOutT >::hist_f1_ [protected]

Placeholder for the f1 histogram.

Definition at line 238 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::VectorXf pcl::VFHEstimation< PointInT, PointNT, PointOutT >::hist_f2_ [protected]

Placeholder for the f2 histogram.

Definition at line 240 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::VectorXf pcl::VFHEstimation< PointInT, PointNT, PointOutT >::hist_f3_ [protected]

Placeholder for the f3 histogram.

Definition at line 242 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::VectorXf pcl::VFHEstimation< PointInT, PointNT, PointOutT >::hist_f4_ [protected]

Placeholder for the f4 histogram.

Definition at line 244 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::VectorXf pcl::VFHEstimation< PointInT, PointNT, PointOutT >::hist_vp_ [protected]

Placeholder for the vp histogram.

Definition at line 246 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
Eigen::Vector4f pcl::VFHEstimation< PointInT, PointNT, PointOutT >::normal_to_use_ [protected]

Normal to be used to computed VFH. Default, the average normal of the whole point cloud.

Definition at line 249 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::normalize_bins_ [protected]

Normalize bins by the number the total number of points.

Definition at line 260 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::normalize_distances_ [protected]

Normalize the shape distribution component of VFH.

Definition at line 262 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
int pcl::VFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f1_ [private]

The number of subdivisions for each feature interval.

Definition at line 217 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
int pcl::VFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f2_ [private]

Definition at line 217 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
int pcl::VFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f3_ [private]

Definition at line 217 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
int pcl::VFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f4_ [private]

Definition at line 217 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
int pcl::VFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_vp_ [private]

Definition at line 217 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::size_component_ [protected]

Activate or deactivate the size component of VFH.

Definition at line 264 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::use_given_centroid_ [protected]

Use the centroid_to_use_.

Definition at line 258 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
bool pcl::VFHEstimation< PointInT, PointNT, PointOutT >::use_given_normal_ [protected]

Use the normal_to_use_.

Definition at line 256 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::VFHEstimation< PointInT, PointNT, PointOutT >::vpx_ [private]

Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0.

Definition at line 222 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::VFHEstimation< PointInT, PointNT, PointOutT >::vpy_ [private]

Definition at line 222 of file vfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
float pcl::VFHEstimation< PointInT, PointNT, PointOutT >::vpz_ [private]

Definition at line 222 of file vfh.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:37