31 #ifndef SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H
32 #define SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H
36 #include <grasping_msgs/Object.h>
38 #include <pcl/io/io.h>
39 #include <pcl/point_types.h>
40 #include <pcl/segmentation/extract_clusters.h>
41 #include <pcl/filters/extract_indices.h>
42 #include <pcl/segmentation/sac_segmentation.h>
43 #include <pcl/filters/voxel_grid.h>
70 bool segment(
const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud,
71 std::vector<grasping_msgs::Object>& objects,
72 std::vector<grasping_msgs::Object>& supports,
73 pcl::PointCloud<pcl::PointXYZRGB>& object_cloud,
74 pcl::PointCloud<pcl::PointXYZRGB>& support_cloud,
79 pcl::SACSegmentation<pcl::PointXYZRGB>
segment_;
86 #endif // SIMPLE_GRASPING_OBJECT_SUPPORT_SEGMENTATION_H