10

I am trying to understand how the AsyncSpinner from ROS really works because I may have something misunderstood. You can find a similar question here.

As seen here its definition mentions:

Asynchronous spinner: spawns a couple of threads (configurable) that will execute callbacks in parallel while not blocking the thread that called it. The start/stop method allows to control when the callbacks start being processed and when it should stop.

And in the official documentation here the AsyncSpinning is also remarked as a type of multi-threading Spinning.

So, said that, I have a very simple example with a publisher and subscriber with an AsyncSpinner to test the multi-threading behavior.

#include "ros/ros.h"
#include "std_msgs/String.h"

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

  ros::Publisher chatter_pub = nh.advertise<std_msgs::String>("chatter", 1000);

  ros::Rate loop_rate(10);
  while (ros::ok())
  {
    std_msgs::String msg;
    msg.data = "hello world";

    chatter_pub.publish(msg);

    ros::spinOnce();

    loop_rate.sleep();
  }

  return 0;
}

And the subscriber where the spinner is defined and used:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <boost/thread.hpp>

int count = 0;

void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
  count++;
  ROS_INFO("Subscriber %i callback: I heard %s", count, msg->data.c_str());
  sleep(1);
}

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

  ros::Subscriber sub = nh.subscribe("chatter", 1000, chatterCallback);

  ros::AsyncSpinner spinner(boost::thread::hardware_concurrency());
  ros::Rate r(10);

  spinner.start();
  ros::waitForShutdown();

  return 0;
}

When I run both programs I get the following output:

[ INFO] [1517215527.481856914]: Subscriber 1 callback: I heard hello world
[ INFO] [1517215528.482005146]: Subscriber 2 callback: I heard hello world
[ INFO] [1517215529.482204798]: Subscriber 3 callback: I heard hello world

As you can see the callback runs every second and no other callbacks are being called in parallel. I know that the global callback queue is being fulfilled because if I stop the publisher, the subscriber will keep popping the accumulated messages from the queue.

I know I should not block a callback but in the definition above is remarked that this will not stop the thread where it was called and I guess neither the others created by the spinner. Am I blocking the next callbacks just because I'm blocking the callback? Is there something I did misunderstood? I am bit confused and not able to demonstrate that the callbacks are running in parallel. Maybe you have another example?

nebulant
  • 143
  • 1
  • 1
  • 9
  • Did you already checked the return value of `boost::thread::hardware_concurrency()` ? – Fruchtzwerg Jan 29 '18 at 18:30
  • `boost::thread::hardware_concurrency()` is returning 8 but even if I pass 0 to the constructor, and that would mean to the spinner create a thread for each core, I get the same result. – nebulant Jan 30 '18 at 14:41

1 Answers1

14

Short answer:

ROS callbacks are threadsafe by default. This means a registered callback can only be processed by one thread and concurrent calls are disabled. A second thread is not able to access the same callback at the same time.

If you register a second callback, you will see the spinner working like expected and multiple threads are calling your callbacks at the same time.

ros::Subscriber sub1 = nh.subscribe("chatter", 1000, chatterCallback);
ros::Subscriber sub2 = nh.subscribe("chatter", 1000, chatterCallback);

Extended answer:

An async spinner tries to call available callbacks in the callback queue as fast as the rate allows. If the callback is already in process (by an other thread) the CallResult is TryAgain. This means a new attempt will be started later on.

The implementation of this lock uses the variable allow_concurrent_callbacks_ which means this behaviour is optional.

Solution:

It is possible to allow concurrent calls by setting the correct SubscribeOptions.allow_concurrent_callbacks which is false by default. Therefore you need to define your own SubscribeOptions. Here is the code you need to subscribe and allow concurrent callback calls:

ros::SubscribeOptions ops;
ops.template init<std_msgs::String>("chatter", 1000, chatterCallback);
ops.transport_hints = ros::TransportHints();
ops.allow_concurrent_callbacks = true;
ros::Subscriber sub = nh.subscribe(ops);
Fruchtzwerg
  • 10,999
  • 12
  • 40
  • 49
  • You are completely right. This will help me out quiet a lot. Thanks for that! – nebulant Jan 31 '18 at 21:14
  • 4
    Just a note: being *thread-safe* has a slightly different meaning. A callback is only thread-safe if either it does not access shared data or it uses appropriate synchronisation mechanisms to access such data. It is true that, by default, no two threads can run the same callback concurrently, though. – afsantos May 22 '18 at 16:21
  • Is the async spinner able to call another available callback in the callback queue if the queue looks like "AABB" or is the lock applied on the callback queue? – pixelpress Dec 09 '20 at 16:23
  • 1
    Yes, the lock is applied for a specific callback. If enouht threads are available the next unlocked callback of the queue will be called. – Fruchtzwerg Dec 10 '20 at 06:58
  • And what would happen if one callback in the callback queue of a multi-threaded spinner exceeds the execution time of all other callbacks together? Can the AsyncSpinner then continue adding elements to the callback queue and start executing the new ones, while one thread is still "one step behind" or is the "next spin" blocked? – pixelpress Dec 10 '20 at 15:51
  • 1
    Should be possible to add new callbacks. – Fruchtzwerg Dec 10 '20 at 16:45
  • in the case of implementing this solution using an object method callback, how would the parameter look like? – Iberico Jun 21 '21 at 08:14
  • Make use of `std::bind`. Here is an example: https://github.com/PX4/PX4-SITL_gazebo/blob/master/src/gazebo_motor_failure_plugin.cpp#L76 – Fruchtzwerg Jun 21 '21 at 08:36