#include <ros/ros.h>
#include <ros/callback_queue.h>
#include <ros/callback_queue_interface.h>
#include <std_msgs/Empty.h>
void callback_1(const std_msgs::EmptyConstPtr& _msg)
{
ROS_INFO(“Called callback_1\n”);
}
void callback_2(const std_msgs::EmptyConstPtr& _msg)
{
ROS_INFO(“Called callback_2\n”);
}
int main(int argn, char* args[])
{
ros::init(argn, args, “callback_q_subscriber”);
ros::NodeHandle nh_1;
ros::NodeHandle nh_2;
ros::CallbackQueue queue_1, queue_2;
nh_1.setCallbackQueue(&queue_1);
nh_2.setCallbackQueue(&queue_2);
ros::Subscriber s_1 = nh_1.subscribe("/topic_1", 1, callback_1);
ros::Subscriber s_2 = nh_2.subscribe("/topic_2", 1, callback_2);
pthread_t id_1, id_2;
int i = 20;
while(i--)
{
queue_1.callOne(ros::WallDuration(1.0)); // can also be callAvailable()
}
i = 20;
while(i--)
{
queue_2.callOne(ros::WallDuration(1.0)); // can also be callAvailable()
}
ROS_INFO("Hurray!");
return 0;
}