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>
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:
-
R.B. Rusu, N. Blodow, Z.C. Marton, M. Beetz. Aligning Point Cloud Views using Persistent Feature Histograms. In Proceedings of the 21st IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Nice, France, September 22-26 2008.
-
R.B. Rusu, Z.C. Marton, N. Blodow, M. Beetz. Learning Informative Point Classes for the Acquisition of Object Model Maps. In Proceedings of the 10th International Conference on Control, Automation, Robotics and Vision (ICARCV), Hanoi, Vietnam, December 17-20 2008.
- 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>
template<typename PointInT, typename PointNT, typename PointOutT>
Constructor & Destructor Documentation
template<typename PointInT, typename PointNT, typename PointOutT>
Empty constructor.
Definition at line 102 of file pfh.h.
Member Function Documentation
template<typename PointInT , typename PointNT , typename PointOutT >
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 constant = 1.0 / (2.0 * M_PI).
Definition at line 172 of file pfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for a histogram index.
Definition at line 169 of file pfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
The number of subdivisions for each angular feature interval.
Definition at line 160 of file pfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for a point's PFH signature.
Definition at line 163 of file pfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
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: