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 Feature< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Feature< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

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.
void getNrSubdivisions (int &nr_subdiv)
 Get the number of subdivisions for the feature interval.
 PFHEstimation ()
 Empty constructor.
void setNrSubdivisions (int nr_subdiv)
 Set the number of subdivisions for each angular feature interval.

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

Private Attributes

float d_pi_
 Float constant = 1.0 / (2.0 * M_PI).
int f_index_ [3]
 Placeholder for a histogram index.
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.

Detailed Description

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

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

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 examples on parallel implementations of the FPFH (Fast Point Feature Histogram).
Author:
Radu Bogdan Rusu

Definition at line 87 of file pfh.h.


Member Typedef Documentation

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

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

Definition at line 99 of file pfh.h.

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

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

Definition at line 98 of file pfh.h.


Constructor & Destructor Documentation

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

Empty constructor.

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  )  [inline, 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:
output the resultant point cloud model dataset that contains the PFH feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 165 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 
) [inline]

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:
cloud the dataset containing the XYZ Cartesian coordinates of the two points
normals the dataset containing the surface normals (assuming normalized vectors) at each point in cloud
p_idx the index of the first point (source)
q_idx the index of the second point (target)
f1 the first angular feature (angle between the projection of nq_idx and u)
f2 the second angular feature (angle between nq_idx and v)
f3 the third angular feature (angle between np_idx and |p_idx - q_idx|)
f4 the distance feature (p_idx - q_idx)

Definition at line 45 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 
) [inline]

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:
cloud the dataset containing the XYZ Cartesian coordinates of the two points
normals the dataset containing the surface normals at each point in cloud
indices the k-neighborhood point indices in the dataset
nr_split the number of subdivisions for each angular feature interval
pfh_histogram the resultant (combinatorial) PFH histogram representing the feature at the query point

Definition at line 111 of file pfh.hpp.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::PFHEstimation< PointInT, PointNT, PointOutT >::getNrSubdivisions ( int &  nr_subdiv  )  [inline]

Get the number of subdivisions for the feature interval.

Parameters:
nr_subdiv the resultant number of subdivisions as set by the user

Definition at line 146 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::PFHEstimation< PointInT, PointNT, PointOutT >::setNrSubdivisions ( int  nr_subdiv  )  [inline]

Set the number of subdivisions for each angular feature interval.

Parameters:
nr_subdiv the number of subdivisions

Definition at line 140 of file pfh.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
float pcl::PFHEstimation< PointInT, PointNT, PointOutT >::d_pi_ [private]

Float constant = 1.0 / (2.0 * M_PI).

Definition at line 172 of file pfh.h.

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

Placeholder for a histogram index.

Definition at line 169 of file pfh.h.

template<typename PointInT, typename PointNT, typename PointOutT>
int pcl::PFHEstimation< PointInT, PointNT, PointOutT >::nr_subdiv_ [private]

The number of subdivisions for each angular feature interval.

Definition at line 160 of file pfh.h.

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

Placeholder for a point's PFH signature.

Definition at line 163 of file pfh.h.

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

Placeholder for a PFH 4-tuple.

Definition at line 166 of file pfh.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:20 2013