Show EOL distros: 

Package Summary

Segmentation Functionality from the RAIL Lab

Package Summary

Segmentation Functionality from the RAIL Lab

Package Summary

Segmentation Functionality from the RAIL Lab

Package Summary

Segmentation Functionality from the RAIL Lab

Package Summary

Segmentation Functionality from the RAIL Lab

About

The rail_segmentation package provides tabletop segmentation functionality given a point cloud. It also allows for segmentation within a robot's coordinate frame, so that objects stored on a robot's platform can be segmented.

Newly proposed, mistyped, or obsolete package. Could not find package "rail_segmentation" in rosdoc: /var/www/docs.ros.org/en/api/rail_segmentation/manifest.yaml

Object Segmentation APIs

This package exposes three APIs to perform object segmentation, with varying inputs and outputs. Each API uses the same underlying object segmentation pipeline, supporting all of the node's parameters (listed in the next section). To call each API, simply use the appropriate ROS service.

  • Broadcast API (~/segment) - segment objects from the most recent point cloud from the point_cloud_topic param, and send the result on the ~/segmented_objects topic. This API takes an empty service message, and is recommended for cases where multiple nodes will need to make use of the segmented object information.

  • Direct API (~/segment_objects) - segment objects from the most recent point cloud from point_cloud_topic, and return the results in the service response. This API directly returns results to the service client that initiated the segmentation call, and is recommended for directly incorporating object segmentation into a linear pipeline.

  • Static Point Cloud API (~/segment_objects_from_point_cloud) - segment objects from a given point cloud, and return the results in the service response. This API provides object segmentation from arbitrary point clouds, not limited to the ~point_cloud_topic param, and is recommended for applications that require multiple algorithms (including object segmentation) to run on the same point cloud, as the user has control over exactly which point cloud is used as input.

Nodes

rail_segmentation

rail_segmentation provides tabletop object segmentation for handheld objects, as well as segmentation within a robot's coordinate frame for detecting objects stored on a robot itself.

Subscribed Topics

<~/point_cloud_topic parameter> (sensor_msgs/PointCloud2)
  • Incoming point cloud data.

Published Topics

~/segmented_objects (rail_manipulation_msgs/SegmentedObjectList)
  • Segmented point clouds, images, markers, and calculated features for detected individual objects.
~/segmented_table (rail_manipulation_msgs/SegmentedObject)
  • A segmented object representing the detected surface above which object segmentation occurs.
~/markers (visualization_msgs/MarkerArray)
  • Visualization markers corresponding to the segmented objects.
~/table_marker (visualization_msgs/Marker)
  • Marker corresponding to the detected segmentation surface.
~/debug_pc (sensor_msgs/PointCloud2)
  • Point cloud publisher for debugging the pipeline, only used if the debug parameter is set to true.
~/debug_img (sensor_msgs/Image)
  • Image publisher for debugging the pipeline, only used if the debug parameter is set to true.

Services

~/segment (std_srvs/Empty)
  • Perform object segmentation that will automatically determine a segmentation zone (coordinate frame and bounding volume) as defined by the zones.yaml config file.
~/segment_objects (rail_manipulation_msgs/SegmentObjects)
  • Alternate API to call object segmentation that returns the segmented objects list as the result in the service message (will also still publish segmented objects on the ~/segmented_objects topic).
~/segment_objects_from_point_cloud (rail_manipulation_msgs/SegmentObjectsFromPointCloud)
  • Alternate API to call object segmentation on a point cloud that's passed in through the service request, rather than on the most up-to-date point cloud from the point_cloud_topic param.
~/clear (std_srvs/Empty)
  • Clear all segmented objects from the segmented object list.
~/remove_object (rail_segmentation/RemoveObject)
  • Remove an object from the segmented object list at a given index.
~/calculate_features (rail_manipulation_msgs/ProcessSegmentedObjects)
  • Recalculate, or fill in uncalculated features of, a given list of segmented objects; assumes that at minimum the point cloud field is set (note that some features cannot be recalculated after segmentation, such as the 2d image).

Parameters

~/debug (bool, default: false)
  • Flag to publish debugging information.
~/point_cloud_topic (string, default: "/camera/depth_registered/points")
  • ROS topic name for incoming point cloud data.
~/zones_config (string, default: "<path to rail_segmentation>/config/zones.yaml")
  • Location of the config file defining segmentation zones.
