ROS Resources: Documentation | Support | Discussion Forum | Service Status | Q&A answers.ros.org
Ask Your Question
34

Significance of ros::spinOnce()

asked 2011-11-10 03:44:55 -0600

karthik gravatar image

updated 2011-11-10 08:42:33 -0600

mmwise gravatar image

Hi, Can somebody explain what is the actual significance of the ros::spinOnce(). How is it useful? What are the situations where its impact is higher? And also difference between ros::spin() ros::spinOnce().

Thanks, Karthik

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
77

answered 2011-11-10 07:28:34 -0600

Patrick Mihelich gravatar image

The roscpp overview has some background info on callbacks and spinning.

In the background, ROS monitors socket connections for any topics you've subscribed to. When a message arrives, ROS pushes your subscriber callback onto a queue. It does not call it immediately. ROS only processes your callbacks when you tell it to with ros::spinOnce().

This is all part of roscpp's "toolbox, not framework" philosophy. roscpp does not mandate a particular threading model for your node, nor does it demand to wrap your main(). ros::spin() is purely a convenience, a main loop for ROS that repeatedly calls ros::spinOnce() until your node is shut down.

There are a few cases when calling ros::spinOnce() directly is useful.

Processing callbacks at a specific time interval

In rare situations you might want to process ROS callbacks only at certain intervals. Make sure to consider your subscriber queues when doing this. If messages arrive at 100Hz, you call ros::spinOnce() every 5Hz, and your subscriber has a queue_size of 1, you'll drop 95/100 messages! That may or may not be what you want.

Usually a Timer is a better way to inject periodic processing.

Perform processing unsuitable for a ROS callback

Perhaps you are using another library that needs to do its own asynchronous event processing. In that case you need to include its analogue to ros::spinOnce() in your main loop:

ros::Rate r(100);
while (ros::ok())
{
  libusb_handle_events_timeout(...); // Handle USB events
  ros::spinOnce();                   // Handle ROS events
  r.sleep();
}

Integrating ROS with framework X

Many frameworks for GUIs, game programming, etc. do wrap your main(). In that case you just have to play by their rules and find a suitable place to drop in ros::spinOnce().

For example, say you're writing a visualizer using OpenGL and GLUT. One way to integrate ROS would be to tell GLUT to call ros::spinOnce() from its main loop every 10ms:

void timerCb(int value) { ros::spinOnce(); }

glutTimerFunc(10, timerCb, 0);
glutMainLoop(); // Never returns
edit flag offensive delete link more

Comments

1

Is there any use then for a ros::spin() or ros::spinOnce() in the main function of a node that has no callbacks?

2ROS0 gravatar image2ROS0 ( 2016-07-19 13:22:44 -0600 )edit
21

answered 2011-11-10 04:53:51 -0600

DimitriProsser gravatar image

ros::spin() will not return until the node has been shut down. Thus, you have no control over your program while ROS is spinning. The advantage of ros::spinOnce() is that it will check for callbacks/service calls/etc only as often as you call it. Why is this useful? Being able to control the rate at which ROS updates allows you to do certain calculations at a certain frequency.

If, for example, you have an accelerometer that samples at 100Hz. At each update of the accelerometer, it registers a callback in your program. That means that your program is processing the accelerometer data 100 times per second. Let's say you want to read that data and save it to a file five times per second (5Hz). If you're using ros::spin(), your program will only process the callback functions at 100Hz. If you use ros::spinOnce(), you can interject your own code at your desired frequency:

int main()
{
  ros::Rate loop_rate(5); // 5Hz

  while (ros::ok())
  {
    Myclass.saveDataToFile();
    loop_rate.sleep();
    ros::spinOnce();
  }
}

This allows you to execute your own code in between ROS's callback handling.

edit flag offensive delete link more

Comments

Thanks DimitriProsser. I partially understand what you explained. Can you tell me what happens if we remove ros::spinOnce() in the above code (having rest the same).
karthik gravatar imagekarthik ( 2011-11-10 05:22:50 -0600 )edit
2
I believe the program will run without checking callbacks/services when spinOnce is removed. When spin is placed instead, the checks will happen at the pace of callback handling. When spinOnce is there then the pace is fixed by user to be 5hz. Let me know if my understanding is correct. Thanks alot.
karthik gravatar imagekarthik ( 2011-11-10 05:25:50 -0600 )edit

Without spinOnce() function, you get nothing from ROS (no messages, no services, etc).

Mike Gao gravatar imageMike Gao ( 2014-11-06 12:13:13 -0600 )edit
1

@DimitriProsser let's say that at the first 1 second, it samples 100 data : data 1, 2 ,3, ...100. Then They put it on queue. We spin at 5Hz, which means it only calls back 5 times during 1 second. But which data it got at the call backs isn't it data 1,2,3,4,5 since we call from the queue?pls explai

alienmon gravatar imagealienmon ( 2016-08-12 03:11:42 -0600 )edit

Your Answer

Please start posting anonymously - your entry will be published after you log in or create a new account.

Add Answer

Question Tools

11 followers

Stats

Asked: 2011-11-10 03:44:55 -0600

Seen: 37,867 times

Last updated: Nov 10 '11