Class ObjectSupportSegmentation
Defined in File object_support_segmentation.h
Class Documentation
-
class ObjectSupportSegmentation
Class that segments a point cloud into objects and supporting surfaces.
Public Functions
Constructor, loads pipeline using ROS parameters.
- Parameters:
node – Node instance to use for accessing parameters.
-
bool segment(const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &cloud, std::vector<grasping_msgs::msg::Object> &objects, std::vector<grasping_msgs::msg::Object> &supports, pcl::PointCloud<pcl::PointXYZRGB> &object_cloud, pcl::PointCloud<pcl::PointXYZRGB> &support_cloud, bool output_clouds)
Split a cloud into objects and supporting surfaces.
- Parameters:
cloud – The point cloud to segment. This cloud should already be transformed into a coordinate frame where XY plane is horizontal.
objects – The vector to fill in with objects found.
supports – The vector to fill in with support surfaces found.
object_cloud – A colored cloud of objects found (if output_clouds).
support_cloud – A colored cloud of supports found (if output_clouds).