Public Types |
typedef boost::shared_ptr
< const VFHEstimation
< PointInT, PointNT, PointOutT > > | ConstPtr |
typedef Feature< PointInT,
PointOutT >::PointCloudOut | PointCloudOut |
typedef boost::shared_ptr
< VFHEstimation< PointInT,
PointNT, PointOutT > > | Ptr |
Public Member Functions |
void | compute (PointCloudOut &output) |
| Overloaded computed method from pcl::Feature.
|
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 | getViewPoint (float &vpx, float &vpy, float &vpz) |
| Get the viewpoint.
|
void | setCentroidToUse (const Eigen::Vector3f ¢roid) |
| Set centroid_to_use_.
|
void | setFillSizeComponent (bool fill_size) |
| set size_component_
|
void | setNormalizeBins (bool normalize) |
| set normalize_bins_
|
void | setNormalizeDistance (bool normalize) |
| set normalize_distances_
|
void | setNormalToUse (const Eigen::Vector3f &normal) |
| Set the normal to use.
|
void | setUseGivenCentroid (bool use) |
| Set use_given_centroid_.
|
void | setUseGivenNormal (bool use) |
| Set use_given_normal_.
|
void | setViewPoint (float vpx, float vpy, float vpz) |
| Set the viewpoint.
|
| VFHEstimation () |
| Empty constructor.
|
Protected Member Functions |
bool | initCompute () |
| This method should get called before starting the actual computation.
|
Protected Attributes |
Eigen::Vector4f | centroid_to_use_ |
| Centroid to be used to computed VFH. Default, the centroid of the whole point cloud.
|
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.
|
Eigen::Vector4f | normal_to_use_ |
| Normal to be used to computed VFH. Default, the average normal of the whole point cloud.
|
bool | normalize_bins_ |
| Normalize bins by the number the total number of points.
|
bool | normalize_distances_ |
| Normalize the shape distribution component of VFH.
|
bool | size_component_ |
| Activate or deactivate the size component of VFH.
|
bool | use_given_centroid_ |
| Use the centroid_to_use_.
|
bool | use_given_normal_ |
| Use the normal_to_use_.
|
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 ()
|
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
| Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
|
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_ |
template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
class pcl::VFHEstimation< PointInT, PointNT, PointOutT >
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud dataset containing points and normals. The default VFH implementation uses 45 binning subdivisions for each of the three extended FPFH values, plus another 45 binning subdivisions for the distances between each point and the centroid and 128 binning subdivisions for the viewpoint component, which results in a 308-byte array of float values. These are stored in a pcl::VFHSignature308 point type. A major difference between the PFH/FPFH descriptors and VFH, is that for a given point cloud dataset, only a single VFH descriptor will be estimated (vfhs->points.size() should be 1), while the resultant PFH/FPFH data will have the same number of entries as the number of points in the cloud.
- 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 an example of a parallel implementation of the FPFH (Fast Point Feature Histogram).
- Author:
- Radu B. Rusu
Definition at line 71 of file vfh.h.
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:
-
[out] | output | the resultant point cloud model dataset that contains the VFH feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 181 of file vfh.hpp.
template<typename PointInT , typename PointNT , typename PointOutT >
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:
-
[in] | centroid_p | the centroid point |
[in] | centroid_n | the centroid normal |
[in] | cloud | the dataset containing the XYZ Cartesian coordinates of the two points |
[in] | normals | the dataset containing the surface normals at each point in cloud |
[in] | indices | the k-neighborhood point indices in the dataset |
Definition at line 91 of file vfh.hpp.
template<typename PointInT, typename PointNT, typename PointOutT = pcl::VFHSignature308>
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 222 of file vfh.h.