ROS AsyncSpinner Example

In this tutorial I’ll show you how to use a ROS AsyncSpinner with an example. You’ll see when using a roscpp AsyncSpinner is required, instead of the standard roscpp spinner.

This tutorial could also be called: how to solve roscpp callback issues, when it seems that some callbacks are stuck or late.

We’ll start by seeing a code example which has some callback problems. Some callbacks will be stuck, waiting for other callbacks (from different topics) to finish. And then we’ll see how using AsyncSpinner instead of the standard roscpp spinner can solve that.

Also, the problem you’ll see here only applies to roscpp callbacks, not rospy. You’ll get to know why during this tutorial.

If you like having problems, start with a few roscpp callbacks!

It’s really important that you understand the problem first. I won’t tell you to use AsyncSpinner because it’s just “better”, without letting you know why.

That’s why this first part is quite long and detailed, so you can understand the real reason behind all that. Once you understand the issue here, you’ll easily see when it makes sense to use AsyncSpinner in your roscpp nodes.


You are learning ROS?

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


Setup with no callback issue (for now)

Let’s create one roscpp node with 2 simple callbacks for 2 simple topics.

#include <ros/ros.h>
#include <std_msgs/String.h>

void callbackTalker1(const std_msgs::String::ConstPtr &msg)
{
    ROS_INFO("In callback talker1.");
    ROS_INFO("%s", msg->data.c_str());
}

void callbackTalker2(const std_msgs::String::ConstPtr &msg)
{
    ROS_INFO("In callback talker2.");
    ROS_INFO("%s", msg->data.c_str());
}


int main(int argc, char **argv)
{
    ros::init(argc, argv, "talker_subscribers");
    ros::NodeHandle nh;

    ros::Subscriber counter1_sub = nh.subscribe("talker1", 10, callbackTalker1);
    ros::Subscriber counter2_sub = nh.subscribe("talker2", 10, callbackTalker2);

    ros::spin();
}

That’s pretty simple here: the node subscribes to 2 topics, named “talker1” and “talker2”. Both topics use the std_msg/String data type. The 2 callbacks do the same thing, which is displaying the received message.

So, it seems like there is no problem with that!

Now let’s create a node to publish on those topics.

#!/usr/bin/env python

import rospy
from std_msgs.msg import String

if __name__ == "__main__":
    rospy.init_node("talker_publishers")

    talker1_pub = rospy.Publisher("talker1", String, queue_size=10)
    talker2_pub = rospy.Publisher("talker2", String, queue_size=10)

    rate = rospy.Rate(1.0)

    while not rospy.is_shutdown():
        talker1_pub.publish("Hey")
        talker2_pub.publish("Oy")
        rate.sleep()

Important note: you can create those publishers in Cpp or Python, it really doesn’t matter. Nothing is wrong with the publisher node, the issue will come (later) from the subscriber node. You could also publish directly from the terminal, but for simplicity, it’s better to just write a small and minimal node.

This node will simply publish on both “talker1” and “talker2” topics at a 1 Hz frequency. The first publisher will send “Hey” and the second publisher will send “Oy”. That’s it. For the rest of this tutorial we won’t modify this node.

Now, you can start roscore, and then the publisher node with for example rosrun asyncspinner_tutorials talker_publishers.py. You can keep it running for the rest of this tutorial or restart it for each test. For simplicity, in the following, when I write “start the subscriber” I’ll assume that the publisher is already running.

And, if you start the roscpp subscriber node, you’ll get this:

$ rosrun asyncspinner_tutorials talker_subscribers 
[ INFO] [1572016597.728219447]: Hey
[ INFO] [1572016597.730289973]: Oy
[ INFO] [1572016598.728299107]: Oy
[ INFO] [1572016598.728426453]: Hey
[ INFO] [1572016599.728055430]: Hey
[ INFO] [1572016599.728406145]: Oy
[ INFO] [1572016600.728138572]: Hey
[ INFO] [1572016600.728322249]: Oy
[ INFO] [1572016601.728317492]: Oy
[ INFO] [1572016601.728488483]: Hey

