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

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

#include <pfh.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const PFHEstimation
< PointInT, PointNT, PointOutT > > 
ConstPtr
typedef Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< PFHEstimation< 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 computePointPFHSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, const std::vector< int > &indices, int nr_split, Eigen::VectorXf &pfh_histogram)
 Estimate the PFH (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.
unsigned int getMaximumCacheSize ()
 Get the maximum internal cache size.
bool getUseInternalCache ()
 Get whether the internal cache is used or not for computing the PFH features.
 PFHEstimation ()
 Empty constructor. Sets use_cache_ to false, nr_subdiv_ to 5, and the internal maximum cache size to 1GB.
void setMaximumCacheSize (unsigned int cache_size)
 Set the maximum internal cache size. Defaults to 2GB worth of entries.
void setUseInternalCache (bool use_cache)
 Set whether to use an internal cache mechanism for removing redundant calculations or not.

Protected Member Functions

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 ()

Protected Attributes

float d_pi_
 Float constant = 1.0 / (2.0 * M_PI)
int f_index_ [3]
 Placeholder for a histogram index.
std::map< std::pair< int, int >
, Eigen::Vector4f, std::less
< std::pair< int, int >
>, Eigen::aligned_allocator
< Eigen::Vector4f > > 
feature_map_
 Internal hashmap, used to optimize efficiency of redundant computations.
std::queue< std::pair< int, int > > key_list_
 Queue of pairs saved, used to constrain memory usage.
unsigned int max_cache_size_
 Maximum size of internal cache memory.
int nr_subdiv_
 The number of subdivisions for each angular feature interval.
Eigen::VectorXf pfh_histogram_
 Placeholder for a point's PFH signature.
Eigen::Vector4f pfh_tuple_
 Placeholder for a PFH 4-tuple.
bool use_cache_
 Set to true to use the internal cache for removing redundant computations.

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
class pcl::PFHEstimation< PointInT, PointNT, PointOutT >

PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals.

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

Note:
If you use this code in any academic work, please cite:
Attention:
The convention for PFH features is:
  • if a query point's nearest neighbors cannot be estimated, the PFH feature will be set to NaN (not a number)
  • it is impossible to estimate a PFH 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 PFH 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 82 of file pfh.h.


Member Typedef Documentation

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

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

Definition at line 86 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
typedef Feature<PointInT, PointOutT>::PointCloudIn pcl::PFHEstimation< PointInT, PointNT, PointOutT >::PointCloudIn

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

Definition at line 97 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::PFHEstimation< PointInT, PointNT, PointOutT >::PointCloudOut

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

Definition at line 96 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
typedef boost::shared_ptr<PFHEstimation<PointInT, PointNT, PointOutT> > pcl::PFHEstimation< PointInT, PointNT, PointOutT >::Ptr

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

Definition at line 85 of file pfh.h.


Constructor & Destructor Documentation

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

Empty constructor. Sets use_cache_ to false, nr_subdiv_ to 5, and the internal maximum cache size to 1GB.

Definition at line 102 of file pfh.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::PFHEstimation< 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:
[out]outputthe resultant point cloud model dataset that contains the PFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 157 of file pfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
bool pcl::PFHEstimation< 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)
Note:
For efficiency reasons, we assume that the point data passed to the method is finite.

Definition at line 46 of file pfh.hpp.

template<typename PointInT , typename PointNT , typename PointOutT >
void pcl::PFHEstimation< PointInT, PointNT, PointOutT >::computePointPFHSignature ( const pcl::PointCloud< PointInT > &  cloud,
const pcl::PointCloud< PointNT > &  normals,
const std::vector< int > &  indices,
int  nr_split,
Eigen::VectorXf &  pfh_histogram 
)

Estimate the PFH (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]indicesthe k-neighborhood point indices in the dataset
[in]nr_splitthe number of subdivisions for each angular feature interval
[out]pfh_histogramthe resultant (combinatorial) PFH histogram representing the feature at the query point

Definition at line 58 of file pfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
unsigned int pcl::PFHEstimation< PointInT, PointNT, PointOutT >::getMaximumCacheSize ( ) [inline]

Get the maximum internal cache size.

Definition at line 127 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
bool pcl::PFHEstimation< PointInT, PointNT, PointOutT >::getUseInternalCache ( ) [inline]

Get whether the internal cache is used or not for computing the PFH features.

Definition at line 151 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
void pcl::PFHEstimation< PointInT, PointNT, PointOutT >::setMaximumCacheSize ( unsigned int  cache_size) [inline]

Set the maximum internal cache size. Defaults to 2GB worth of entries.

Parameters:
[in]cache_sizemaximum cache size

Definition at line 120 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
void pcl::PFHEstimation< PointInT, PointNT, PointOutT >::setUseInternalCache ( bool  use_cache) [inline]

Set whether to use an internal cache mechanism for removing redundant calculations or not.

Note:
Depending on how the point cloud is ordered and how the nearest neighbors are estimated, using a cache could have a positive or a negative influence. Please test with and without a cache on your data, and choose whatever works best!

See setMaximumCacheSize for setting the maximum cache size

Parameters:
[in]use_cacheset to true to use the internal cache, false otherwise

Definition at line 144 of file pfh.h.


Member Data Documentation

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

Float constant = 1.0 / (2.0 * M_PI)

Definition at line 208 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
int pcl::PFHEstimation< PointInT, PointNT, PointOutT >::f_index_[3] [protected]

Placeholder for a histogram index.

Definition at line 205 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
std::map<std::pair<int, int>, Eigen::Vector4f, std::less<std::pair<int, int> >, Eigen::aligned_allocator<Eigen::Vector4f> > pcl::PFHEstimation< PointInT, PointNT, PointOutT >::feature_map_ [protected]

Internal hashmap, used to optimize efficiency of redundant computations.

Definition at line 211 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
std::queue<std::pair<int, int> > pcl::PFHEstimation< PointInT, PointNT, PointOutT >::key_list_ [protected]

Queue of pairs saved, used to constrain memory usage.

Definition at line 214 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
unsigned int pcl::PFHEstimation< PointInT, PointNT, PointOutT >::max_cache_size_ [protected]

Maximum size of internal cache memory.

Definition at line 217 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
int pcl::PFHEstimation< PointInT, PointNT, PointOutT >::nr_subdiv_ [protected]

The number of subdivisions for each angular feature interval.

Definition at line 196 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
Eigen::VectorXf pcl::PFHEstimation< PointInT, PointNT, PointOutT >::pfh_histogram_ [protected]

Placeholder for a point's PFH signature.

Definition at line 199 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
Eigen::Vector4f pcl::PFHEstimation< PointInT, PointNT, PointOutT >::pfh_tuple_ [protected]

Placeholder for a PFH 4-tuple.

Definition at line 202 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
bool pcl::PFHEstimation< PointInT, PointNT, PointOutT >::use_cache_ [protected]

Set to true to use the internal cache for removing redundant computations.

Definition at line 220 of file pfh.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:00