Creating nodes: Messages | Publishers and subscribers | Services | Parameters | Logging | Exceptions | Running nodes | Building your package with Ant and rosmake | manifest.xml | ros.properties | Developing your project in Eclipse | Integrating test results from JUnit | rosjava-related packages

Location of Generated Messages

Unlike other ROS client libraries, rosjava stores generated ROS messages in your local .ros preferences folder (usually located at ~/.ros/rosjava/).

This is a temporary solution. In the future, generated messages will be stored in a local Maven repository. See issue 62.

Using Messages

To import a specific message, you must first declare a dependency on that message's package in your manifest.xml file. This will add the message's jar file to your Java classpath.

Next, to use a message such as sensor_msgs/PointCloud2, simply add an import. Rather than instantiate the message directly, however, it's preferred that you use a MessageFactory instead. This helps allow the underlying message implementation to change in the future.

   1 import  org.ros.message.sensor_msgs.PointCloud;
   2 
   3 ...
   4 
   5 Node node;
   6 
   7 ...
   8 
   9 PointCloud2 msg = node.getMessageFactory()
  10     .newMessage("sensor_msgs/PointCloud");

If you want to use messages that you define, there are at least 2 cases as follows.

Use the messages newly defined for the package

Under the same stack, create a non-java package that only contains message definition. Then in manifest.xml in your java package, refer to that non-java package. rosmake should generate jar file accordingly.

Use the messages defined in another non-java package

Similarly, specify dependency in manifest.xml file. Do the same for the rest.

Messages as BLOBs (Advanced)

If you need to deserialize a ROS message BLOB, it is important to remember that Java is a big endian virtual machine. When supplying the ByteBuffer to the MessageDeserializer, make sure that order is set to little endian.

   1 Node node;
   2 byte[] messageData;
   3 
   4 ...
   5 
   6 ByteBuffer buffer = ByteBuffer.wrap(messageData);
   7 buffer.order(ByteOrder.LITTLE_ENDIAN);
   8 PointCloud2 msg = node.getMessageSerializationFactory()
   9     .newMessageDeserializer("sensor_msgs/PointCloud")
  10         .deserialize(buffer);

Wiki: rosjava/Overview/Messages (last edited 2011-10-24 22:10:27 by IsaacSaito)