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.
|
unsigned int | getMaximumCacheSize () |
| Get the maximum internal cache size.
|
bool | getUseInternalCache () |
| Get whether the internal cache is used or not for computing the PFH features.
|
| PFHEstimation () |
| Empty constructor. Sets use_cache_ to false, nr_subdiv_ to 5, and the internal maximum cache size to 1GB.
|
void | setMaximumCacheSize (unsigned int cache_size) |
| Set the maximum internal cache size. Defaults to 2GB worth of entries.
|
void | setUseInternalCache (bool use_cache) |
| Set whether to use an internal cache mechanism for removing redundant calculations or not.
|
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 ()
|
Protected Attributes |
float | d_pi_ |
| Float constant = 1.0 / (2.0 * M_PI)
|
int | f_index_ [3] |
| Placeholder for a histogram index.
|
std::map< std::pair< int, int >
, Eigen::Vector4f, std::less
< std::pair< int, int >
>, Eigen::aligned_allocator
< Eigen::Vector4f > > | feature_map_ |
| Internal hashmap, used to optimize efficiency of redundant computations.
|
std::queue< std::pair< int, int > > | key_list_ |
| Queue of pairs saved, used to constrain memory usage.
|
unsigned int | max_cache_size_ |
| Maximum size of internal cache memory.
|
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.
|
bool | use_cache_ |
| Set to true to use the internal cache for removing redundant computations.
|
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::PFHSignature125>
class pcl::PFHEstimation< PointInT, PointNT, PointOutT >
PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing points and normals.
A commonly used type for PointOutT is pcl::PFHSignature125.
- 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.
- Attention:
- The convention for PFH features is:
- if a query point's nearest neighbors cannot be estimated, the PFH feature will be set to NaN (not a number)
- it is impossible to estimate a PFH 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 PFH 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 101 of file pfh.h.
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:
-
[out] | output | the resultant point cloud model dataset that contains the PFH feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
Definition at line 158 of file pfh.hpp.
template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
template<typename PointInT, typename PointNT, typename PointOutT >
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:
-
[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 |
[in] | nr_split | the number of subdivisions for each angular feature interval |
[out] | pfh_histogram | the resultant (combinatorial) PFH histogram representing the feature at the query point |
Definition at line 59 of file pfh.hpp.
template<typename PointInT, typename PointNT, typename PointOutT = pcl::PFHSignature125>
Set whether to use an internal cache mechanism for removing redundant calculations or not.
- Note:
- Depending on how the point cloud is ordered and how the nearest neighbors are estimated, using a cache could have a positive or a negative influence. Please test with and without a cache on your data, and choose whatever works best!
See setMaximumCacheSize for setting the maximum cache size
- Parameters:
-
[in] | use_cache | set to true to use the internal cache, false otherwise |
Definition at line 161 of file pfh.h.