Basics before starting with Robotics — Part 6

Topics in ROS

Talha Hanif Butt
13 min readApr 6, 2022

I have previously written about some basics of ROS here:

Things only get interesting when nodes communicate with each other, exchanging information and data. The most common way to do that is through topics. A topic is a name for a stream of messages with a defined type. For example, the data from a camera might be sent over a topic called image , with a message type of Image.

Topics implement a publish/subscribe communication mechanism, one of the more common ways to exchange data in a distributed system. Before nodes start to transmit data over topics, they must first announce, or advertise, both the topic name and the types of messages that are going to be sent. Then they can start to send, or publish, the actual data on the topic. Nodes that want to receive messages on a topic can subscribe to that topic by making a request to roscore . After subscribing, all messages on the topic are delivered to the node that made the request. One of the main advantages to using ROS is that all the messy details of setting up the necessary connections when nodes advertise or subscribe to topics is handled for you by the underlying communication mechanism so that you don’t have to worry about it yourself.

In ROS, all messages on the same topic must be of the same data type. Although ROS does not enforce it, topic names often describe the messages that are sent over them. For example, on the PR2 robot, the topic /wide_stereo/right/image_color is used for color images from the rightmost camera of the wide-angle stereo pair.

Following is the basic code for advertising a topic and publishing messages on it. This node publishes consecutive integers on the topic counter at a rate of 2 Hz.

#!/usr/bin/env python2

import rospy
from std_msgs.msg import Int32

rospy.init_node(‘topic_publisher’)
pub = rospy.Publisher(‘counter’, Int32)
rate = rospy.Rate(2)
count = 0

while not rospy.is_shutdown():
pub.publish(count)
count += 1
rate.sleep()

#!/usr/bin/env python2
is known as the shebang. It lets the operating system know that this is a Python file, and that it should be passed to the Python interpreter. Since we’re going to be running the nodes we write as programs, we also have to set execute permissions on them using the Linux chmod command:

chmod u+x topic_publisher.py

This particular invocation of chmod will allow the owner of the file to execute it.

import rospy
appears in every ROS Python node and imports all of the basic functionality that we’ll need. The next line imports the definition of the message that we’re going to send over the topic:

from std_msgs.msg import Int32
In this case, we’re going to use a 32-bit integer, defined in the ROS standard message package, std_msgs .

Since we’re using a message from another package, we have to tell the ROS build system about this by adding a dependency to our package.xml file:
<depend>std_msgs</depend>

Without this dependency, ROS will not know where to find the message definition, and the node will not be able to run.

After initializing the node, we advertise it with a Publisher :
pub = rospy.Publisher(‘counter’, Int32)

This gives the topic a name ( counter ) and specifies the type of message that will be sent over it ( Int32 ). Behind the scenes, the publisher also sets up a connection to roscore and sends some information to it. When another node tries to subscribe to the counter topic, roscore will share its list of publishers and subscribers, which the nodes will then use to create direct connections between all publishers and of all subscribers to each topic.

At this point, the topic is advertised and is available for other nodes to subscribe to. Now we can go about actually publishing messages over the topic:
rate = rospy.Rate(2)
count = 0

while not rospy.is_shutdown():
pub.publish(count)
count += 1
rate.sleep()

First, we set the rate, in hertz, at which we want to publish. For this example, we’re going to publish twice a second. The is_shutdown() function will return True if the node is ready to be shut down and False otherwise, so we can use this to determine if it is time to exit the while loop.

Inside the while loop, we publish the current value of the counter, increment its value by 1, and then sleep for a while. The call to rate.sleep() will sleep for long enough to make sure that we run the body of the while loop at approximately 2 Hz.

And that’s it. We now have a minimalist ROS node that advertises the counter topic and publishes integers on it.

Checking That Everything Works as Expected

Now that we have a node set up, let’s verify that it works. We can use the rostopic command to dig into the currently available topics. Open a new terminal, and start up roscore . Once it’s running, you can see what topics are available by running rostopic list in another terminal:
rostopic list

These topics are used by ROS for logging and debugging; don’t worry about them. If you ever forget what the arguments to rostopic are, then you can use the -h flag to list them. This generally works for the other ROS command-line tools, too:
rostopic -h

Now, run the node we’ve just looked at in yet another terminal. Make sure that the my_awesome_code package is in a workspace, and you’ve sourced the setup file for that workspace:
rosrun my_awesome_code topic_publisher.py

Remember that the my_awesome_code directory has to be in your catkin workspace, and that, if you typed in the code for the node yourself, the file will need to have its execute permissions set using chmod . Once the node is running, you can verify that the counter topic is advertised by running rostopic list again:
rostopic list