It’s working pretty well, no problem here! From the log timestamps you can see that each “Hey” and “Oy” are received by the subscriber and printed every second, which is the rate set on the publisher side.

You can notice that sometimes, data from the “talker1” topic comes after data from the “talker2” topic. This is not an issue here. In fact, in the publisher we publish on those topics without any delay, so it’s like they’re sent at the exact same time. The subscriber node will receive them at almost the same time, and when waking up the callback functions, the second one may be called before the first one, that’s it.

Now, let’s get to the problem.

A callback is stuck or late because of another callback

Let’s add a delay in the first callback.

void callbackTalker1(const std_msgs::String::ConstPtr &msg)
{
    ROS_INFO("In callback talker1.");
    ros::Duration(2.0).sleep();
    ROS_INFO("%s", msg->data.c_str());
}

The callback for “talker1” topic will now take 2 seconds, in addition to the time to process log messages.

I’ve also added a log before the sleep() function so we can see in the terminal when the callback is called, and when it’s about to exit.

Compile with catkin_make, and start the roscpp subscriber node again.

$ rosrun asyncspinner_tutorials talker_subscribers 
[ INFO] [1572017356.727231274]: In callback talker1. # --> 1. + 2.
[ INFO] [1572017358.729365483]: Hey                  # --> 3.
[ INFO] [1572017358.729531863]: Oy                   # --> 4.
[ INFO] [1572017358.729620036]: Oy
[ INFO] [1572017358.729695363]: In callback talker1. # --> 5.
[ INFO] [1572017360.729897573]: Hey
[ INFO] [1572017360.730062467]: In callback talker1.
[ INFO] [1572017362.730324234]: Hey
[ INFO] [1572017362.730476893]: Oy
[ INFO] [1572017362.730599778]: Oy
[ INFO] [1572017362.730718380]: In callback talker1.
[ INFO] [1572017364.730940686]: Hey
[ INFO] [1572017364.731074145]: In callback talker1.
[ INFO] [1572017366.731296653]: Hey
[ INFO] [1572017366.731472865]: Oy
[ INFO] [1572017366.731568124]: In callback talker1.

Things start to get weird!

So, what’s happening here (I’ve added numbers after the logs so this will be easier for you to follow):

  1. The subscriber node first receives a message from “talker1” and calls its associated callback.
  2. The callback is stuck for 2 seconds because of the sleep() we added. Nothing wrong with that, but as you can see it also prevents the “talker2” callback from being called! We didn’t change the “talker2” callback and yet it’s stuck because of another callback taking too much time.
  3. When the 2 seconds pause ends, “Hey” is printed, the “talker1” callback exits.
  4. Right after that – as you can see with the log timestamps – the “talker2” callback is called 2 times! This is because messages continued to arrive while “talker1” callback was stuck (the node kept them in a temporary queue), and now all the callbacks are triggered – one by one.
  5. And right after that, the “talker1” callback is called again, because while it was waiting for 2 seconds, another “talker1” message arrived, and the callback is already late.

And now, you already have a few messages in both the “talker1” and “talker2” waiting queues. So it’s becoming a mess and you can’t tell when a message will be printed by the subscriber node.

Also, when the temporary queue for a topic is full (limit set by the queue size parameter when creating the publisher or subscriber), some messages will be lost. In this code example I’ve set the queue size to 10. It means that 10 messages maximum will be saved, waiting for the callback to be triggered. After that, when a new message arrives, another one is deleted – and definitively lost.

roscpp spin is single-threaded

First, let’s talk about the “talker1” subscriber. It’s quite obvious that if you publish on this topic every second, and then in the callback you wait for 2 seconds, messages on this topic will be delayed. It’s not really an internal problem here, it’s more of a developer choice to do that (in this case, not a very good choice, but that made a good example for this tutorial).

The real question is: why is the “talker2” callback affected by the “talker1” callback? That’s the problem we will solve in this tutorial. We really want to receive messages from “talker2” at 1Hz.

The reason behind all that is that the roscpp standard spinner (ros::spin()) is single-threaded. It will execute all callbacks one by one, trying to respect the arrival date of messages or requests.

