rosserial overview: NodeHandles and Initialization | Messages | Publishers and Subscribers | Time | Logging | Limitations | Protocol | Parameters

Message generation

Like all ROS Client Libraries, rosserial takes msg files and generates Arduino C/C++ source code for them. The pattern for this is:

  • package_name/msg/Foo.msgpackage_name::Foo

Similarly, srv files also have C/C++ source code generated. The pattern for this is:

  • package_name/srv/Bar.srvpackage_name::Bar

The source for the generated files are in the package_name directory of ros_lib library folder.

Thus, including the std_msgs/String message in your code involves:

   1 #include <std_msgs/String.h>
   2 

and instantiating the message:

   1 std_msgs::String str;

Note that all fields in a message are currently initialized to a default value of 0 (or null pointers for strings and variable-length arrays).

Also be aware that the arrays in the messages are not defined as vector objects. Thus you have to predefine the array and then pass it as pointer to the message. To determine the end of the array each one has an auto-generated integer companion with the same name and the suffix _length. (see also rosserial/Overview/Limitations)

Example for sensor_msgs/JointState:

   1 //creating the message
   2 sensor_msgs::JointState jstate;
   3 
   4 //creating the arrays for the message
   5 char *name[] = {"motor_1", "motor_2"};
   6 float vel[]={0,0};
   7 float pos[]={0,0};
   8 float eff[]={0,0};
   9 
  10 //assigning the arrays to the message
  11 jstate.name=name;
  12 jstate.position=pos;
  13 jstate.velocity=vel;
  14 jstate.effort=eff;
  15 
  16 //setting the length
  17 jstate.name_length=2;
  18 jstate.position_length=2;
  19 jstate.velocity_length=2;
  20 jstate.effort_length=2;

Message Header Generation

When you run make in the rosserial_arduino package, header files are automatically created for many common messages. Please see this tutorial if you have additional messages for which you need to create header files.

Wiki: rosserial/Overview/Messages (last edited 2017-04-16 22:30:09 by RomainReignier)