Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #ifndef SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H
00032 #define SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H
00033
00034 #include <vector>
00035
00036 #include <grasping_msgs/Object.h>
00037
00038 #include <pcl/io/io.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/segmentation/extract_clusters.h>
00041 #include <pcl/filters/extract_indices.h>
00042 #include <pcl/segmentation/sac_segmentation.h>
00043 #include <pcl/filters/voxel_grid.h>
00044
00045 namespace simple_grasping
00046 {
00047
00051 class ObjectSupportSegmentation
00052 {
00053 public:
00054
00059 ObjectSupportSegmentation(ros::NodeHandle& nh);
00060
00070 bool segment(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
00071 std::vector<grasping_msgs::Object>& objects,
00072 std::vector<grasping_msgs::Object>& supports,
00073 pcl::PointCloud<pcl::PointXYZRGB>& object_cloud,
00074 pcl::PointCloud<pcl::PointXYZRGB>& support_cloud,
00075 bool output_clouds);
00076
00077 private:
00078 pcl::VoxelGrid<pcl::PointXYZRGB> voxel_grid_;
00079 pcl::SACSegmentation<pcl::PointXYZRGB> segment_;
00080 pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> extract_clusters_;
00081 pcl::ExtractIndices<pcl::PointXYZRGB> extract_indices_;
00082 };
00083
00084 }
00085
00086 #endif // SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H