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

#include <organized_curvature_estimation.h>

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

List of all members.

Public Types

typedef pcl::PointCloud
< PointLabelT > 
LabelCloudOut
typedef LabelCloudOut::ConstPtr LabelCloudOutConstPtr
typedef LabelCloudOut::Ptr LabelCloudOutPtr
typedef pcl::PointCloud< PointNT > NormalCloudIn
typedef NormalCloudIn::ConstPtr NormalCloudInConstPtr
typedef NormalCloudIn::Ptr NormalCloudInPtr
typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud
< PointOutT > 
PointCloudOut
typedef PointCloudOut::ConstPtr PointCloudOutConstPtr
typedef PointCloudOut::Ptr PointCloudOutPtr

Public Member Functions

void computePointCurvatures (const NormalCloudIn &normals, const int index, const std::vector< int > &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2, int &label_out)
void computePointCurvatures (const NormalCloudIn &normals, const int index, const std::vector< int > &indices, const std::vector< float > &sqr_distances, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2, int &label_out)
 OrganizedCurvatureEstimation ()
void setEdgeClassThreshold (float th)
void setInputNormals (const NormalCloudInConstPtr &normals)
void setOutputLabels (LabelCloudOutPtr labels)

Protected Member Functions

void computeFeature (PointCloudOut &output)

Protected Attributes

float edge_curvature_threshold_
LabelCloudOutPtr labels_
NormalCloudInConstPtr normals_

Detailed Description

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
class cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >

Definition at line 75 of file organized_curvature_estimation.h.


Member Typedef Documentation

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef pcl::PointCloud<PointLabelT> cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::LabelCloudOut

Definition at line 98 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef LabelCloudOut::ConstPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::LabelCloudOutConstPtr

Definition at line 100 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef LabelCloudOut::Ptr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::LabelCloudOutPtr

Definition at line 99 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef pcl::PointCloud<PointNT> cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::NormalCloudIn

Definition at line 94 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef NormalCloudIn::ConstPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::NormalCloudInConstPtr

Definition at line 96 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef NormalCloudIn::Ptr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::NormalCloudInPtr

Definition at line 95 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef pcl::PointCloud<PointInT> cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudIn
template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef PointCloudIn::ConstPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudInConstPtr
template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef PointCloudIn::Ptr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudInPtr
template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef pcl::PointCloud<PointOutT> cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudOut
template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef PointCloudOut::ConstPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudOutConstPtr

Definition at line 104 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
typedef PointCloudOut::Ptr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::PointCloudOutPtr

Definition at line 103 of file organized_curvature_estimation.h.


Constructor & Destructor Documentation

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

Definition at line 106 of file organized_curvature_estimation.h.


Member Function Documentation

template<typename PointInT , typename PointNT , typename PointLabelT , typename PointOutT >
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::computeFeature ( PointCloudOut output) [protected, virtual]
template<typename PointInT , typename PointNT , typename PointLabelT , typename PointOutT >
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::computePointCurvatures ( const NormalCloudIn normals,
const int  index,
const std::vector< int > &  indices,
float &  pcx,
float &  pcy,
float &  pcz,
float &  pc1,
float &  pc2,
int &  label_out 
)

Definition at line 70 of file organized_curvature_estimation.hpp.

template<typename PointInT , typename PointNT , typename PointLabelT , typename PointOutT >
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::computePointCurvatures ( const NormalCloudIn normals,
const int  index,
const std::vector< int > &  indices,
const std::vector< float > &  sqr_distances,
float &  pcx,
float &  pcy,
float &  pcz,
float &  pc1,
float &  pc2,
int &  label_out 
)

Definition at line 83 of file organized_curvature_estimation.hpp.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::setEdgeClassThreshold ( float  th) [inline]

Definition at line 118 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::setInputNormals ( const NormalCloudInConstPtr normals) [inline]

Definition at line 112 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
void cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::setOutputLabels ( LabelCloudOutPtr  labels) [inline]

Definition at line 115 of file organized_curvature_estimation.h.


Member Data Documentation

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
float cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::edge_curvature_threshold_ [protected]

Definition at line 156 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
LabelCloudOutPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::labels_ [protected]

Definition at line 154 of file organized_curvature_estimation.h.

template<typename PointInT, typename PointNT, typename PointLabelT, typename PointOutT>
NormalCloudInConstPtr cob_3d_features::OrganizedCurvatureEstimation< PointInT, PointNT, PointLabelT, PointOutT >::normals_ [protected]

Definition at line 153 of file organized_curvature_estimation.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