ROS Topic command line tools – practical example (rostopic and rosmsg)

This tutorial is a practical guide on how to use rostopic and rosmsg command line tools to debug a ROS topic.

If you wonder how to monitor the publishers you’ve created, how to easily print the data from a topic, or even how to monitor a topic’s bandwidth, this post is for you. Through a real example I’ll show you how to get many info and debug a ROS topic from the terminal.

Code example for this tutorial

Let’s create a simple ROS publisher. In this example I’ll use Python with rospy to publish an integer value which increments at a given frequency (5 Hz to start).

import rospy
from std_msgs.msg import Int32

if __name__ == '__main__':
    rospy.init_node("counter_publisher")
    rate = rospy.Rate(5)
    pub = rospy.Publisher("/counter", Int32, queue_size=10)
    counter = 0
    rospy.loginfo("Publisher has been started.")

    while not rospy.is_shutdown():
        counter += 1
        msg = Int32()
        msg.data = counter
        pub.publish(counter)
        rate.sleep()

Run this node:

  • First don’t forget to start roscore in another terminal.
  • Make the file executable: chmod +x counter_publisher.py.
  • Run the node: python counter_publisher.py (you can also use rosrun if you want).

The node is now running, and your publisher has started publishing on the “/counter” topic. Let’s use the ROS topic command line tools to debug this topic!

Find the topic (rostopic list)

With rostopic list you can get the list of all active topics. As soon as you create a publisher on a topic, or a subscriber, the topic will appear on the list.


You are learning ROS?

Check out ROS For Beginners and learn ROS step by step.


$ rostopic list 
/counter
/rosout
/rosout_agg

We found the “/counter” topic!

As you may already know, 2 topics (“/rosout” and “/rosout_agg”) are started as soon as you start the ROS master. Those topics are used by the “/rosout” node to provide logging for your entire ROS app.

Note that as your application grows, so does the number of topics you have. When you start to have too many topics, using grep will help you save some time when looking for a specific topic.

$ rostopic list | grep counter
/counter

Print the data from the topic (rostopic echo)

Now that we have the name of the topic, let’s print everything that is published to it on the terminal. For that, use rostopic echo.

$ rostopic echo /counter 
data: 38
---
data: 39
---
data: 40
---
data: 41
---
data: 42
---

This command is basically doing the same thing as if you created a ROS subscriber in a node, and printed the data on the terminal every time the subscriber callback was triggered.

Creating a new node with a subscriber, just to see the data on the topic, is really not a valuable use of your time. rostopic echo is maybe the command line tool I use the most, it’s really useful and saves a lot of time.

Get more info about the topic (rostopic info)

So, you have found the topic on the list, and you can approximately guess what kind of data is published by printing the data on the terminal. To get more info, in order to be able to create a publisher or subscriber, use rostopic info.

$ rostopic info /counter 
Type: std_msgs/Int32

