Subscriber Counter Throttle
Keep a counter in the callback that returns without doing anything unless counter % 50 == 0
- but there is a deserialization performance hit involved there
Standard Throttle
The topic_tools throttle should not have the deserialization penalty depending on how ShapeShifter works.
Nodelet Throttle
A nodelet version of throttle would be nice to eliminate additional copies between throttle and your subscriber- and it turns out it already exists: http://wiki.ros.org/nodelet_topic_tools (is there any reason why there should be a non-nodelet version of throttle that isn't just a wrapper around the nodelet?). You would have to make your subscriber a nodelet and put it into the same nodelet manager as the throttle. Copying 50 messages a second is not a big proportion of the cpu being compared to the resources required for handling the other 950 messages, so maybe the nodelet isn't worth the trouble.
Additionally, in looking at the code for this nodelet throttle it appears to be using a template system rather than the generic ShapeShifter message that the regular throttle uses, which means it is deseerializing and reserializing everything, making it slower than regular throttle as the test result below shows.
The template system also requires you to create your own nodelet that instantiates the type you want to throttle, which is non-trivial, but there is an Image example and I've made an imu nodelet throttle.
Queue Throttling
A different and hacky approach is to keep track of time since the last processed subscribed message in your callback, and do a blocking sleep with the remaining 1/50th of a second while also having a subscriber queue_size of 1.
If the queue is full and a new message
arrives, the oldest message will be
thrown out. Additionally, the message
is not actually deserialized until the
first callback which needs it is about
to be called.
http://wiki.ros.org/roscpp/Overview/P...
Test Results
- A python node publishing Imu at 1000 Hz takes about 14% cpu.
- regular throttle takes about 7% cpu
- nodelet throttle (in a wrapper) takes 10% cpu
- Queue overflow method with rospy node takes 2% cpu, though the queue isn't getting updated properly.
- Queue overflow with cpp node takes 5% cpu and timing seems solid
- The python node subscribing to Imu (and doing nothing with it) at the throttled 50 hz is negligible.
- Python imu subscriber without throttling takes 8% cpu
- C++ imu subscriber without throttling takes 7% cpu
One unexpected result is that a python subscriber plus regular throttle doesn't run any faster than a python or C++ node subscribing to the full rate Imu topic.
The rospy queue throttling node got increasingly behind with the messages it was receiving, while the C++ version worked fine and so far is the best solution for the most efficient throttle.
All the code is on https://github.com/lucasw/topic_throttle