ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
26

ROS callbacks, threads and spinning

asked 2013-01-22 06:33:33 -0500

Victor_ocv2 gravatar image

updated 2013-03-19 23:34:52 -0500

Hello, I have read some tutorials (such as http://www.ros.org/wiki/roscpp/Overview/Callbacks%20and%20Spinning) but I still have some doubts about ROS and callbacks:

Let's say that:

  • in my program I have several threads: A, B and C
  • each thread A,B and C subcribes to a different topic and has declares its own ros::NodeHandle and ros::subscriber
  • each thread has its own main loop where ros::spinOnce() is called and some other stuff is done, such as control loop with ros::Rate loop_rate(Hz)

My questions are:

  1. when ros::spinOnce() is called in each thread, which callbacks are executed?
  2. is there a problem with this configuration? if so, how should it be done?

The reason why I have several threads is for parallel execution of some stuff related to the callbacks, but also to have different control loop speeds: i.e. one thread will run at 10hz while other one will run at 30hz.

Thanks for your time!

EDIT: detail explanation on my case:

thread A: subscribes to laser, callback gets data from laser, thread process the data to detect legs

thread B: subscribes to kinect, callback gets data from kinect, thread process the data to detect humans

thread C: subscribes to a path-publisher (own work), callback gets points, thread computes a route and publish cmd_vel

etc...

edit retag flag offensive close merge delete

Comments

2

This seems like a complicated use case, and I want to be sure you don't have an XY problem. Can you describe what you're trying to accomplish (the problem itself, that is) in more detail?

Mac gravatar image Mac  ( 2013-01-22 06:48:26 -0500 )edit

Detailled information published, thanks for your time!

Victor_ocv2 gravatar image Victor_ocv2  ( 2013-01-22 06:54:05 -0500 )edit
4

Cool, thanks for the update. How interdependent are A, B, and C here? If the coupling is fairly loose, this looks to me like three nodes, not three threads. If it's fairly tight, that's a different story.

Mac gravatar image Mac  ( 2013-01-22 07:48:37 -0500 )edit
1

If you are just worried about message copying overhead, another option is to user nodelets, see: http://ros.org/wiki/nodelet

joq gravatar image joq  ( 2013-01-22 11:42:17 -0500 )edit

Each thread writes its results in shared memory. These results are read by the main process, which is the robot's state machine

Victor_ocv2 gravatar image Victor_ocv2  ( 2013-01-22 22:13:46 -0500 )edit

I have read about nodelets in the past, but as I understand it requires the creation of several nodes first (extra work). Moreover, as I understand they are indicated for high throughput nodes that need to communicate, which I do not think it is my case (depends on what is high throughput)

Victor_ocv2 gravatar image Victor_ocv2  ( 2013-01-22 22:17:53 -0500 )edit

3 Answers

Sort by » oldest newest most voted
79

answered 2013-01-22 12:44:23 -0500

Thomas gravatar image

updated 2013-09-30 15:24:36 -0500

Briefly: It won't work as you expect and you probably do not need such a complex way of designing your node.

The theory

When it comes to communication in roscpp, two kind of objects are handling callbacks:

A spinner is an object that has the ability to call the callbacks contained in a callback queue. A callback queue is the object in which each subscriber will add an element each time a message is received by resolving which kind of message should call which callbacks (and with which arguments).

Regarding the spinners, there is currently three implementations available in roscpp:

  • Single thread spinner: the default one, takes the messages contained in a callback queue and process the callbacks one by one while blocking the execution of the thread that called it.
  • Multi-threaded spinner: spawns a couple of threads (configurable) that will execute callbacks in parallel when messages are received but blocks the execution of the thread that called it.
  • 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.

These objects may be instantiated manually in advanced ROS nodes but to avoid verbose initialization, an alternative, object-less, API is provided through functions in the ROS namespace. Aka ros::spin(), ros::spinOnce() and so on. This API rely on a default callback queue implemented as a singleton which is accessible through the ros::getGlobalCallbackQueue() function.

So basically when you call the ros::spinOnce() function, a single-thread spinner is created and its spin method is called once using the default callback queue (see init.cpp from roscpp).

And to finish, when you create a Subscriber, you pass it a NodeHandle and each NodeHandle has an associated callbackqueue that default to the global one but which can be overridden using the getCallbackQueue/setCallbackQueue methods.

Your case

If you take a look at spinner.cpp you will see there is a mutex that make the SingleThreader thread-safe while discouraging you to use it in this case (line 48).

Conclusion: what you do is safe but will trigger regularly ROS error messages as there is chances that several instances of ros::SpinOnce will be executed in parallel.

Proposed solution

Considering your applications, I think your callbacks are just not written as they should. A callback should stay as simple and fast as possible. In most of the cases, a callback is just feeding ROS data to your own classes which is usually as simple as copying data (and maybe converting them). It will help you ensuring that your callbacks are thread-safe (if you want to convert your node to a nodelet for instance, one day) and avoid making "ros::Spin" blocking for a long time, even in the case you are using the single-threaded spinner.

Typically, if you want to do time-consuming computations such as "leg detection", the callbacks are definitively ... (more)

edit flag offensive delete link more

Comments

Exactly the answer I was looking for. Just for the record I did not to get any ros error msgs (spinner.cpp line 48) about what I was doing, therefore It was unclear for me to notice if I was doing something strange or not. Moreover, I thank you for this clear explanation on ros callbacks and spins

Victor_ocv2 gravatar image Victor_ocv2  ( 2013-01-22 23:21:26 -0500 )edit

+1 for the clear and interesting answer. I am facing a similar problem. I don't get the "main thread" part. should it be while(ros::ok()) { leg_detector.process(latest_scan); ros::spinOnce(); } ? I think there should be at least 2 threads: one for the callbacks and one for the heavy work...

brice rebsamen gravatar image brice rebsamen  ( 2013-04-02 10:22:21 -0500 )edit
1

Yes, this is what I suggest. The question is: what benefit will you have if create two threads? Your leg detector is anyway too slow to process all the data. 99% of the cases you are just fine letting them being thrown away.

Thomas gravatar image Thomas  ( 2013-04-02 18:23:35 -0500 )edit
3

This is an excellent answer! It is even clearer than the tutorials in some places. Brilliant! Thank you!

McMurdo gravatar image McMurdo  ( 2014-01-07 23:26:15 -0500 )edit

I have similar situation. I want subscribe scan data and image_rect data from xtion. so I already use message_fillters. but it seem not working. I think is that sync problem maybe. I ask here.

haryngod gravatar image haryngod  ( 2015-12-29 03:25:31 -0500 )edit

Work perfectly here! thank you!

José Diôgo gravatar image José Diôgo  ( 2016-11-30 07:12:47 -0500 )edit
2

How can we add this to the Callbacks and Spinning wiki page? This would be very helpful to have and would clear up unnecessary confusion when visiting that page for the first time.

doncat gravatar image doncat  ( 2018-05-31 18:33:59 -0500 )edit

I don't see the advantage of calling the time-consuming computation in the same main thread. Every callback is blocked anyway, since ros::spin() is not executed. Or am I misunderstanding something?

prex gravatar image prex  ( 2020-12-08 07:25:40 -0500 )edit
0

answered 2020-08-06 13:33:41 -0500

cascais gravatar image

"ROS Spinning, Threading, Queuing Effective use of multi spinner threads, different queues in ROS" https://levelup.gitconnected.com/ros-...

edit flag offensive delete link more
0

answered 2013-01-22 12:16:02 -0500

Claudio gravatar image

I'd suggest you change topology.

Why not having a single thread manage all the ROS messaging and then dispatching relevant information to the relevant processing thread?

As to say:

  • Thread A: ros spin, subscribing, callbacks, dispatcher
  • Thread B: laser, gets data from relevant dispatcher in thread A
  • Thread C: kinect, gets data from relevant dispatcher in thread A
  • Thread D: motion planner, gets data from all of the above and publishes cmd_vel

You should already be faced with the problem of how to pass data from your actual threads A and B to C (motion planner needs to know about legs and humans from A and B right?), so adding to this doesn't really over-complicate it.

I suggest you have a look at the ZeroMQ messaging library. It will allow you to easily shuffle messages back and forth from your threads, and make the program a little easier to both code and maintain.

edit flag offensive delete link more

Question Tools

10 followers

Stats

Asked: 2013-01-22 06:33:33 -0500

Seen: 45,923 times

Last updated: Aug 06 '20