roscpp Callback Thread Safety SEGFAULT
I'm currently subscribing to every topic ever published in my program via ShapeShifter
, and deserializing as necessary. This works great, but I'm receiving SEGFAULTs when using ros::AsyncSpinner
. I'm essentially trying to create a live rqt_graph, which monitors latency between sent and received messages.
Why is the below not threadsafe? From my console, it looks like the shared::ptr to Shapeshifter
msg within my callback get changed on me without me finishing the callback. Is it not safe to pass shared::ptr to ROS callback threads?
ERROR MESSAGE
Program received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffea7fc700 (LWP 31281)]
__memcpy_sse2_unaligned () at ../sysdeps/x86_64/multiarch/memcpy-sse2-unaligned.S:79
79 ../sysdeps/x86_64/multiarch/memcpy-sse2-unaligned.S: No such file or directory.
MAIN
int main(int argc, char* argv[])
{
ros::init(argc, argv, "performance_tracker_node");
ros::AsyncSpinner spinner(4);
spinner.start();
// Loop on the main thread and search for new topics being published
// If the topic caught doesn't exist in our Node list yet, add it
while(ros::ok()){
//Code that finds new topics not included
PerformanceTracker newNode = PerformanceTracker(info.name);
performanceNodes.insert(std::pair<std::string, PerformanceTracker>(info.name, newNode));
}
ros::waitForShutdown;
}
Performance Tracker Constructor
PerformanceTracker::PerformanceTracker(std::string topicName):
_topicName(topicName)
{
ros::NodeHandle nh("~");
_nh = nh;
// Subscribe To Generic Message
_sub = _nh.subscribe( _topicName, 10, &PerformanceTracker::topicCallback, this);
}
Performance Tracker Callback
void PerformanceTracker::topicCallback(const boost::shared_ptr<topic_tools::ShapeShifter> msg){
//Current Time
ros::Time begin = ros::Time::now();
//Prevent OOB error by only checking msgs that are at least the size of a header msg
if(msg->size() >= sizeof(std_msgs::Header)){
//Deserialize message
std_msgs::Header header;
uint8_t buf[msg->size()];
ros::serialization::OStream stream(buf, msg->size());
msg->write(stream);
header.seq = ((uint32_t *)buf)[0];
header.stamp.sec = ((int32_t *)buf)[1];
header.stamp.nsec = ((int32_t *)buf)[2];
// Delays greater than 1 hour are clearly wrong., and the header doesn't exist, so skip this
double lagTime = (begin-header.stamp).toSec();
if(lagTime > 3600){
// Skip this topic in the future
std::cout << "Topic " << _topicName << " sent at " << header.stamp << " returned nonsense time for " << lagTime << " seconds" << std::endl;
_nh.shutdown();
}
//if delayed, then log time lag
else if(lagTime > 1){
std::cout << "Topic " << _topicName << " sent at " << header.stamp << " delayed for" << lagTime << " seconds" << std::endl;
}
}
// Remove topic for future if topic message type is too small
else{
// Skip this topic in the future
std::cout << "Topic " << _topicName << " message size was smaller than just a std::msg Header, and likely did not have a header "<< std::endl;
_nh.shutdown();
}
}