Public Types |
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 | computePointSPFHSignature (const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int row, const std::vector< int > &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3) |
| Estimate the SPFH (Simple 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.
|
| FPFHEstimation () |
| Empty constructor.
|
void | getNrSubdivisions (int &nr_bins_f1, int &nr_bins_f2, int &nr_bins_f3) |
| Get the number of subdivisions for each angular feature interval.
|
void | setNrSubdivisions (int nr_bins_f1, int nr_bins_f2, int nr_bins_f3) |
| Set the number of subdivisions for each angular feature interval.
|
void | weightPointSPFHSignature (const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const std::vector< int > &indices, const std::vector< float > &dists, Eigen::VectorXf &fpfh_histogram) |
| Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH (Fast Point Feature Histogram) for a given point based on its 3D spatial neighborhood.
|
Protected Member Functions |
void | computeFeature (PointCloudOut &output) |
| Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
|
void | computeSPFHSignatures (std::vector< int > &spf_hist_lookup, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3) |
| Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud.
|
Protected Attributes |
float | d_pi_ |
| Float constant = 1.0 / (2.0 * M_PI)
|
Eigen::VectorXf | fpfh_histogram_ |
| Placeholder for a point's FPFH signature.
|
Eigen::MatrixXf | hist_f1_ |
| Placeholder for the f1 histogram.
|
Eigen::MatrixXf | hist_f2_ |
| Placeholder for the f2 histogram.
|
Eigen::MatrixXf | hist_f3_ |
| Placeholder for the f3 histogram.
|
int | nr_bins_f1_ |
| The number of subdivisions for each angular feature interval.
|
int | nr_bins_f2_ |
int | nr_bins_f3_ |
Private Member Functions |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
| Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
|
template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
class pcl::FPFHEstimation< PointInT, PointNT, PointOutT >
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset containing points and normals.
A commonly used type for PointOutT is pcl::FPFHSignature33.
- Note:
- If you use this code in any academic work, please cite:
- R.B. Rusu, N. Blodow, M. Beetz. Fast Point Feature Histograms (FPFH) for 3D Registration. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Kobe, Japan, May 12-17 2009.
- R.B. Rusu, A. Holzbach, N. Blodow, M. Beetz. Fast Geometric Point Labeling using Conditional Random Fields. In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), St. Louis, MO, USA, October 11-15 2009.
- Attention:
- The convention for FPFH features is:
- if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN (not a number)
- it is impossible to estimate a FPFH 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 FPFH 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 79 of file fpfh.h.
template<typename PointInT , typename PointNT , typename PointOutT >
template<typename PointInT, typename PointNT, typename PointOutT = pcl::FPFHSignature33>
template<typename PointInT, typename PointNT, typename PointOutT >
Estimate the SPFH (Simple 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] | 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] | p_idx | the index of the query point (source) |
[in] | row | the index row in feature histogramms |
[in] | indices | the k-neighborhood point indices in the dataset |
[out] | hist_f1 | the resultant SPFH histogram for feature f1 |
[out] | hist_f2 | the resultant SPFH histogram for feature f2 |
[out] | hist_f3 | the resultant SPFH histogram for feature f3 |
Definition at line 60 of file fpfh.hpp.