This package can segment object clusters on top of a table plane. == ROS API == {{{ #!clearsilver CS/NodeAPI name = table_object_cluster desc = The `table_object_cluster` node takes in <> 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. goal{ 0.name=table_object_cluster/goal 0.type=cob_3d_mapping_msgs/TableObjectClusterActionGoal 0.desc=contains the table plane and triggers cluster detection } result{ 0.name=table_object_cluster/result 0.type=cob_3d_mapping_msgs/TableObjectClusterActionResult 0.desc=returns the bounding boxes for the object clusters } feedback{ 0.name=table_object_cluster/feedback 0.type=cob_3d_mapping_msgs/TableObjectClusterActionFeedback 0.desc=empty } sub{ 0.name = /point_cloud 0.type = sensor_msgs/PointCloud2 0.desc = The input point cloud 1.name = /shape_array 1.type = cob_3d_mapping_msgs/ShapeArray 1.desc = The supporting plane(s) } pub{ 0.name = /bb_marker 0.type = visualization_msgs/Marker 0.desc = Bounding boxes for object cluster 1.name = /cluster_array 1.type = cob_perception_msgs/PointCloud2Array 1.desc = The object clusters } param{ 0.name = ~height_min 0.type = double 0.default = -0.5 0.desc = lower boundary of cluster search area (relative to table plane, negative values for area on top of table) 1.name = ~height_max 1.type = double 1.default = -0.03 1.desc = upper boundary of cluster search area (relative to table plane, negative values for area on top of table) 2.name = ~min_cluster_size 2.type = double 2.default = 10 2.desc = minimum number of points for a valid cluster 3.name = ~cluster_tolerance 3.type = double 3.default = 0.06 3.desc = threshold for separation of two clusters 4.name = ~save 4.type = bool 4.default = false 4.desc = Flag for saving the results as PCD files (for debugging) 5.name = ~file_path 5.type = string 5.default = /tmp 5.desc = File path for saving the results } req_tf{ } prov_tf{ } }}} == 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 <>. === 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 <> for bounding boxes and <>.