Even better, you can see the messages being published to the topic by running rostopic echo :
rostopic echo counter -n 5

The -n 5 flag tells rostopic to only print out five messages. Without it, it will happily go on printing messages forever, until you stop it with a Ctrl-C. We can also use rostopic to verify that we’re publishing at the rate we think we are:
rostopic hz counter

rostopic hz has to be stopped with a Ctrl-C. Similarly, rostopic bw will give information about the bandwidth being used by the topic.

You can also find out about an advertised topic with rostopic info :
rostopic info counter

This reveals that counter carries messages of type std_msgs/Int32 , that it is currently being advertised by topic_publisher , and that no one is currently subscribing to it. Since it’s possible for more than one node to publish to the same topic and for more than one node to be subscribed to a topic, this command can help you make sure things are connected in the way that you think they are. Here, the publisher topic_publisher is running on the computer hostname and is communicating over TCP port 39964. rostopic type works similarly but only returns the message type for a given topic.

Finally, you can find all of the topics that publish a certain message type using rostopic find :
rostopic find std_msgs/Int32

Subscribing to a Topic

Following shows a minimalist node that subscribes to the counter topic and prints out the values in the messages as they arrive.

#!/usr/bin/env python2
import rospy
from std_msgs.msg import Int32

def callback(msg):
print msg.data

rospy.init_node(‘topic_subscriber’)
sub = rospy.Subscriber(‘counter’, Int32, callback)
rospy.spin()

The first interesting part of this code is the callback that handles the messages as they come in:
def callback(msg):
print msg.data

ROS is an event-driven system, and it uses callback functions heavily. Once a node has subscribed to a topic, every time a message arrives on it the associated callback function is called, with the message as its parameter. In this case, the function simply prints out the data contained in the message.

After initializing the node, as before, we subscribe to the counter topic:
sub = rospy.Subscriber(‘counter’, Int32, callback)

We give the name of the topic, the message type of the topic, and the name of the callback function. Behind the scenes, the subscriber passes this information on to roscore and tries to make a direct connection with the publishers of this topic. If the topic does not exist, or if the type is wrong, there are no error messages: the node will simply wait until messages start being published on the topic.

Once the subscription is made, we give control over to ROS by calling rospy.spin() . This function will only return when the node is ready to shut down. This is just a useful shortcut to avoid having to define a top-level while loop. ROS does not necessarily need to “take over” the main thread of execution.

Checking That Everything Works as Expected

First, make sure that the publisher node is still running and that it is still publishing messages on the counter topic. Then, in another terminal, start up the subscriber node:
rosrun my_awesome_code topic_subscriber.py

It should start to print out integers published to the counter topic by the publisher node.

Congratulations! You’re now running your first ROS system.

Defining Your Own Message Types

ROS offers a rich set of built-in message types. The std_msgs package defines the primitive types. Arrays of these types, both fixed and variable length, are returned (from the lower-level communications deserialization code) as tuples in Python and can be set as either tuples or lists.

These primitive types are used to build all of the messages used in ROS. These messages are contained in the std_msgs package and the common_msgs package. These message types are part of what gives ROS its power. Since (most) laser range-finder sensors publish sensor_msgs/LaserScan messages, we can write control code for our robots without having to know the specific details of the laser range-finder hardware.

Furthermore, most robots can publish their estimated locations in a standard way. Using standardized message types for laser scans and location estimates enables nodes can be written that provide navigation and mapping (among many other things) for a wide variety of robots.

However, there are times when the built-in message types are not enough, and we have to define our own messages. These messages are “first-class citizens” in ROS, and there is no distinction between the message types that are defined in the core of ROS and those you define yourself.

Defining a New Message

ROS messages are defined by special message-definition files in the msg directory of a package. These files are then compiled into language-specific implementations that can be used in your code. This means that, even if you’re using an interpreted language such as Python, you need to run catkin_make if you’re going to define your own message types. Otherwise, the language-specific implementation will not be generated, and Python will not be able to find your new message type. Furthermore, if you don’t rerun catkin_make after you change the message definition, Python will still be using the older version of the message type. Although this sounds like an extra layer of complexity, there is a good reason to do things this way: it allows us to define a message once and have it automatically available in all languages that ROS supports, without having to manually write the (extremely tedious) code that “deflates” and “inflates” messages as they come
across the network.

Message-definition files are typically quite simple and short. Each line specifies a type and a field name. Types can be built-in ROS primitive types, message types from other packages, arrays of types (either primitive or from other packages, and either fixed or variable length), or the special Header type.

