Note: This tutorial assumes that you have completed the previous tutorials: installing ROS.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Creating a ROS msg and srv (plain cmake)

Description: This tutorial covers how to create and build msg and srv files using plain cmake (i.e., not catkin).

Tutorial Level: BEGINNER

Note: Be sure that you have already installed ROS and remember that you must source the appropriate setup file in every shell you create.

Making a directory in which to work

To help keep yourself organized, make a directory in which to work. You can use any name; we'll just call it msgsrv:

mkdir -p msgsrv
cd msgsrv

Introduction to msg and srv

  • msg: msg files are simple text files that describe the fields of a ROS message. They are used to generate source code for messages in different languages.

  • srv: an srv file describes a service. It is composed of two parts: a request and a response.

msgs are just simple text files with a field type and field name per line. The field types you can use are:

  • int8, int16, int32, int64 (plus uint*)
  • float32, float64
  • string
  • time, duration
  • other msg files
  • variable-length array[] and fixed-length array[C]

There is also a special type in ROS: Header, the header contains a timestamp and coordinate frame information that are commonly used in ROS. You will frequently see the first line in a msg file have Header header.

Here is an example of a msg that uses a Header, a string primitive, and two other msgs :

  Header header
  string child_frame_id
  geometry_msgs/PoseWithCovariance pose
  geometry_msgs/TwistWithCovariance twist

srv files are just like msg files, except they contain two parts: a request and a response. The two parts are separated by a '---' line. Here is an example of a srv file:

int64 A
int64 B
---
int64 Sum

In the above example, A and B are the request, and Sum is the response.

Using msg

Creating a msg

Let's define a couple of new messages. Create a file named Foo.msg and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/Foo.msg

   1 int16 foo

Create a file named Bar.msg and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/Bar.msg

   1 uint16 bar
   2 # Use messages from other packages
   3 geometry_msgs/Pose pose
   4 map_msgs/ProjectedMap map

Using an existing msg (C++)

To have a simple C++ example of using an existing ROS message in code, create a file named use_existing_msg.cpp and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/use_existing_msg.cpp

#include <sensor_msgs/LaserScan.h>
#include <stdio.h>
int
main(void)
{
  sensor_msgs::LaserScan scan;
  for(int i=0; i<100; i++)
    scan.ranges.push_back(42.0*i);

  for(std::vector<float>::const_iterator it = scan.ranges.begin();
      it != scan.ranges.end();
      ++it)
    printf("%f\n", *it);
}

Using the new message in code (C++)

To have a simple C++ example of how to use custom messages from code, create a file named use_custom_msg.cpp and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/use_custom_msg.cpp

#include <myproject/Foo.h>
#include <myproject/Bar.h>
#include <stdio.h>
int
main(void)
{
  myproject::Foo foo;
  foo.foo = 42;
  printf("%d\n", foo.foo);

  myproject::Bar bar;
}

Using existing and new messages in code (Python)

To have a simple Python example of using both existing and new messages in code, create a file named use_msgs.py and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/use_msgs.py

#!/usr/bin/env python

from sensor_msgs.msg import LaserScan
from myproject.msg import Foo

f = Foo(42)
print(f.foo)

s = LaserScan()

Building messages and code

To use custom messages, we need to run the code generators provided by ROS to process .msg files into code for use in C++, Python, and other languages. Create a file named CMakeLists.txt and put the following in it:

https://raw.githubusercontent.com/gerkey/ros1_external_use/master/ros1_msgs/CMakeLists.txt

   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(myproject)
   3 
   4 # Build an executable that uses an existing ROS msg: find_package() the ROS
   5 # package that contains the message, then use its reported include directories.
   6 find_package(sensor_msgs REQUIRED)
   7 include_directories(${sensor_msgs_INCLUDE_DIRS})
   8 add_executable(use_existing_msg use_existing_msg.cpp)
   9 
  10 # Generate code from our own custom messages
  11 # find_package catkin and genmsg, required for message generation macros
  12 find_package(catkin REQUIRED)
  13 find_package(genmsg REQUIRED)
  14 # find_package the other message packages that our custom messages use
  15 find_package(geometry_msgs REQUIRED)
  16 find_package(map_msgs REQUIRED)
  17 # Enumerate our custom messages files
  18 add_message_files(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} FILES Foo.msg Bar.msg)
  19 # Do code generation, specifying which other message packages we depend on.
  20 generate_messages(DEPENDENCIES geometry_msgs map_msgs)
  21 
  22 # Build an executable that uses our messages, making it depend on the
  23 # message-generation step.
  24 add_executable(use_custom_msg use_custom_msg.cpp)
  25 add_dependencies(use_custom_msg ${PROJECT_NAME}_generate_messages)
  26 
  27 # (optional) Install the executables. The generated code will also
  28 # automatically be installed.
  29 install(TARGETS use_existing_msg use_custom_msg
  30         DESTINATION bin)
  31 install(PROGRAMS use_msgs.py
  32         DESTINATION bin)

Process your messages and build your (C++) code in a subdirectory of msgsrv named build using the standard cmake sequence:

mkdir -p build
cd build
cmake ..
make

Running the code

To confirm that everything is working properly, run each of the programs (they won't do anything terribly interesting):

./build/use_existing_msg

./build/use_custom_msg

python use_msgs.py

Using srv

TODO: fill out this section with analogous examples

Wiki: ROS/Tutorials/CreatingMsgAndSrv(plain cmake) (last edited 2020-01-10 21:46:19 by BrianGerkey)