ESFEstimation estimates the ensemble of shape functions descriptors for a given point cloud dataset containing points. Shape functions are D2, D3, A3. For more information about the ESF descriptor, see: Walter Wohlkinger and Markus Vincze, "Ensemble of Shape Functions for 3D Object Classification", IEEE International Conference on Robotics and Biomimetics (IEEE-ROBIO), 2011 More...
#include <esf.h>
Public Types | |
typedef pcl::PointCloud< PointInT > | PointCloudIn |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
void | compute (PointCloudOut &output) |
Overloaded computed method from pcl::Feature. | |
ESFEstimation () | |
Empty constructor. | |
Protected Member Functions | |
void | cleanup9 (PointCloudIn &cluster) |
... | |
void | computeESF (PointCloudIn &pc, std::vector< float > &hist) |
... | |
void | computeFeature (PointCloudOut &output) |
Estimate the Ensebmel of Shape Function (ESF) descriptors at a set of points given by <setInputCloud (),. | |
int | lci (const int x1, const int y1, const int z1, const int x2, const int y2, const int z2, float &ratio, int &incnt, int &pointcount) |
... | |
void | scale_points_unit_sphere (const pcl::PointCloud< PointInT > &pc, float scalefactor, Eigen::Vector4f ¢roid) |
... | |
void | voxelize9 (PointCloudIn &cluster) |
... | |
Private Member Functions | |
void | computeFeatureEigen (pcl::PointCloud< Eigen::MatrixXf > &) |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class. | |
Private Attributes | |
PointCloudIn | local_cloud_ |
... | |
std::vector< std::vector < std::vector< int > > > | lut_ |
... |
ESFEstimation estimates the ensemble of shape functions descriptors for a given point cloud dataset containing points. Shape functions are D2, D3, A3. For more information about the ESF descriptor, see: Walter Wohlkinger and Markus Vincze, "Ensemble of Shape Functions for 3D Object Classification", IEEE International Conference on Robotics and Biomimetics (IEEE-ROBIO), 2011
typedef pcl::PointCloud<PointInT> pcl::ESFEstimation< PointInT, PointOutT >::PointCloudIn |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::ESFEstimation< PointInT, PointOutT >::PointCloudOut |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
pcl::ESFEstimation< PointInT, PointOutT >::ESFEstimation | ( | ) | [inline] |
void pcl::ESFEstimation< PointInT, PointOutT >::cleanup9 | ( | PointCloudIn & | cluster | ) | [protected] |
void pcl::ESFEstimation< PointInT, PointOutT >::compute | ( | PointCloudOut & | output | ) |
Overloaded computed method from pcl::Feature.
[out] | output | the resultant point cloud model dataset containing the estimated features |
Reimplemented from pcl::Feature< PointInT, PointOutT >.
void pcl::ESFEstimation< PointInT, PointOutT >::computeESF | ( | PointCloudIn & | pc, |
std::vector< float > & | hist | ||
) | [protected] |
void pcl::ESFEstimation< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected, virtual] |
Estimate the Ensebmel of Shape Function (ESF) descriptors at a set of points given by <setInputCloud (),.
output | the resultant point cloud model histogram that contains the ESF feature estimates |
Implements pcl::Feature< PointInT, PointOutT >.
void pcl::ESFEstimation< PointInT, PointOutT >::computeFeatureEigen | ( | pcl::PointCloud< Eigen::MatrixXf > & | ) | [inline, private, virtual] |
Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.
[out] | output | the output point cloud |
Implements pcl::Feature< PointInT, PointOutT >.
int pcl::ESFEstimation< PointInT, PointOutT >::lci | ( | const int | x1, |
const int | y1, | ||
const int | z1, | ||
const int | x2, | ||
const int | y2, | ||
const int | z2, | ||
float & | ratio, | ||
int & | incnt, | ||
int & | pointcount | ||
) | [protected] |
void pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere | ( | const pcl::PointCloud< PointInT > & | pc, |
float | scalefactor, | ||
Eigen::Vector4f & | centroid | ||
) | [protected] |
void pcl::ESFEstimation< PointInT, PointOutT >::voxelize9 | ( | PointCloudIn & | cluster | ) | [protected] |
PointCloudIn pcl::ESFEstimation< PointInT, PointOutT >::local_cloud_ [private] |
std::vector<std::vector<std::vector<int> > > pcl::ESFEstimation< PointInT, PointOutT >::lut_ [private] |