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.
More...
#include <vfh.h>
List of all members.
Public Types |
typedef Feature< PointInT,
PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions |
void | computePointSPFHSignature (const Eigen::Vector4f ¢roid_p, const Eigen::Vector4f ¢roid_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 | getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3, int &nr_bins_f4) |
| Get the number of subdivisions for each feature interval.
|
void | getNrViewpointSubdivisions (int &nr_bins) |
| Get the number of subdivisions for the viewpoint feature interval.
|
void | getViewPoint (float &vpx, float &vpy, float &vpz) |
| Get the viewpoint.
|
void | setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3, int nr_bins_f4) |
| Set the number of subdivisions for each feature interval.
|
void | setNrViewpointSubdivisions (int nr_bins) |
| Set the number of subdivisions for the viewpoint feature interval.
|
void | setViewPoint (float vpx, float vpy, float vpz) |
| Set the viewpoint.
|
| VFHEstimation () |
| Empty constructor.
|
Protected Attributes |
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.
|
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>
class pcl::VFHEstimation< PointInT, PointNT, PointOutT >
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) 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, G. Bradski, R. Thibaux, J. Hsu. Fast 3D Recognition and Pose Using the Viewpoint Feature Histogram. In Proceedings of International Conference on Intelligent Robots and Systems (IROS) Taipei, Taiwan, October 18-22 2010.
- 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 64 of file vfh.h.
Member Typedef Documentation
template<typename PointInT, typename PointNT, typename PointOutT>
Constructor & Destructor Documentation
template<typename PointInT, typename PointNT, typename PointOutT>
Empty constructor.
Definition at line 78 of file vfh.h.
Member Function Documentation
template<typename PointInT , typename PointNT , typename PointOutT >
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:
-
| output | the resultant point cloud model dataset that contains the VFH feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 117 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 | |
|
) |
| | [inline] |
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:
-
| centroid_p | the centroid point |
| centroid_n | the centroid normal |
| 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 |
Definition at line 47 of file vfh.hpp.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::getNrSubdivisions |
( |
int & |
nr_bins_f1, |
|
|
int & |
nr_bins_f2, |
|
|
int & |
nr_bins_f3, |
|
|
int & |
nr_bins_f4 | |
|
) |
| | [inline] |
Get the number of subdivisions for each feature interval.
Definition at line 116 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::getNrViewpointSubdivisions |
( |
int & |
nr_bins |
) |
[inline] |
Get the number of subdivisions for the viewpoint feature interval.
Definition at line 130 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::getViewPoint |
( |
float & |
vpx, |
|
|
float & |
vpy, |
|
|
float & |
vpz | |
|
) |
| | [inline] |
Get the viewpoint.
Definition at line 147 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setNrSubdivisions |
( |
int |
nr_bins_f1, |
|
|
int |
nr_bins_f2, |
|
|
int |
nr_bins_f3, |
|
|
int |
nr_bins_f4 | |
|
) |
| | [inline] |
Set the number of subdivisions for each feature interval.
- Parameters:
-
| nr_bins_f1 | number of subdivisions for the first angular feature |
| nr_bins_f2 | number of subdivisions for the second angular feature |
| nr_bins_f3 | number of subdivisions for the third angular feature |
| nr_bins_f4 | number of subdivisions for the fourth distance feature |
Definition at line 106 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setNrViewpointSubdivisions |
( |
int |
nr_bins |
) |
[inline] |
Set the number of subdivisions for the viewpoint feature interval.
- Parameters:
-
| nr_bins | number of subdivisions for the viewpoint feature interval. |
Definition at line 127 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
void pcl::VFHEstimation< PointInT, PointNT, PointOutT >::setViewPoint |
( |
float |
vpx, |
|
|
float |
vpy, |
|
|
float |
vpz | |
|
) |
| | [inline] |
Set the viewpoint.
- Parameters:
-
| vpx | the X coordinate of the viewpoint |
| vpy | the Y coordinate of the viewpoint |
| vpz | the Z coordinate of the viewpoint |
Definition at line 138 of file vfh.h.
Member Data Documentation
template<typename PointInT, typename PointNT, typename PointOutT>
Float constant = 1.0 / (2.0 * M_PI).
Definition at line 184 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for the f1 histogram.
Definition at line 172 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for the f2 histogram.
Definition at line 174 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for the f3 histogram.
Definition at line 176 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for the f4 histogram.
Definition at line 178 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
Placeholder for the vp histogram.
Definition at line 180 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
The number of subdivisions for each feature interval.
Definition at line 157 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
template<typename PointInT, typename PointNT, typename PointOutT>
template<typename PointInT, typename PointNT, typename PointOutT>
template<typename PointInT, typename PointNT, typename PointOutT>
template<typename PointInT, typename PointNT, typename PointOutT>
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 161 of file vfh.h.
template<typename PointInT, typename PointNT, typename PointOutT>
template<typename PointInT, typename PointNT, typename PointOutT>
The documentation for this class was generated from the following files: