#include "ros/ros.h"
#include "ros/callback_queue.h"
#include "std_msgs/String.h"
#include <boost/thread.hpp>
Go to the source code of this file.
Functions | |
void | callbackThread () |
void | chatterCallbackCustomQueue (const std_msgs::String::ConstPtr &msg) |
void | chatterCallbackMainQueue (const std_msgs::String::ConstPtr &msg) |
int | main (int argc, char **argv) |
Variables | |
ros::CallbackQueue | g_queue |
void callbackThread | ( | ) |
Definition at line 59 of file custom_callback_processing.cpp.
void chatterCallbackCustomQueue | ( | const std_msgs::String::ConstPtr & | msg | ) |
This callback gets called from the custom queue
Definition at line 50 of file custom_callback_processing.cpp.
void chatterCallbackMainQueue | ( | const std_msgs::String::ConstPtr & | msg | ) |
This tutorial demonstrates the use of custom separate callback queues that can be processed independently, whether in different threads or just at different times. This callback gets called from the main queue processed in spin()
Definition at line 42 of file custom_callback_processing.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
The SubscribeOptions structure lets you specify a custom queue to use for a specific subscription. You can also set a default queue on a NodeHandle using the NodeHandle::setCallbackQueue() function.
AdvertiseOptions and AdvertiseServiceOptions offer similar functionality.
Now we subscribe using the normal method, to demonstrate the difference.
Start a thread to service the custom queue
Now do a custom spin, to demonstrate the difference.
Definition at line 70 of file custom_callback_processing.cpp.
The custom queue used for one of the subscription callbacks
Definition at line 58 of file custom_callback_processing.cpp.