Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
pcl::ESFEstimation< PointInT, PointOutT > Class Template Reference

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>

Inheritance diagram for pcl::ESFEstimation< PointInT, PointOutT >:
Inheritance graph
[legend]

List of all members.

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 &centroid)
 ...
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_
 ...

Detailed Description

template<typename PointInT, typename PointOutT = pcl::ESFSignature640>
class pcl::ESFEstimation< PointInT, PointOutT >

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

Author:
Walter Wohlkinger

Definition at line 60 of file esf.h.


Member Typedef Documentation

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
typedef pcl::PointCloud<PointInT> pcl::ESFEstimation< PointInT, PointOutT >::PointCloudIn

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 71 of file esf.h.

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::ESFEstimation< PointInT, PointOutT >::PointCloudOut

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 72 of file esf.h.


Constructor & Destructor Documentation

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
pcl::ESFEstimation< PointInT, PointOutT >::ESFEstimation ( ) [inline]

Empty constructor.

Definition at line 75 of file esf.h.


Member Function Documentation

template<typename PointInT , typename PointOutT >
void pcl::ESFEstimation< PointInT, PointOutT >::cleanup9 ( PointCloudIn cluster) [protected]

...

Definition at line 460 of file esf.hpp.

template<typename PointInT , typename PointOutT >
void pcl::ESFEstimation< PointInT, PointOutT >::compute ( PointCloudOut output)

Overloaded computed method from pcl::Feature.

Parameters:
[out]outputthe resultant point cloud model dataset containing the estimated features

Reimplemented from pcl::Feature< PointInT, PointOutT >.

Definition at line 514 of file esf.hpp.

template<typename PointInT , typename PointOutT >
void pcl::ESFEstimation< PointInT, PointOutT >::computeESF ( PointCloudIn pc,
std::vector< float > &  hist 
) [protected]

...

Definition at line 51 of file esf.hpp.

template<typename PointInT , typename PointOutT >
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 (),.

Parameters:
outputthe resultant point cloud model histogram that contains the ESF feature estimates

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 542 of file esf.hpp.

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
void pcl::ESFEstimation< PointInT, PointOutT >::computeFeatureEigen ( pcl::PointCloud< Eigen::MatrixXf > &  ) [inline, private, virtual]

Make the computeFeature (&Eigen::MatrixXf); inaccessible from outside the class.

Parameters:
[out]outputthe output point cloud

Implements pcl::Feature< PointInT, PointOutT >.

Definition at line 140 of file esf.h.

template<typename PointInT , typename 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]

...

Definition at line 312 of file esf.hpp.

template<typename PointInT , typename PointOutT >
void pcl::ESFEstimation< PointInT, PointOutT >::scale_points_unit_sphere ( const pcl::PointCloud< PointInT > &  pc,
float  scalefactor,
Eigen::Vector4f &  centroid 
) [protected]

...

Definition at line 489 of file esf.hpp.

template<typename PointInT , typename PointOutT >
void pcl::ESFEstimation< PointInT, PointOutT >::voxelize9 ( PointCloudIn cluster) [protected]

...

Definition at line 431 of file esf.hpp.


Member Data Documentation

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
PointCloudIn pcl::ESFEstimation< PointInT, PointOutT >::local_cloud_ [private]

...

Definition at line 134 of file esf.h.

template<typename PointInT , typename PointOutT = pcl::ESFSignature640>
std::vector<std::vector<std::vector<int> > > pcl::ESFEstimation< PointInT, PointOutT >::lut_ [private]

...

Definition at line 131 of file esf.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:18