Created
May 25, 2016 17:29
-
-
Save bgromov/e6f5eb142346b3c88e9f96bce17eee92 to your computer and use it in GitHub Desktop.
Demonstrates the use of AsyncSpinner and custom callback queue in ROS. Uses custom queue for enable/disable topic and global for heartbeats.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#include <ros/ros.h> | |
#include <ros/spinner.h> | |
#include <ros/callback_queue.h> | |
#include <std_msgs/Empty.h> | |
#include <std_msgs/Bool.h> | |
boost::shared_ptr<ros::AsyncSpinner> g_spinner; | |
bool g_enable = false; | |
bool g_trigger = false; | |
// called from global callback queue | |
void enableCb(const std_msgs::BoolConstPtr& msg) | |
{ | |
if (g_enable != msg->data) | |
{ | |
g_enable = msg->data; | |
g_trigger = true; | |
} | |
} | |
// called from custom callback queue | |
void heartbeatCb(const std_msgs::EmptyConstPtr& msg) | |
{ | |
ROS_INFO("Heartbeat"); | |
} | |
int main(int argc, char** argv) | |
{ | |
ros::init(argc, argv, "test_node"); | |
// custom callback queue | |
ros::CallbackQueue queue; | |
// This node handle uses custom queue | |
ros::NodeHandle n; | |
// Set custom callback queue | |
n.setCallbackQueue(&queue); | |
// and this one uses the global queue | |
ros::NodeHandle hb_n; | |
ros::Subscriber enable = n.subscribe<std_msgs::Bool>("enable", 10, enableCb); | |
// Note that we use different NodeHandle here | |
ros::Subscriber hb = hb_n.subscribe<std_msgs::Empty>("heartbeat", 100, heartbeatCb); | |
// Create AsyncSpinner, run it on all available cores and make it process custom callback queue | |
g_spinner.reset(new ros::AsyncSpinner(0, &queue)); | |
g_enable = true; | |
g_trigger = true; | |
// Loop with 100 Hz rate | |
ros::Rate loop_rate(100); | |
while (ros::ok()) | |
{ | |
// Enable state changed | |
if (g_trigger) | |
{ | |
if (g_enable) | |
{ | |
// Clear old callbacks from the queue | |
ros::getGlobalCallbackQueue()->clear(); | |
// Start the spinner | |
g_spinner->start(); | |
ROS_INFO("Spinner enabled"); | |
} | |
else | |
{ | |
// Stop the spinner | |
g_spinner->stop(); | |
ROS_INFO("Spinner disabled"); | |
} | |
// Reset trigger | |
g_trigger = false; | |
} | |
// Process messages on custom callback queue the same way ros::spinOnce() does | |
queue.callAvailable(ros::WallDuration()); | |
loop_rate.sleep(); | |
} | |
// Release AsyncSpinner object | |
g_spinner.reset(); | |
// Wait for ROS threads to terminate | |
ros::waitForShutdown(); | |
} |
I have observed that the "heartbeatCb" was not got called.
This is true, because hb_n is listening on the global callback queue. Callbacks there are processed through ros::spinOnce()
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Hello Boris,
Thanks for your example.
I am trying to understand the ros::CallbackQueue. I tried to run your example as a ros node.
I have observed that the "heartbeatCb" was not got called.
Also, I have observed the queue is empty. The main thread is getting struck at the sleep().
Could you please spare some time and explain me how can I proceed to call the heartbeatCb at a specified frequency.
Thanks in advance
Murali