Mech Turk ROS package contains tools to annotation images (sensor_msgs/Image) with boxes and outlines of objects. The package provide:

  • image_snapper.py - a node to send all images from a topic for annotation
  • session_2_messages.py - retrieve all annotations from a session and send them as messages
  • link_topic.py - a temporary tool to register remote publishers in the local core
  • annotate_image_action_server.py - multi-goal action server implementing AnnotateImageAction

ROS API

image_snapper

Captures images and submits them for annotation

Subscribed Topics

image (sensor_msgs/Image)
  • Stream of images

Parameters

~server (string, default: "default")
  • The URL or alias of the server.
~session (string, default: REQUIRED)
  • The name of the session
~submit_enabled (bool, default: False)
  • if enabled, the images are submitted for annotation. The submission is disabled by default.
~jpeg_output_dir (bool, default: EMPTY)
  • The folder name where to save images. If unset, the images are not saved locally.

annotate_image_action

Anntoate image action server provides an implementation of AnnotateImage action.

Subscribed Topics

annotate_image_action/goal (mech_turk_ros/AnnotateImageActionGoal)
  • An image to annotate.
annotate_image_action/cancel (actionlib_msgs/GoalID)
  • A request to cancel a specific goal.
annotation (mech_turk_ros_msgs/ExternalImageAnnotation)
  • The topic on which annotation server broadcasts the annotations (can be specified through ~annotation_topic)

Published Topics

annotate_image_action/feedback (mech_turk_ros/AnnotateImageActionFeedback)
  • Feedback is not provided.
annotate_image_action/status (actionlib_msgs/GoalStatusArray)
  • Provides status information on the goals that are sent to the annotate_image action.
annotate_image_action/result (mech_turk_ros/AnnotateImageActionResult)
  • Result contains the mech_turk_ros_msgs/ExternalImageAnnotation with the resulting annotation.

Parameters

~server (string, default: "default")
  • The URL or alias of the server.
~session (string, default: REQUIRED)
  • The name of the session
~annotation_topic (string, default: "annotation")
  • New name of the topic on which the server publishes annotations
/run_id (string, default: )
  • Run ID is used to generate unique image IDs.
Links local annotation topic to the remote server annotation topic. Remote topic "/annotation" is linked to the local "annotation" topic. Local topic can be remapped or specified in "~local_topic_name". Either "url" or "server" is required.

Published Topics

annotation (mech_turk_ros_msgs/ExternalImageAnnotation)
  • Annotations from the remote server

Parameters

~url (string, default: NONE)
  • The URL of the remote web server
~server (string, default: NONE)
  • The alias of the remote web server
~remote_topic_name (string, default: /annotation)
  • The name of the remote topic to link from

session_2_messages

Downloads all annotations from the server and publishes them as messages.

Published Topics

annotation (mech_turk_ros_msgs/ExternalImageAnnotation)
  • Annotations from the remote server

Parameters

~server (string, default: "default")
  • The alias of the remote web server
~target_session (string, default: REQUIRED)
  • The name of the annotation session on the server
~quality_filter (string, default: "none")
  • The quality filter: "none" - no filtering, "good" - only good submissions.

Image UID

Mech turk ROS generates unique IDs for images to refer to images in the annotations. The image unique ID is formed as: run_id.topic.secs.nsecs . We replace "/" with "-" in the topic name to ensure that the UID can be used as part of a URL.

This UID format is used by image_snapper and annotation_image_action_server to identify images on the annotation server. The UID is then saved in the ImageReference.uid field. The image_snapper and annotate_image_action_server require the image header to have a non-empty time stamp.

Wiki: mech_turk_ros (last edited 2010-02-23 17:54:07 by PeterBrook)