From bfb803831b8a1f25a0ae2d6f18332209ed5b024a Mon Sep 17 00:00:00 2001 From: Adel Fakih Date: Mon, 11 Jan 2016 15:39:02 -0500 Subject: [PATCH] Solve a bug that causes a deadlock in MessageFilter The deadlock happens when the following two things happen at the same instant: * MessageFilter trying to erase a message from the queue, locks the messages_mutex_ then calls BufferCore::cancelTransformableRequest where it needs the transformable_requests_mutex_ * BufferCore upon receiving a TF callback, locks the transformable_requests_mutex_ in testTransformableRequests and goes through the list of requests where one of the callback it calls is MessageFilter::Transformable that attempts to acquire a unique_lock on message_mutex_ --- tf2/src/buffer_core.cpp | 21 ++++++++++++++++++--- tf2_ros/include/tf2_ros/message_filter.h | 13 ++----------- 2 files changed, 20 insertions(+), 14 deletions(-) diff --git a/tf2/src/buffer_core.cpp b/tf2/src/buffer_core.cpp index ef9b5c3cc..f75d981d5 100644 --- a/tf2/src/buffer_core.cpp +++ b/tf2/src/buffer_core.cpp @@ -37,6 +37,7 @@ #include #include #include "tf2/LinearMath/Transform.h" +#include namespace tf2 { @@ -1312,6 +1313,11 @@ void BufferCore::testTransformableRequests() { boost::mutex::scoped_lock lock(transformable_requests_mutex_); V_TransformableRequest::iterator it = transformable_requests_.begin(); + + typedef boost::tuple TransformableTuple; + std::vector transformables; + for (; it != transformable_requests_.end();) { TransformableRequest& req = *it; @@ -1351,8 +1357,12 @@ void BufferCore::testTransformableRequests() M_TransformableCallback::iterator it = transformable_callbacks_.find(req.cb_handle); if (it != transformable_callbacks_.end()) { - const TransformableCallback& cb = it->second; - cb(req.request_handle, lookupFrameString(req.target_id), lookupFrameString(req.source_id), req.time, result); + transformables.push_back(boost::make_tuple(boost::ref(it->second), + req.request_handle, + lookupFrameString(req.target_id), + lookupFrameString(req.source_id), + boost::ref(req.time), + boost::ref(result))); } } @@ -1369,9 +1379,14 @@ void BufferCore::testTransformableRequests() } } - // unlock before allowing possible user callbacks to avoid potential detadlock (#91) + // unlock before allowing possible user callbacks to avoid potential deadlock (#91) lock.unlock(); + BOOST_FOREACH (TransformableTuple tt, transformables) + { + tt.get<0>()(tt.get<1>(), tt.get<2>(), tt.get<3>(), tt.get<4>(), tt.get<5>()); + } + // Backwards compatability callback for tf _transforms_changed_(); } diff --git a/tf2_ros/include/tf2_ros/message_filter.h b/tf2_ros/include/tf2_ros/message_filter.h index 8f900e900..4009bb0c4 100644 --- a/tf2_ros/include/tf2_ros/message_filter.h +++ b/tf2_ros/include/tf2_ros/message_filter.h @@ -367,12 +367,10 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi } else { + boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_); // If this message is about to push us past our queue size, erase the oldest message if (queue_size_ != 0 && message_count_ + 1 > queue_size_) { - // While we're using the reference keep a shared lock on the messages. - boost::shared_lock< boost::shared_mutex > shared_lock(messages_mutex_); - ++dropped_message_count_; const MessageInfo& front = messages_.front(); TF2_ROS_MESSAGEFILTER_DEBUG("Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)", message_count_, @@ -380,26 +378,19 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi V_TransformableRequestHandle::const_iterator it = front.handles.begin(); V_TransformableRequestHandle::const_iterator end = front.handles.end(); + for (; it != end; ++it) { bc_.cancelTransformableRequest(*it); } messageDropped(front.event, filter_failure_reasons::Unknown); - // Unlock the shared lock and get a unique lock. Upgradeable lock is used in transformable. - // There can only be one upgrade lock. It's important the cancelTransformableRequest not deadlock with transformable. - // They both require the transformable_requests_mutex_ in BufferCore. - shared_lock.unlock(); - // There is a very slight race condition if an older message arrives in this gap. - boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_); messages_.pop_front(); --message_count_; } // Add the message to our list info.event = evt; - // Lock access to the messages_ before modifying them. - boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_); messages_.push_back(info); ++message_count_; }