Defining messages
CONTENT

jrosclient keeps all standard ROS message definitions in jrosmessages Java module. This module provides definition for some basic ROS messages (from std_msgs and others) which are identical for all versions of ROS (ROS1, ROS2). Messages which are different between ROS versions available in separate modules: jros2messages, jros1messages.

In case some of the standard ROS messages are missing or you want to use your own messages, it is highly recommended to use msgmonster application. Additionally jrosclient allows you to define them manually as described in this document.

Built-in type mapping

jrosclient supports following mapping of ROS built-in types to Java types:

Complete list of ROS built-in types:

Type of char

In Java size of char is 2 bytes whereas in ROS2 it is the same as in C++ and equals to 1 byte. To prevent possible data loss when converting Java char (2 bytes) to ROS char (1 byte), jros2client maps both ROS built-in types "byte" and "char" into single Java primitive type "byte" (see CharMessageSubscriberApp for example). In ROS1 char is deprecated.

Message class requirements

Every message class should:

  1. Implement Message interface
  2. Be annotated with @MessageMetadata
  3. Have default constructor
  4. Streamed field names should match with how they are defined in ROS msg file
  5. Streamed fields should be defined in the same order as they defined in ROS msg file
  6. All streamed fields should be public
  7. If ROS message consist from more than one field then all such fields should be listed inside "fields" parameter of the @MessageMetadata annotation. Fields should be listed in the same order as they defined inside the ROS message (and this is also the order in which they will be (de)serialized). For example:
  8. Streamed fields which have reference types should be initialized. If they contain null they will be ignored during serialization of the message object which will lead to invalid format of the message.
  9. For example this is wrong, since stamp field contains null:

    public Time stamp;
    

    Correct, field stamp is non-null and Time class will be serialized as part of the message class where it is declared:

    public Time stamp = new Time();
    
  10. Streamed fields which point to arrays should be initialized with empty arrays:
  11. public Point32Message[] points = new Point32Message[0];
    
  12. Streamed fields which point to fixed size arrays should include @Array annotation with array size:
  13. # ROS shape_msgs/Plane definition
    float64[4] coef
    
    // Java definition
    @Array(size = 4)
    public double[] coef = new double[0];
    

Example of defining new message

As an example lets define message Java class for geometry_msgs/PolygonStamped (it is already part of jrosclient).

Its ROS definition can be found in ROS_INSTALL_DIR/share/geometry_msgs/msg/PolygonStamped.msg and it looks like:

# This represents a Polygon with reference coordinate frame and timestamp
Header header
Polygon polygon

As we see it consist from two other messages:

Because Polygon type is not available, before proceeding with PolygonStamped we need to define Polygon first.

Polygon definition

Polygon definition can be found in ROS_INSTALL_DIR/geometry_msgs/msg/Polygon.msg and it consist from:

#A specification of a polygon where the first and last points are assumed to be connected
Point32[] points

Point32 type is available in jrosclient so we can define Polygon message type right away.

Before writing a message class make sure you have:

To calculate md5 sum for geometry_msgs/Polygon (required for ROS1 only) we can use following ROS1 command:

rosmsg md5 geometry_msgs/Polygon
cd60a26494a087f577976f0329fa120e

Now, since we have all the information let's define a Java message class for geometry_msgs/Polygon:

/** Example of custom message definition */
@MessageMetadata(
        name = PolygonMessage.NAME,
        /*fields = {"points"} /* This parameter is optional because message has only one field */
        md5sum = "cd60a26494a087f577976f0329fa120e")
public static class PolygonMessage implements Message {

    static final String NAME = "geometry_msgs/Polygon";

    public Point32Message[] points = new Point32Message[0];

    public PolygonMessage withPoints(Point32Message[] points) {
        this.points = points;
        return this;
    }
}

Since this message has same format between ROS1 and ROS2 we would like to use it for both and therefore we specify md5sum. For messages which target only ROS2 md5sum is not required.

PolygonStamped definition

As we saw before geometry_msgs/PolygonStamped message consist from:

Because now we have all these types available we are ready to define geometry_msgs/PolygonStamped itself. But due to difference of Header type format in ROS2 and ROS1 we will have to create separate PolygonStamped for each of them.

ROS2

Java message class definition for geometry_msgs/PolygonStamped:

import id.jros2messages.std_msgs.HeaderMessage;

/** Example of custom message definition */
@MessageMetadata(
        name = PolygonStampedMessage.NAME,
        fields = {"header", "polygon"})
public static class PolygonStampedMessage implements Message {

    static final String NAME = "geometry_msgs/PolygonStamped";

    public HeaderMessage header = new HeaderMessage();

    public PolygonMessage polygon = new PolygonMessage();

    public PolygonStampedMessage withPolygon(PolygonMessage polygon) {
        this.polygon = polygon;
        return this;
    }

    public PolygonStampedMessage withHeader(HeaderMessage header) {
        this.header = header;
        return this;
    }
}

ROS1

As always first step is to calculate the md5 sum or the ROS1 message definition:

rosmsg md5 geometry_msgs/PolygonStamped
c6be8f7dc3bee7fe9e8d296070f53340

Now Java message class definition for geometry_msgs/PolygonStamped:

import id.jros1messages.std_msgs.HeaderMessage;

/** Example of custom message definition */
@MessageMetadata(
        name = PolygonStampedMessage.NAME,
        fields = {"header", "polygon"},
        md5sum = "c6be8f7dc3bee7fe9e8d296070f53340")
public static class PolygonStampedMessage implements Message {

    static final String NAME = "geometry_msgs/PolygonStamped";

    public HeaderMessage header = new HeaderMessage();

    public PolygonMessage polygon = new PolygonMessage();

    public PolygonStampedMessage withPolygon(PolygonMessage polygon) {
        this.polygon = polygon;
        return this;
    }

    public PolygonStampedMessage withHeader(HeaderMessage header) {
        this.header = header;
        return this;
    }
}

Using new message

Since we just defined geometry_msgs/PolygonStamped message, lets create a topic for it and start to publish messages from Java using jrosclient. Complete examples:

Final result

Once you start the application you should see its output like:

Published
Published
Published
Published
Published
Published
Published
Published
Published
...

Now start RViz and go to Displays -> Add -> By Topic -> /PolygonExample. This should subscribe you to the topic and you should see the polygon: