Public Types | Public Member Functions | Private Member Functions | Private Attributes
cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT > Class Template Reference

#include <depth_segmentation.h>

Inheritance diagram for cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef ClusterGraphT::Ptr ClusterGraphPtr
typedef ClusterGraphT::ClusterPtr ClusterPtr
typedef ClusterGraphT::EdgePtr EdgePtr
typedef pcl::PointCloud
< PointLabelT > 
LabelCloud
typedef LabelCloud::ConstPtr LabelCloudConstPtr
typedef LabelCloud::Ptr LabelCloudPtr
typedef pcl::PointCloud< PointNT > NormalCloud
typedef NormalCloud::ConstPtr NormalCloudConstPtr
typedef NormalCloud::Ptr NormalCloudPtr
typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Public Member Functions

virtual bool compute ()
 DepthSegmentation ()
virtual LabelCloudConstPtr getOutputCloud ()
 gets preprocessed output cloud
void getPotentialObjects (std::map< int, int > &objs, int max_size=0)
virtual operator cob_3d_mapping_msgs::ShapeArray () const
 convert to ROS message
void performInitialSegmentation ()
void refineSegmentation ()
void setClusterGraphOut (ClusterGraphPtr clusters)
virtual void setInputCloud (const PointCloudConstPtr &points)
void setLabelCloudInOut (LabelCloudPtr labels)
void setNormalCloudIn (NormalCloudConstPtr normals)
 ~DepthSegmentation ()

Private Member Functions

void addIfIsValid (int u, int v, int idx, int idx_prev, float dist_th, float p_z, Eigen::Vector3f &n, SegmentationQueue &seg_queue, ClusterPtr c)
void addSmallNeighbors (ClusterPtr c, std::map< int, int > &objs, std::set< int > &processed, int obj_counter, int max_size)
void computeBoundaryProperties (ClusterPtr c, EdgePtr e)
void computeBoundaryProperties (ClusterPtr c)
void computeEdgeSmoothness (EdgePtr e)
void computeEdgeSmoothness ()

Private Attributes

ClusterGraphPtr graph_
LabelCloudPtr labels_
int min_cluster_size_
float min_dot_boundary_
float min_dot_normals_
NormalCloudConstPtr normals_
PointCloudConstPtr surface_

Detailed Description

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
class cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >

Definition at line 114 of file depth_segmentation.h.


Member Typedef Documentation

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef ClusterGraphT::Ptr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::ClusterGraphPtr

Definition at line 129 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef ClusterGraphT::ClusterPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::ClusterPtr

Definition at line 130 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef ClusterGraphT::EdgePtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::EdgePtr

Definition at line 131 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef pcl::PointCloud<PointLabelT> cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::LabelCloud

Definition at line 125 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef LabelCloud::ConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::LabelCloudConstPtr

Definition at line 127 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef LabelCloud::Ptr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::LabelCloudPtr

Definition at line 126 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef pcl::PointCloud<PointNT> cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::NormalCloud

Definition at line 121 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef NormalCloud::ConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::NormalCloudConstPtr

Definition at line 123 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef NormalCloud::Ptr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::NormalCloudPtr

Definition at line 122 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef pcl::PointCloud<PointT> cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::PointCloud

Definition at line 117 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef PointCloud::ConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::PointCloudConstPtr

Definition at line 119 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
typedef PointCloud::Ptr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::PointCloudPtr

Definition at line 118 of file depth_segmentation.h.


Constructor & Destructor Documentation

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::DepthSegmentation ( ) [inline]

Definition at line 134 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::~DepthSegmentation ( ) [inline]

Definition at line 144 of file depth_segmentation.h.


Member Function Documentation

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::addIfIsValid ( int  u,
int  v,
int  idx,
int  idx_prev,
float  dist_th,
float  p_z,
Eigen::Vector3f &  n,
SegmentationQueue seg_queue,
ClusterPtr  c 
) [private]

Definition at line 76 of file depth_segmentation.hpp.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::addSmallNeighbors ( ClusterPtr  c,
std::map< int, int > &  objs,
std::set< int > &  processed,
int  obj_counter,
int  max_size 
) [private]

Definition at line 290 of file depth_segmentation.hpp.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
virtual bool cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::compute ( ) [inline, virtual]

Implements GeneralSegmentation< PointT, PointLabelT >.

Definition at line 153 of file depth_segmentation.h.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::computeBoundaryProperties ( ClusterPtr  c,
EdgePtr  e 
) [private]

Definition at line 219 of file depth_segmentation.hpp.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::computeBoundaryProperties ( ClusterPtr  c) [private]

Definition at line 232 of file depth_segmentation.hpp.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::computeEdgeSmoothness ( EdgePtr  e) [private]

Definition at line 245 of file depth_segmentation.hpp.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::computeEdgeSmoothness ( ) [private]

Definition at line 263 of file depth_segmentation.hpp.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
virtual LabelCloudConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::getOutputCloud ( ) [inline, virtual]

gets preprocessed output cloud

Implements GeneralSegmentation< PointT, PointLabelT >.

Definition at line 152 of file depth_segmentation.h.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::getPotentialObjects ( std::map< int, int > &  objs,
int  max_size = 0 
)

Definition at line 270 of file depth_segmentation.hpp.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
virtual cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::operator cob_3d_mapping_msgs::ShapeArray ( ) const [inline, virtual]

convert to ROS message

Implements GeneralSegmentation< PointT, PointLabelT >.

Definition at line 167 of file depth_segmentation.h.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::performInitialSegmentation ( )

Definition at line 105 of file depth_segmentation.hpp.

template<typename ClusterGraphT , typename PointT , typename PointNT , typename PointLabelT >
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::refineSegmentation ( )

Definition at line 180 of file depth_segmentation.hpp.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::setClusterGraphOut ( ClusterGraphPtr  clusters) [inline]

Definition at line 147 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
virtual void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::setInputCloud ( const PointCloudConstPtr points) [inline, virtual]

Definition at line 151 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::setLabelCloudInOut ( LabelCloudPtr  labels) [inline]

Definition at line 150 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
void cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::setNormalCloudIn ( NormalCloudConstPtr  normals) [inline]

Definition at line 149 of file depth_segmentation.h.


Member Data Documentation

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
ClusterGraphPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::graph_ [private]

Definition at line 185 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
LabelCloudPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::labels_ [private]

Definition at line 188 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
int cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::min_cluster_size_ [private]

Definition at line 183 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
float cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::min_dot_boundary_ [private]

Definition at line 182 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
float cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::min_dot_normals_ [private]

Definition at line 181 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
NormalCloudConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::normals_ [private]

Definition at line 187 of file depth_segmentation.h.

template<typename ClusterGraphT, typename PointT, typename PointNT, typename PointLabelT>
PointCloudConstPtr cob_3d_segmentation::DepthSegmentation< ClusterGraphT, PointT, PointNT, PointLabelT >::surface_ [private]

Definition at line 186 of file depth_segmentation.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