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

FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals. More...

#include <fpfh.h>

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

List of all members.

Public Types

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

Public Member Functions

bool computePairFeatures (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
 Compute the 4-tuple representation containing the three angles and one distance between two points represented by Cartesian coordinates and normals.
void computePointSPFHSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int row, const std::vector< int > &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
 Estimate the SPFH (Simple Point Feature Histograms) individual signatures of the three angular (f1, f2, f3) features for a given point based on its spatial neighborhood of 3D points with normals.
 FPFHEstimation ()
 Empty constructor.
void getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3)
 Get the number of subdivisions for each angular feature interval.
void setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3)
 Set the number of subdivisions for each angular feature interval.
void weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const std::vector< int > &indices, const std::vector< float > &dists, Eigen::VectorXf &fpfh_histogram)
 Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH (Fast Point Feature Histogram) for a given point based on its 3D spatial neighborhood.

Protected Member Functions

void computeFeature (PointCloudOut &output)
 Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
void computeSPFHSignatures (std::vector< int > &spf_hist_lookup, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
 Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud.

Protected Attributes

float d_pi_
 Float constant = 1.0 / (2.0 * M_PI)
Eigen::VectorXf fpfh_histogram_
 Placeholder for a point's FPFH signature.
Eigen::MatrixXf hist_f1_
 Placeholder for the f1 histogram.
Eigen::MatrixXf hist_f2_
 Placeholder for the f2 histogram.
Eigen::MatrixXf hist_f3_
 Placeholder for the f3 histogram.
int nr_bins_f1_
 The number of subdivisions for each angular feature interval.
int nr_bins_f2_
int nr_bins_f3_

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
class pcl::FPFHEstimation< PointInT, PointNT, PointOutT >

FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals.

A commonly used type for PointOutT is pcl::FPFHSignature33.

Note:
If you use this code in any academic work, please cite:
Attention:
The convention for FPFH features is:
  • if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN (not a number)
  • it is impossible to estimate a FPFH descriptor for a point that doesn't have finite 3D coordinates. Therefore, any point that contains NaN data on x, y, or z, will have its FPFH feature property set to NaN.
Note:
The code is stateful as we do not expect this class to be multicore parallelized. Please look at FPFHEstimationOMP for examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
Author:
Radu B. Rusu

Definition at line 80 of file fpfh.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
typedef boost::shared_ptr<const FPFHEstimation<PointInT, PointNT, PointOutT> > pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::ConstPtr
template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::PointCloudOut
template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
typedef boost::shared_ptr<FPFHEstimation<PointInT, PointNT, PointOutT> > pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::Ptr

Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 97 of file fpfh.h.


Member Function Documentation

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

Estimate the Fast Point Feature Histograms (FPFH) 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 FPFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Reimplemented in pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, and pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >.

Definition at line 234 of file fpfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT >
bool pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computePairFeatures ( const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
int  p_idx,
int  q_idx,
float &  f1,
float &  f2,
float &  f3,
float &  f4 
)

Compute the 4-tuple representation containing the three angles and one distance between two points represented by Cartesian coordinates and normals.

Note:
For explanations about the features, please see the literature mentioned above (the order of the features might be different).
Parameters:
[in]cloudthe dataset containing the XYZ Cartesian coordinates of the two points
[in]normalsthe dataset containing the surface normals (assuming normalized vectors) at each point in cloud
[in]p_idxthe index of the first point (source)
[in]q_idxthe index of the second point (target)
[out]f1the first angular feature (angle between the projection of nq_idx and u)
[out]f2the second angular feature (angle between nq_idx and v)
[out]f3the third angular feature (angle between np_idx and |p_idx - q_idx|)
[out]f4the distance feature (p_idx - q_idx)

Definition at line 49 of file fpfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT >
void pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computePointSPFHSignature ( const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
int  p_idx,
int  row,
const std::vector< int > &  indices,
Eigen::MatrixXf &  hist_f1,
Eigen::MatrixXf &  hist_f2,
Eigen::MatrixXf &  hist_f3 
)

Estimate the SPFH (Simple Point Feature Histograms) individual signatures of the three angular (f1, f2, f3) features for a given point based on its spatial neighborhood of 3D points with normals.

Parameters:
[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]p_idxthe index of the query point (source)
[in]rowthe index row in feature histogramms
[in]indicesthe k-neighborhood point indices in the dataset
[out]hist_f1the resultant SPFH histogram for feature f1
[out]hist_f2the resultant SPFH histogram for feature f2
[out]hist_f3the resultant SPFH histogram for feature f3

Definition at line 61 of file fpfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::computeSPFHSignatures ( std::vector< int > &  spf_hist_lookup,
Eigen::MatrixXf &  hist_f1,
Eigen::MatrixXf &  hist_f2,
Eigen::MatrixXf &  hist_f3 
) [protected]

Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud.

Parameters:
[out]spfh_hist_lookupa lookup table for all the SPF feature indices
[out]hist_f1the resultant SPFH histogram for feature f1
[out]hist_f2the resultant SPFH histogram for feature f2
[out]hist_f3the resultant SPFH histogram for feature f3

Definition at line 174 of file fpfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
void pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::getNrSubdivisions ( int &  nr_bins_f1,
int &  nr_bins_f2,
int &  nr_bins_f3 
) [inline]

Get the number of subdivisions for each angular feature interval.

Parameters:
[out]nr_bins_f1number of subdivisions for the first angular feature
[out]nr_bins_f2number of subdivisions for the second angular feature
[out]nr_bins_f3number of subdivisions for the third angular feature

Definition at line 175 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
void pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::setNrSubdivisions ( int  nr_bins_f1,
int  nr_bins_f2,
int  nr_bins_f3 
) [inline]

Set the number of subdivisions for each angular feature interval.

Parameters:
[in]nr_bins_f1number of subdivisions for the first angular feature
[in]nr_bins_f2number of subdivisions for the second angular feature
[in]nr_bins_f3number of subdivisions for the third angular feature

Definition at line 162 of file fpfh.h.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::weightPointSPFHSignature ( const Eigen::MatrixXf &  hist_f1,
const Eigen::MatrixXf &  hist_f2,
const Eigen::MatrixXf &  hist_f3,
const std::vector< int > &  indices,
const std::vector< float > &  dists,
Eigen::VectorXf &  fpfh_histogram 
)

Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH (Fast Point Feature Histogram) for a given point based on its 3D spatial neighborhood.

Parameters:
[in]hist_f1the histogram feature vector of f1 values over the given patch
[in]hist_f2the histogram feature vector of f2 values over the given patch
[in]hist_f3the histogram feature vector of f3 values over the given patch
[in]indicesthe point indices of p_idx's k-neighborhood in the point cloud
[in]diststhe distances from p_idx to all its k-neighbors
[out]fpfh_histogramthe resultant FPFH histogram representing the feature at the query point

Definition at line 106 of file fpfh.hpp.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
float pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::d_pi_ [protected]

Float constant = 1.0 / (2.0 * M_PI)

Definition at line 218 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
Eigen::VectorXf pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::fpfh_histogram_ [protected]

Placeholder for a point's FPFH signature.

Definition at line 215 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
Eigen::MatrixXf pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::hist_f1_ [protected]

Placeholder for the f1 histogram.

Definition at line 206 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
Eigen::MatrixXf pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::hist_f2_ [protected]

Placeholder for the f2 histogram.

Definition at line 209 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
Eigen::MatrixXf pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::hist_f3_ [protected]

Placeholder for the f3 histogram.

Definition at line 212 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
int pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f1_ [protected]

The number of subdivisions for each angular feature interval.

Reimplemented in pcl::FPFHEstimationOMP< PointInT, PointNT, PointOutT >, and pcl::FPFHEstimationOMP< PointType, pcl::Normal, pcl::FPFHSignature33 >.

Definition at line 203 of file fpfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
int pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f2_ [protected]
template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
int pcl::FPFHEstimation< PointInT, PointNT, PointOutT >::nr_bins_f3_ [protected]

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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:40:56