A message-definition file comprises a list of types that make up the message. These types can either be ones that are built into ROS, such as those defined in the std_msgs package, or types that you have defined yourself.

As a concrete example, suppose we wanted to publish random
complex numbers, instead of integers. A complex number has two parts, real and imaginary, both of which are floating-point numbers. The message-definition file for our new type, called Complex , is as follows:

The file Complex.msg is in the msg directory of the my_awesome_code package. It defines two values, real and imaginary , both with the same type ( float32 ).

Once the message is defined, we need to run catkin_make to generate the language-specific code that will let us use it. This code includes a definition of the type, and code to marshal and unmarshal it for transmission down a topic. This allows us to use the message in all of the languages that ROS supports; nodes written in one language can subscribe to topics from nodes written in another. Moreover, it allows us to use messages to communicate seamlessly between computers with different architectures.

To get ROS to generate the language-specific message code, we need to make sure that we tell the build system about the new message definitions. We can do this by adding these lines to our package.xml file:

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>

Next, we need to make a few changes to the CMakeLists.txt file. First, we need to add message_generation to the end of the find_package() call , so that catkin knows to look for the message_generation package:

find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation # Add message_generation here, after the other packages
)

Then we need to tell catkin that we’re going to use messages at runtime, by adding message_runtime to the catkin_package() call:

catkin_package(
CATKIN_DEPENDS message_runtime # This will not be the only thing here
)

We tell catkin which message files we want to compile by adding them to the
add_message_files() call:

add_message_files(
FILES
Complex.msg
)

Finally, still in the CMakeLists.txt file, we need to make sure the generate_messages() call is uncommented and contains all the dependencies that are needed by our messages:

generate_messages(
DEPENDENCIES
std_msgs
)

Now that we’ve told catkin everything that it needs to know about our messages, we’re ready to compile them. Go to the root of your catkin workspace, and run catkin_make . This will generate a message type with the same name as the message-definition file, with the .msg extension removed. By convention, ROS types are capitalized and contain no underscores.

Generated message definitions contain an MD5 checksum. This is used by ROS to make sure that it’s using the correct version of a message. If you modify your message-definition files and run catkin_make over them, you might also have to run catkin_make over any code that uses these messages, to make sure that the checksums match up. This is generally more of a problem with C++ than with Python, since the checksums are compiled into the executables. However, it can be an issue with Python with compiled byte code (.pyc files).

Using Your New Message

Once your message is defined and compiled, you can use it just like any other message in ROS, as you can see below:

#!/usr/bin/env python2
import rospy
from my_awesome_code.msg import Complex
from random import random

rospy.init_node(‘message_publisher’)
pub = rospy.Publisher(‘complex’, Complex)
rate = rospy.Rate(2)

while not rospy.is_shutdown():

msg = Complex()
msg.real = random()
msg.imaginary = random()
pub.publish(msg)
rate.sleep()

Importing your new message type works just like including a standard ROS message type and allows you to create a message instance just like any other Python class. Once you’ve created the instance, you can fill in the values for the individual fields. Any fields that are not explicitly assigned a value should be considered to have an undefined value.

Subscribing to and using your new message is similarly easy as shown below:

#!/usr/bin/env python2
import rospy
from my_awesome_code.msg import Complex

def callback(msg):

print ‘Real:’, msg.real
print ‘Imaginary:’, msg.imaginary
print

rospy.init_node(‘message_subscriber’)
sub = rospy.Subscriber(‘complex’, Complex, callback)
rospy.spin()

When Should You Make a New Message Type?

The short answer is, “Only when you absolutely have to.” ROS already has a rich set of message types, and you should use one of these if you can. Part of the power of ROS is the ability to combine nodes together to form complex systems, and this can only happen if nodes publish and receive messages of the same type. So, before you go and create a new message type, you should use rosmsg to see if there is already something there that you can use instead. ROS messages define the public interface between nodes. Nodes that use the same messages can easily be combined into a running system. However, if every node uses a different message for similar data, then you’ll have to do a lot of (pointless) work translating between these messages in order to get something working. You should prefer existing message types whenever you can, since this will make your code fit in more seamlessly with the existing ROS code base. Similarly, you should use SI units (meters, kilograms, seconds, etc.) whenever possible, since this is what the rest of ROS uses.

That’s it for now. See you later.

References

https://github.com/StevenShiChina/books/blob/master/Programming.Robots.with.ROS.A.Practical.Introduction.to.the.Robot.Operating.System.pdf

--

--

Talha Hanif Butt

PhD Student -- Signal and Systems Engineering, Halmstad University, Volvo Trucks http://pk.linkedin.com/in/talhahanifbutt