general_segmentation.h
Go to the documentation of this file.
00001 
00063 #ifndef SEGMENTATION_H_
00064 #define SEGMENTATION_H_
00065 
00066 #include <pcl/common/common.h>
00067 #include <pcl/point_types.h>
00068 #include <pcl/point_cloud.h>
00069 #include <cob_3d_mapping_common/point_types.h>
00070 #include <cob_3d_mapping_msgs/ShapeArray.h>
00071 #include <cob_3d_mapping_msgs/Shape.h>
00072 
00076   template <typename Point, typename PointLabel>
00077 class GeneralSegmentation
00078 {
00079 public:
00080   virtual ~GeneralSegmentation() {}
00081 
00083   virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud) =0;
00084 
00086   virtual boost::shared_ptr<const pcl::PointCloud<PointLabel> > getOutputCloud () =0;
00087 
00088   virtual bool compute()=0;
00089 
00091   virtual operator cob_3d_mapping_msgs::ShapeArray() const = 0;
00092 };
00093 
00094 
00095 
00096 
00097 #endif /* SEGMENTATION_H_ */


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