Publishers: 
 * /counter_publisher (http://ros-pc:35115/)

Subscribers: 
 * /rostopic_8672_1565641783401 (http://ros-pc:43663/)

A few useful info here:

  • Type: this is the message definition (.msg file) you need to use in order to publish or subscribe to the topic.
  • Publishers: list of all nodes publishing on the topic. Very useful if you don’t know from where some data is coming from.
  • Subscribers: list of all nodes subscribing to the topic. In this case we see the subscriber that was created the step before, when we used rostopic echo.

Find out what data you need to send and receive (rosmsg show)

Now that you have the definition (type) of the message for this topic, you can find out what data exactly you need to send (and receive) with rosmsg show.

$ rosmsg show std_msgs/Int32
int32 data

From that, we can conclude that the “std_msgs/Int32” message has only one field. This field is a 32 bits integer, and its name is “data”. By using rostopic echo we also knew the name of the field, but we couldn’t be sure about the exact data type.

For a complete list of all available message definitions on your ROS environment, run rosmsg list (the list will be quite long!). This can be useful combined with grep, to see if you’re missing a specific message definition (not installed or not compiled).

Publish on the topic from the terminal (rostopic pub)

As you can subscribe to a topic from the terminal (using rostopic echo), you can also publish directly with one command line.

Use rostopic pub with the info you got from the previous step:

$ rostopic pub /counter std_msgs/Int32 "data: 4" 
publishing and latching message. Press ctrl-C to terminate

First you need to give the name of the topic, then the type, and finally the data to send (Tip: press “TAB” for auto-completion, which makes things even more simple). You can see this newly sent data with rostopic echo /counter – make sure to subscribe before you publish the value, or else you won’t see it.

Now, one interesting thing here, is that you can publish on topics that don’t already exist… And even better, you can also subscribe to topics that don’t have a publisher yet.

Let’s subscribe to the “/new_in_town” topic (before we publish the data or else we’ll miss it).

$ rostopic echo /new_in_town
WARNING: topic [/new_in_town] does not appear to be published yet

The warning is absolutely not a problem. It can be useful if you misspelled a topic name (“coutner” instead of “counter” for example), but here we are conscious there is no publisher yet.

Let’s publish some data now (would also work without a subscriber but in this case no one receives the data):

$ rostopic pub /new_in_town std_msgs/String "data: 'hello there'" 
publishing and latching message. Press ctrl-C to terminate

Going back to the other tab, where we launched the subscriber:

$ rostopic echo /new_in_town
WARNING: topic [/new_in_town] does not appear to be published yet
data: "hello there"
---

Success!

This rostopic pub command can be useful to test behavior on a subscriber node. Note however that it’s only really handy for topics with small message definitions. If you want to publish big messages at a high frequency, it will be much simpler for you to create a 10-lines Python file.

Case with multiple nodes publishing on a topic

For now we’ve only seen what’s happening when only one node is publishing. In real ROS projects things are often more complicated than that.

Let’s create another publisher on this topic. For that, no need to create a new file.

Simply set the node as anonymous by changing this line:

rospy.init_node("counter_publisher")

to this:

rospy.init_node("counter_publisher", anonymous=True)

By doing that you’ll be able to spawn as many “counter_publisher” nodes as you want, each one publishing on the “/counter” topic.

Start the node in a terminal, open a new terminal, and start the node again.

Let’s run the commands we saw before to see what’s different.

$ rostopic list 
/counter
/rosout
/rosout_agg

Well, nothing changes here! Even if we have 2 nodes, they both publish on the same topic.

$ rostopic info /counter 
Type: std_msgs/Int32

Publishers: 
 * /counter_publisher_5999_1565637470743 (http://ros-pc:40047/)
 * /counter_publisher_6015_1565637475604 (http://ros-pc:42711/)

Subscribers: None

We can see that 2 different nodes are publishing on the topic. It’s quite handy to know that if you see data like this:

$ rostopic echo /counter 
data: 35
---
data: 60
---
data: 36
---
data: 61
---
data: 37
---
data: 62
---
data: 38
---
data: 63

This doesn’t look like a counter at all! Well, if you look closely, you’ll see that the 2 counters from the 2 publishers are mixed up. We can see the first counter: 35, 36, 37, … and the second one: 60, 61, 62, …

Of course, in real life it doesn’t really make sense to publish multiple counters on the same topic. But imagine you have a robot with 4 temperature sensors quite close to each other, and the overall temperature of the robot is the average of the data coming from those sensors. For each sensor you can start a node publishing on the “/temperature” topic. Thus you’ll have 4 publishers on this topic, and your subscriber can receive all the data and make the computation.

Monitor topic statistics and check performance (rostopic hz and rostopic bw)

Use rostopic hz to compute the publishing rate (or frequency) of a given topic.

Let’s run the publishing node only once.

$ rostopic hz /counter 
subscribed to [/counter]
average rate: 4.997
    min: 0.200s max: 0.201s std dev: 0.00026s window: 5
average rate: 4.999
    min: 0.200s max: 0.201s std dev: 0.00019s window: 10
average rate: 4.999
    min: 0.200s max: 0.201s std dev: 0.00016s window: 15

From that we can confirm that the publisher is keeping the 5Hz rate we set in the code. Not so hard, because 5Hz is quite low and we are just publishing a number. But if you publish, let’s say, a complete image at 1kHz, your publisher might have a hard time keeping up with this rate.

Using rostopic hz can be useful to see if a publisher can’t catch up with the given rate.

And now let’s run another anonymous node on another terminal.

$ rostopic hz /counter 
subscribed to [/counter]
average rate: 10.068
    min: 0.094s max: 0.106s std dev: 0.00577s window: 10
average rate: 10.032
    min: 0.094s max: 0.106s std dev: 0.00584s window: 20
average rate: 10.020
    min: 0.094s max: 0.106s std dev: 0.00584s window: 30

Here it’s quite obvious: 5Hz and 5Hz gives 10Hz, as we are publishing twice as fast. When you have different publishers with different rates, with this command you can get an idea of the average rate of all published data. This becomes less simple when different publishers have different rates!

After the average frequency, we can also monitor the average bandwidth used by a topic, with rostopic bw.

With one node running:

$ rostopic bw /counter 
subscribed to [/counter]
average: 22.71B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 5
average: 21.25B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 10
average: 20.81B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 15

With 2 nodes running:

$ rostopic bw /counter 
subscribed to [/counter]
average: 40.61B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 10
average: 40.28B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 20
average: 40.17B/s
    mean: 4.00B min: 4.00B max: 4.00B window: 30

Here you can see how much data is transferred every second on the topic. As we’re publishing integers at a low rate, the bandwidth is also really low. But that’s something worth monitoring if you’re working with 3D sensors, cameras, etc.

You can try to increase the frequency (ROS Rate inside the code) to see what’s going on. The maximum frequency and bandwidth you can get will depend on your computer performance.

Closing the loop

From the name of the topic, you were able to find a lot of useful info, all that in the terminal, using simple ROS topic command line tools.

Among those info you got the name of the publishing nodes.

Let’s close the loop (using one non-anonymous node):

$ rosnode info /counter_publisher 
--------------------------------------------------------------------------------
Node [/counter_publisher]
Publications: 
 * /counter [std_msgs/Int32]
 * /rosout [rosgraph_msgs/Log]

Subscriptions: None

Services: 
 * /counter_publisher/get_loggers
 * /counter_publisher/set_logger_level


contacting node http://ros-pc:36711/ ...
Pid: 6619
Connections:
 * topic: /rosout
    * to: /rosout
    * direction: outbound
    * transport: TCPROS

And… we can find the “/counter” topic (with the message type) inside the publisher list. The debugging loop is now complete!

ROS topic command line tools: going further with rostopic and rosmsg

With the steps you did in this tutorial, you know have enough knowledge and practice to seriously get started with debugging your own ROS topics.

From there I encourage you to experiment more with those command line tools. Create more complex topics, or use already existing ones from some ROS plugins, to get used to monitoring and debugging topics.

In this tutorial I haven’t showed you 100% of the command line tools, only the most important ones in a practical point of view. To get a reference of all available commands, type rostopic and rosmsg with no argument.

Did you find this tutorial useful?

Do you want to learn how to program with ROS?

If yes, this course is for you:

ROS For Beginners - A Step By Step Course

>> ROS For Beginners - A Step By Step Course <<