A callback will be executed only if the previous callback has finished. And the next callback will have to wait for the current callback to end.

That’s a pretty simple mechanism, and now you can understand why we had so many issues with the “talker2” callback. The “talker1” callback took a long time to complete, thus preventing the “talker2” callback from being executed.

Note: this issue only happens with roscpp. The rospy spinner is already multi-threaded, so you won’t be able to reproduce this issue if you translate the Cpp subscriber node to Python.

And as you could guess, the solution here will be to use the roscpp AsyncSpinner!

Other scenarios when you can have this issue

Of course, this issue doesn’t only happen when you have 2 subscribers and one is blocking the other. I chose this example because I think it allows to explain the problem without having to write – and explain – too much code.

Here are some common cases when you might encounter this problem:

  • You have one subscriber and one service server. The service server callback takes some time to respond, and the subscriber callback is delayed.
  • You have multiple subscriber callbacks and need a more precise timing. Even if no callback is completely blocking the callback stack, when you add up all callback execution duration, it can lead to some unwanted small “delays” in the last called callback.
  • You are using the roscpp ActionServer and want to be able to work with action callbacks and other subscriber callbacks in the same node.
  • Etc.

Using roscpp AsyncSpinner

AsyncSpinner is a threaded spinner. It means that each callback will get its own thread (if available). This should solve our problem with the “talker2” callback.

Solve the callback problem with AsyncSpinner

Keep the “talker1” callback with the delay, just change the spinner in the main.

...

int main(int argc, char **argv)
{
    ros::init(argc, argv, "talker_subscribers");
    ros::NodeHandle nh;

    ros::AsyncSpinner spinner(0);
    spinner.start();

    ros::Subscriber counter1_sub = nh.subscribe("talker1", 10, callbackTalker1);
    ros::Subscriber counter2_sub = nh.subscribe("talker2", 10, callbackTalker2);

    ros::waitForShutdown();
    // ros::spin(); --> we don't use that anymore
}

You need 3 lines instead of one:

  • ros::AsyncSpinner spinner(0); will create the spinner. The parameter corresponds to the number of threads you want to use. 0 means that the spinner will use as many threads as there are processors on your machine. If you use 3 for example, only 3 threads will be used.
  • spinner.start(); will start the AsyncSpinner asynchronously, as its name suggests. Note that the multi-threaded spinner is now running in the background, and the program continues.
  • ros::waitForShutdown(); is required here, because the AsyncSpinner won’t block. This command simply waits for the node to be killed.

Now, let’s run the subscriber node again:

$ rosrun asyncspinner_tutorials talker_subscribers 
[ INFO] [1572020143.073816636]: In callback talker1.
[ INFO] [1572020143.075847158]: Oy
[ INFO] [1572020144.073720083]: Oy
[ INFO] [1572020145.072990625]: Oy
[ INFO] [1572020145.075870583]: Hey
[ INFO] [1572020145.075935900]: In callback talker1.
[ INFO] [1572020146.072956221]: Oy
[ INFO] [1572020147.072851190]: Oy
[ INFO] [1572020147.076047053]: Hey
[ INFO] [1572020147.076103314]: In callback talker1.
[ INFO] [1572020148.072887200]: Oy
[ INFO] [1572020149.072907233]: Oy
[ INFO] [1572020149.076195823]: Hey

Well, as you can see, the “talker2” callback is now properly working! You can see a “Oy” message every second, no matter what is happening with the “talker1” callback.

Conclusion on AsyncSpinner

This callback issue can sometimes be quite tricky to find. You may spend a huge amount of time trying to debug your application, before you find out that a callback is not on time because of other callbacks. I hope this ROS AsyncSpinner example will help you shorten this debugging time.

A good practice is to always keep your callback functions fast, so you can avoid this kind of situation. But when you have several topic subscribers, service servers, and action servers running on your node, well that can quickly become quite tricky!

So, if your node is quite simple and you know exactly what’s going on, using a single threaded spinner (ros::spin()) might be more appropriate. If you have too many callbacks and are afraid that things will go out of control, use a roscpp AsyncSpinner.

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 <<