[Documentation] [TitleIndex] [WordIndex

Overview

The rosserial protocol is aimed at point-to-point ROS communications over a serial transmission line. We use the same serialization/de-serialization as standard ROS messages, simply adding a packet header and tail which allows multiple topics to share a common serial link. This page describes the low-level details of the packet header and tail, and several special topics used for synchronization.

Packet Format

  1st Byte - Sync Flag (Value: 0xff)
  2nd Byte - Sync Flag / Protocol version
  3rd Byte - Message Length (N) - Low Byte
  4th Byte - Message Length (N) - High Byte
  5th Byte - Checksum over message length
  6th Byte - Topic ID - Low Byte
  7th Byte - Topic ID - High Byte
  N Bytes  - Serialized Message Data
  Byte N+8 - Checksum over Topic ID and Message Data

The Protocol version byte was 0xff on ROS Groovy, 0xfe on ROS Hydro, Indigo, and Jade.

Topics ID 0-100 are reserved for system functions, as defined in the rosserial_msgs/TopicInfo message.

The checksums on the length and data are used to make sure that a particular packet has not been corrupted. The checksum over the data is computed as follows:

255 - ( (Topic ID Low Byte + 
         Topic ID High Byte + 
         data byte values) % 256)

Topic Negotiation

Before data transfer can begin, the PC/Tablet side must query the Arduino or other embedded device for the names and types of topics which will be published or subscribed to.

Topic negotiation consists of a query for topics, a response with the number of topics, and packets to define each topic. The request for topics uses a topic ID of 0.

The query for topics will look like:

  0xff 0xfe 0x00 0x00 0xff 0x00 0x00 0xff

A series of response packets (message type rosserial_msgs/TopicInfo, each containing information about a particular topic, with the following data in place of the serialized message:

  uint16 topic_id
  string topic_name
  string message_type
  string md5sum
  int32 buffer_size

Here, the topic name is the name of the topic, for instance "cmd_vel", and message type is the type of the message, for instance "geometry_msgs/Twist".

If a response packet is not received correctly, another query may be sent.

New in 0.3.0 MD5 checksums are now transmitted to verify that both the sender and receiver are using the same message.

Time

Time synchronization is handled by sending a std_msgs::Time in each direction. The embedded device can request the current time from the PC/Tablet by sending an empty Time message. The returned time is used to find clock offset.


2024-11-02 17:22