My question is that is the callback thread-safe? For multiple callbacks that may access and potentially modify shared data, is adding mutex locks a good practice?
I am testing the behavior of running two threads with two callback functions that access and modify shared data.
I have found a similar post here, but in my simple experiments, I am expecting something such as race condition happening, but it did not happen.
I wrote a publisher node which can publish two String
messages in two threads and each message will be pubished for one second with different frequency.
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <std_msgs/String.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "AB_topic_pub");
ros::NodeHandle nh;
ros::Publisher pub_a = nh.advertise<std_msgs::String>("msg_a", 200);
ros::Publisher pub_b = nh.advertise<std_msgs::String>("msg_b", 200);
int COUNT_A = 0, COUNT_B = 0;
ros::Duration(2.0).sleep();
boost::thread pub_thread_a(
[&]()
{
ROS_INFO("Publishing A for one second.");
ros::Time start_time = ros::Time::now();
ros::Rate freq(1000);
while (ros::Time::now() - start_time < ros::Duration(1.0)) {
std_msgs::String MSG_A;
MSG_A.data = "A" + std::to_string(COUNT_A);
pub_a.publish(MSG_A);
freq.sleep();
COUNT_A++;
}
}
);
boost::thread pub_thread_b(
[&]()
{
ROS_INFO("Publishing B for one second.");
ros::Time start_time = ros::Time::now();
ros::Rate freq(200);
while (ros::Time::now() - start_time < ros::Duration(1.0)) {
std_msgs::String MSG_B;
MSG_B.data = "B" + std::to_string(COUNT_B);
pub_b.publish(MSG_B);
freq.sleep();
COUNT_B++;
}
}
);
pub_thread_a.join();
pub_thread_b.join();
std::cout << "A COUNT: " << COUNT_A << std::endl;
std::cout << "B COUNT: " << COUNT_B << std::endl;
}
I wrote a subscriber node with two callback queues. In the following code, I want to count the how many times the callbacks are called in total. I defined two variables COUNT_WO_LOCK
without mutex guarding and COUNT_W_LOCK
with a mutex guarding.
#include <iostream>
#include <boost/function.hpp>
#include <boost/atomic/atomic.hpp>
#include <boost/thread.hpp>
#include <ros/callback_queue.h>
#include <ros/ros.h>
#include <std_msgs/String.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "callback_lock_test");
ros::NodeHandle nh_a;
ros::NodeHandle nh_b;
ros::CallbackQueue cq_a, cq_b;
nh_a.setCallbackQueue(&cq_a);
nh_b.setCallbackQueue(&cq_b);
int COUNT_WO_LOCK;
COUNT_WO_LOCK = 0;
int COUNT_W_LOCK;
COUNT_W_LOCK = 0;
boost::mutex LOCK;
boost::function<void(const std_msgs::String::ConstPtr &msg)> cb_a =
[&](const std_msgs::StringConstPtr &msg)
{
LOCK.lock();
COUNT_W_LOCK++;
LOCK.unlock();
COUNT_WO_LOCK++;
ROS_INFO("[Thread ID: %s] I am A, heard: [%s]", boost::lexical_cast<std::string>(boost::this_thread::get_id()).c_str() , msg->data.c_str());
};
boost::function<void(const std_msgs::String::ConstPtr &msg)> cb_b =
[&](const std_msgs::StringConstPtr &msg)
{
LOCK.lock();
COUNT_W_LOCK++;
LOCK.unlock();
COUNT_WO_LOCK++;
ROS_WARN("\t\t[Thread ID: %s] I am B, heard: [%s]", boost::lexical_cast<std::string>(boost::this_thread::get_id()).c_str() , msg->data.c_str());
};
// A pub for one second at 1000Hz
ros::Subscriber sub_a = nh_a.subscribe<std_msgs::String>("msg_a", 200,
cb_a, ros::VoidConstPtr(), ros::TransportHints().tcpNoDelay(true));
// B pub for one second at 200Hz
ros::Subscriber sub_b = nh_b.subscribe<std_msgs::String>("msg_b", 200,
cb_b, ros::VoidConstPtr(), ros::TransportHints().tcpNoDelay(true));
boost::thread spin_thread_a(
[&]()
{
ROS_ERROR("\t\t\t\t\t [Spinner Thead ID: %s]", boost::lexical_cast<std::string>(boost::this_thread::get_id()).c_str());
while (!sub_a.getNumPublishers()) { }
while (ros::ok())
cq_a.callAvailable(ros::WallDuration());
}
);
boost::thread spin_thread_b(
[&]()
{
ROS_ERROR("\t\t\t\t\t [Spinner Thead ID: %s]", boost::lexical_cast<std::string>(boost::this_thread::get_id()).c_str());
while (!sub_b.getNumPublishers()) { }
while (ros::ok())
cq_b.callAvailable(ros::WallDuration());
}
);
spin_thread_a.join();
spin_thread_b.join();
if (ros::isShuttingDown()) {
std::cout << "LOCKED COUNT: " << COUNT_W_LOCK << std::endl;
std::cout << "UNLOCKED COUNT: " << COUNT_WO_LOCK << std::endl;
}
}
I first launched the subscriber node and then launched the publisher node. I am expecting that COUNT_W_LOCK
is 1200
and COUNT_WO_LOCK
is <1200
, but in fact they are all 1200
.