Public Types | Public Member Functions | Private Attributes
cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT > Class Template Reference

#include <cluster_handler.h>

Inheritance diagram for cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< LabelT > LabelCloud
typedef LabelCloud::Ptr LabelCloudPtr
typedef pcl::PointCloud< PointNT > NormalCloud
typedef NormalCloud::ConstPtr NormalCloudConstPtr
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef boost::shared_ptr
< DepthClusterHandler< LabelT,
PointT, PointNT > > 
Ptr

Public Member Functions

void addBorderIndicesToClusters ()
void addPoint (ClusterPtr c, int idx)
void clearOrientation (ClusterPtr c) const
void computeClusterComponents (ClusterPtr c)
void computeCurvature (ClusterPtr c)
void computeNormalIntersections (ClusterPtr c)
void computePointCurvature (ClusterPtr c, int search_size)
bool computePrincipalComponents (ClusterPtr c)
 DepthClusterHandler ()
void mapClusterBorders (pcl::PointCloud< pcl::PointXYZRGB >::Ptr points)
void mapClusterNormalIntersectionResults (pcl::PointCloud< pcl::PointXYZ >::Ptr ints_centroids, pcl::PointCloud< pcl::Normal >::Ptr comp1, pcl::PointCloud< pcl::Normal >::Ptr comp2, pcl::PointCloud< pcl::Normal >::Ptr comp3, pcl::PointCloud< pcl::PointXYZ >::Ptr centroids, pcl::PointCloud< pcl::Normal >::Ptr connection)
void merge (ClusterPtr source, ClusterPtr target)
void setLabelCloudInOut (LabelCloudPtr labels)
void setNormalCloudIn (NormalCloudConstPtr normals)
void setPointCloudIn (PointCloudConstPtr points)
void updateNormal (ClusterPtr c, const Eigen::Vector3f &normal) const
 ~DepthClusterHandler ()

Private Attributes

LabelCloudPtr labels_
NormalCloudConstPtr normals_
PointCloudConstPtr surface_

Detailed Description

template<typename LabelT, typename PointT, typename PointNT>
class cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >

Definition at line 179 of file cluster_handler.h.


Member Typedef Documentation

template<typename LabelT, typename PointT, typename PointNT>
typedef pcl::PointCloud<LabelT> cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::LabelCloud

Definition at line 184 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef LabelCloud::Ptr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::LabelCloudPtr

Definition at line 185 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef pcl::PointCloud<PointNT> cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::NormalCloud

Definition at line 188 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef NormalCloud::ConstPtr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::NormalCloudConstPtr

Definition at line 189 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef pcl::PointCloud<PointT> cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::PointCloud

Definition at line 186 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef PointCloud::ConstPtr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::PointCloudConstPtr

Definition at line 187 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
typedef boost::shared_ptr<DepthClusterHandler<LabelT,PointT,PointNT> > cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::Ptr

Definition at line 182 of file cluster_handler.h.


Constructor & Destructor Documentation

template<typename LabelT, typename PointT, typename PointNT>
cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::DepthClusterHandler ( ) [inline]

Definition at line 192 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::~DepthClusterHandler ( ) [inline]

Definition at line 194 of file cluster_handler.h.


Member Function Documentation

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::addBorderIndicesToClusters ( ) [inline]

Definition at line 240 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::addPoint ( ClusterPtr  c,
int  idx 
) [inline, virtual]
template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::clearOrientation ( ClusterPtr  c) const [inline]

Definition at line 214 of file cluster_handler.h.

template<typename LabelT , typename PointT , typename PointNT >
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::computeClusterComponents ( ClusterPtr  c)

Definition at line 70 of file cluster_handler.hpp.

template<typename LabelT , typename PointT , typename PointNT >
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::computeCurvature ( ClusterPtr  c)

Definition at line 99 of file cluster_handler.hpp.

template<typename LabelT , typename PointT , typename PointNT >
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::computeNormalIntersections ( ClusterPtr  c)

Definition at line 128 of file cluster_handler.hpp.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::computePointCurvature ( ClusterPtr  c,
int  search_size 
)
template<typename LabelT, typename PointT, typename PointNT>
bool cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::computePrincipalComponents ( ClusterPtr  c)
template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::mapClusterBorders ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  points) [inline]

Definition at line 261 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::mapClusterNormalIntersectionResults ( pcl::PointCloud< pcl::PointXYZ >::Ptr  ints_centroids,
pcl::PointCloud< pcl::Normal >::Ptr  comp1,
pcl::PointCloud< pcl::Normal >::Ptr  comp2,
pcl::PointCloud< pcl::Normal >::Ptr  comp3,
pcl::PointCloud< pcl::PointXYZ >::Ptr  centroids,
pcl::PointCloud< pcl::Normal >::Ptr  connection 
) [inline]

Definition at line 274 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::merge ( ClusterPtr  source,
ClusterPtr  target 
) [inline, virtual]
template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::setLabelCloudInOut ( LabelCloudPtr  labels) [inline]

Definition at line 229 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::setNormalCloudIn ( NormalCloudConstPtr  normals) [inline]

Definition at line 231 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::setPointCloudIn ( PointCloudConstPtr  points) [inline]

Definition at line 230 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
void cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::updateNormal ( ClusterPtr  c,
const Eigen::Vector3f &  normal 
) const [inline]

Definition at line 209 of file cluster_handler.h.


Member Data Documentation

template<typename LabelT, typename PointT, typename PointNT>
LabelCloudPtr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::labels_ [private]

Definition at line 312 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
NormalCloudConstPtr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::normals_ [private]

Definition at line 314 of file cluster_handler.h.

template<typename LabelT, typename PointT, typename PointNT>
PointCloudConstPtr cob_3d_segmentation::DepthClusterHandler< LabelT, PointT, PointNT >::surface_ [private]

Definition at line 313 of file cluster_handler.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