Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT > Class Template Reference

#include <fast_edge_estimation_3d.h>

Inheritance diagram for cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud< PointNT > PointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef pcl::PointCloud
< PointOutT > 
PointCloudOut

Public Member Functions

 FastEdgeEstimation3D ()
 Empty constructor.
void isEdgePoint (const pcl::PointCloud< PointInT > &cloud, const PointInT &q_point, const std::vector< int > &indices, const Eigen::Vector3f &n, float &strength)
void setInputNormals (PointCloudNConstPtr cloud)

Protected Member Functions

void computeFeature (PointCloudOut &output)

Protected Attributes

PointCloudNConstPtr normals_

Detailed Description

template<typename PointInT, typename PointNT, typename PointOutT>
class cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >

Definition at line 71 of file fast_edge_estimation_3d.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointInT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudIn
template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::ConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudInConstPtr
template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudIn::Ptr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudInPtr
template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointNT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudN

Definition at line 86 of file fast_edge_estimation_3d.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::ConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudNConstPtr

Definition at line 88 of file fast_edge_estimation_3d.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef PointCloudN::Ptr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudNPtr

Definition at line 87 of file fast_edge_estimation_3d.h.

template<typename PointInT, typename PointNT, typename PointOutT>
typedef pcl::PointCloud<PointOutT> cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::PointCloudOut

Constructor & Destructor Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::FastEdgeEstimation3D ( ) [inline]

Empty constructor.

Definition at line 94 of file fast_edge_estimation_3d.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointOutT >
void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]
template<typename PointInT , typename PointNT , typename PointOutT >
void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::isEdgePoint ( const pcl::PointCloud< PointInT > &  cloud,
const PointInT &  q_point,
const std::vector< int > &  indices,
const Eigen::Vector3f &  n,
float &  strength 
)

Definition at line 69 of file fast_edge_estimation_3d.hpp.

template<typename PointInT, typename PointNT, typename PointOutT>
void cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::setInputNormals ( PointCloudNConstPtr  cloud) [inline]

Definition at line 100 of file fast_edge_estimation_3d.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointOutT>
PointCloudNConstPtr cob_3d_features::FastEdgeEstimation3D< PointInT, PointNT, PointOutT >::normals_ [protected]

Definition at line 115 of file fast_edge_estimation_3d.h.


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


cob_3d_features
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:26