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