~/min_cluster_size (int, default: 200)
  • Minimum number of points in a segmented cluster required to be considered a segmented object.
~/max_cluster_size (int, default: 10000)
  • Maximum number of points in a segmented cluster required to be considered a segmented object.
~/cluster_tolerance (double, default: 0.02)
  • Maximum Euclidean distance to consider a point as belonging to a cluster, in meters.
~/use_color (bool, default: false)
  • Flag to enable color-based clustering on top of Euclidean distance clustering.
~/crop_first (bool, default: false)
  • Flag to crop the workspace to the segmentation zone workspace bounds before performing table surface detection (helps performance, but may make it harder to detect large surfaces, particularly in cluttered environments).
~/label_markers (bool, default: false)
  • Flag to label the cluster visualization markers published on the ~/markers topic with text markers showing the corresponding cluster indices from the ~/segmented_objects topic.

Installation

To install the rail_segmentation package, you can install from source with the following commands:

  •    1 cd /(your catkin workspace)/src
       2 git clone https://github.com/GT-RAIL/rail_segmentation.git
       3 cd ..
       4 catkin_make
       5 catkin_make install
    

Defining Segmentation Zones

Segmentation zones can be defined in yaml config files, an example of which can be found in the config directory. The zones.yaml file defines a segmentation zone that will segment objects on horizontal surfaces anywhere above the level of the floor.

The fields for defining a zone are as follows:

Required fields:

  • name - (string) the name of the zone
  • parent_frame_id - (string) parent frame for calculating the roll, pitch, and yaw of the camera
  • child_frame_id - (string) child frame for calculating the roll, pitch, and yaw of the camera
  • bounding_frame_id - (string) the coordinate frame in which the segmentation bounding volume is defined
  • segmentation_frame_id - (string) the coordinate frame in which objects should be segmented

Optional fields:

  • remove_surface - (bool) flag for surface removal; set to true if segmentation surfaces should be detected and removed, false if segmentation should be bounded only by the bounding volume (defaults to false).
  • require_surface - (bool) flag for requiring a surface to be found in order to perform segmentation; if set to true, clustering will not be run if a large horizontal surface is not detected (defaults to false).
  • roll_min - (double) lower bound on camera roll for this zone to be used, calculated as the roll from the parent_frame_id to the child_frame_id
  • roll_max - (double) upper bound on camera roll (for zone selection)
  • pitch_min - (double) lower bound on camera pitch (for zone selection)
  • pitch_max - (double) upper bound on camera pitch (for zone selection)
  • yaw_min - (double) lower bound on camera yaw (for zone selection)
  • yaw_max - (double) upper bound on camera yaw (for zone selection)
  • x_min - lower x bound defining the bounding volume (for workspace cropping)
  • x_max - upper x bound defining the bounding volume (for workspace cropping)
  • y_min - lower y bound defining the bounding volume (for workspace cropping)
  • y_max - upper y bound defining the bounding volume (for workspace cropping)
  • z_min - lower z bound defining the bounding volume (for workspace cropping)
  • z_max - upper z bound defining the bounding volume (for workspace cropping)

Segmentation and Results

Segmentation is performed by point cloud clustering according to Euclidean distance (and optionally, similar color patches) within a workspace defined by the segmentation zone yaml file.

Each resulting segmented object is represented by a rail_manipulation_msgs SegmentedObject message, with the following data calculated and filled in:

  • point_cloud: the segmented point cloud
  • image: an rgb image containing the points of the segmented point cloud
  • centroid: the segmented point cloud centroid
  • center: the segmented point cloud center (ignores point cloud density)
  • bounding_volume: a vertically-aligned, minimum volume bounding rectangular prism
  • width (deprecated in favor of the bounding volume): object width (dimension along the x-axis in the point cloud frame)
  • depth (deprecated in favor of the bounding volume): object depth (dimension along the y-axis in the point cloud frame)
  • height (deprecated in favor of the bounding volume): object height (dimension along the z-axis in the point cloud frame)
  • rgb: average color in RGB color space
  • cielab: average color in CIELAB color space (allows for Euclidean distance calculation in the color space)
  • marker: downsampled point cloud marker for display in rviz

Startup

The rail_segmentation package can be launched by running the rail_segmentation node:

  • rosrun rail_segmentation rail_segmentation

Wiki: rail_segmentation (last edited 2019-06-27 18:28:10 by davidkent)