Public Types | Public Member Functions | Private Member Functions | Private Attributes
cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT > Class Template Reference

#include <cluster_classifier.h>

List of all members.

Public Types

typedef ClusterHandlerT::Ptr ClusterHdlPtr
typedef ClusterHandlerT::ClusterPtr ClusterPtr
typedef
ClusterHandlerT::ClusterType 
ClusterType
typedef pcl::PointCloud< LabelT > LabelCloud
typedef LabelCloud::ConstPtr LabelCloudConstPtr
typedef pcl::PointCloud< NormalTNormalCloud
typedef NormalCloud::Ptr NormalCloudPtr
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr

Public Member Functions

void classify ()
void classifyOld ()
 ClusterClassifier ()
void mapPointClasses (pcl::PointCloud< pcl::PointXYZRGB >::Ptr points)
void mapUnusedPoints (pcl::PointCloud< pcl::PointXYZRGB >::Ptr points)
void setClusterHandler (ClusterHdlPtr clusters)
void setLabelCloudIn (LabelCloudConstPtr labels)
void setNormalCloudInOut (NormalCloudPtr normals)
void setPointCloudIn (PointCloudConstPtr points)
 ~ClusterClassifier ()

Private Member Functions

bool computeClusterPointCurvature (int index, int r, int steps, float &pc_min, float &pc_max, Eigen::Vector3f &pc_min_direction)
void recomputeClusterNormals (ClusterPtr c)
void recomputeClusterNormals (ClusterPtr c, int w_size, int steps)

Private Attributes

ClusterHdlPtr clusters_
LabelCloudConstPtr labels_
NormalCloudPtr normals_
PointCloudConstPtr surface_
std::vector< int > test
std::vector< int > test_cyl
std::vector< int > test_plane
std::vector< int > test_sph

Detailed Description

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
class cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >

Definition at line 73 of file cluster_classifier.h.


Member Typedef Documentation

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef ClusterHandlerT::Ptr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::ClusterHdlPtr

Definition at line 83 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef ClusterHandlerT::ClusterPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::ClusterPtr

Definition at line 84 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef ClusterHandlerT::ClusterType cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::ClusterType

Definition at line 85 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef pcl::PointCloud<LabelT> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::LabelCloud

Definition at line 80 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef LabelCloud::ConstPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::LabelCloudConstPtr

Definition at line 81 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef pcl::PointCloud<NormalT> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::NormalCloud

Definition at line 78 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef NormalCloud::Ptr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::NormalCloudPtr

Definition at line 79 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef pcl::PointCloud<PointT> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::PointCloud

Definition at line 76 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
typedef PointCloud::ConstPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::PointCloudConstPtr

Definition at line 77 of file cluster_classifier.h.


Constructor & Destructor Documentation

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::ClusterClassifier ( ) [inline]

Definition at line 88 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::~ClusterClassifier ( ) [inline]

Definition at line 91 of file cluster_classifier.h.


Member Function Documentation

template<typename ClusterHandlerT , typename PointT , typename NormalT , typename LabelT >
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::classify ( )

Definition at line 103 of file cluster_classifier.hpp.

template<typename ClusterHandlerT , typename PointT , typename NormalT , typename LabelT >
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::classifyOld ( )

Definition at line 74 of file cluster_classifier.hpp.

template<typename ClusterHandlerT , typename PointT , typename NormalT , typename LabelT >
bool cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::computeClusterPointCurvature ( int  index,
int  r,
int  steps,
float &  pc_min,
float &  pc_max,
Eigen::Vector3f &  pc_min_direction 
) [private]

Definition at line 201 of file cluster_classifier.hpp.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::mapPointClasses ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  points) [inline]

Definition at line 109 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::mapUnusedPoints ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  points) [inline]

Definition at line 102 of file cluster_classifier.h.

template<typename ClusterHandlerT , typename PointT , typename NormalT , typename LabelT >
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::recomputeClusterNormals ( ClusterPtr  c) [private]

Definition at line 176 of file cluster_classifier.hpp.

template<typename ClusterHandlerT , typename PointT , typename NormalT , typename LabelT >
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::recomputeClusterNormals ( ClusterPtr  c,
int  w_size,
int  steps 
) [private]

Definition at line 184 of file cluster_classifier.hpp.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::setClusterHandler ( ClusterHdlPtr  clusters) [inline]

Definition at line 94 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::setLabelCloudIn ( LabelCloudConstPtr  labels) [inline]

Definition at line 97 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::setNormalCloudInOut ( NormalCloudPtr  normals) [inline]

Definition at line 96 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
void cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::setPointCloudIn ( PointCloudConstPtr  points) [inline]

Definition at line 95 of file cluster_classifier.h.


Member Data Documentation

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
ClusterHdlPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::clusters_ [private]

Definition at line 135 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
LabelCloudConstPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::labels_ [private]

Definition at line 136 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
NormalCloudPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::normals_ [private]

Definition at line 138 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
PointCloudConstPtr cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::surface_ [private]

Definition at line 137 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
std::vector<int> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::test [private]

Definition at line 139 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
std::vector<int> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::test_cyl [private]

Definition at line 140 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
std::vector<int> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::test_plane [private]

Definition at line 141 of file cluster_classifier.h.

template<typename ClusterHandlerT, typename PointT, typename NormalT, typename LabelT>
std::vector<int> cob_3d_segmentation::ClusterClassifier< ClusterHandlerT, PointT, NormalT, LabelT >::test_sph [private]

Definition at line 142 of file cluster_classifier.h.


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


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03