This package can segment object clusters on top of a table plane.
ROS API
table_object_cluster
The table_object_cluster node takes in sensor_msgs/PointCloud2 messages for the point map and the table plane and extracts objects clusters on top of the table. As output, bounding boxes for all the objects are provided.Action Goal
table_object_cluster/goal (cob_3d_mapping_msgs/TableObjectClusterActionGoal)- contains the table plane and triggers cluster detection
Action Result
table_object_cluster/result (cob_3d_mapping_msgs/TableObjectClusterActionResult)- returns the bounding boxes for the object clusters
Action Feedback
table_object_cluster/feedback (cob_3d_mapping_msgs/TableObjectClusterActionFeedback)- empty
Subscribed Topics
/point_cloud (sensor_msgs/PointCloud2)- The input point cloud
- The supporting plane(s)
Published Topics
/bb_marker (visualization_msgs/Marker)- Bounding boxes for object cluster
- The object clusters
Parameters
~height_min (double, default: -0.5)- lower boundary of cluster search area (relative to table plane, negative values for area on top of table)
- upper boundary of cluster search area (relative to table plane, negative values for area on top of table)
- minimum number of points for a valid cluster
- threshold for separation of two clusters
- Flag for saving the results as PCD files (for debugging)
- File path for saving the results
Usage/Examples
Action mode and geometry map
Start the mapping pipeline in cob_3d_mapping_pipeline
roslaunch cob_3d_mapping_pipeline mapping.launch
Make sure that a table is in the field of view of the camera and trigger the mapping by
rosrun cob_3d_mapping_point_map trigger_mapping.py start
Check in rviz if the table is in the map (as a plane).
Start the semantic extraction of tables
roslaunch cob_3d_mapping_semantics extract_semantics.launch
Launch the cluster detection
roslaunch cob_table_object_cluster tabletop_object_cluster.launch
Run
rosrun cob_table_object_cluster table_object_cluster_action_client
This will extract object cluster on each table surface found. Bounding boxes for the cluster are published as visualization_msgs/Marker.
Topic mode
Run the segmentation from cob_3d_segmentation
roslaunch cob_3d_segmentation fast_segmentation.launch
Make sure to subscribe directly to the camera point cloud topic if you are not using registration. Launch the supporting plane extraction in cob_3d_mapping_semantics
roslaunch cob_3d_mapping_semantics extract_supporting_plane.launch
Launch the object cluster detection
roslaunch cob_table_object_cluster tabletop_object_cluster.launch
The object clusters are published as visualization_msgs/Marker for bounding boxes and cob_perception_msgs/PointCloud2Array.