Skip to content

Commit

Permalink
Fix bug that connection drop signal related funtion throw a bad_weak … (
Browse files Browse the repository at this point in the history
#1940)

* Fix bug that connection drop signal related funtion throw a bad_weak exception

TransportSubscriberLink::onConnectionDropped throws a bad_weak exception
while call shared_from_this() if TransportSubscriberLink already destroyed

* Fix dead lock about call_queue_mutex_ and drop_mutex_ in two threads

Signed-off-by: Barry Xu <[email protected]>

* Remove check that is not necessary

Signed-off-by: Barry Xu <[email protected]>
  • Loading branch information
Barry-Xu-2018 authored May 15, 2020
1 parent d09becc commit 5f8d76d
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 4 deletions.
3 changes: 3 additions & 0 deletions clients/roscpp/include/ros/transport_publisher_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
#include "publisher_link.h"
#include "connection.h"

#include <boost/signals2/connection.hpp>

namespace ros
{
class Header;
Expand Down Expand Up @@ -79,6 +81,7 @@ class ROSCPP_DECL TransportPublisherLink : public PublisherLink
void onRetryTimer(const ros::SteadyTimerEvent&);

ConnectionPtr connection_;
boost::signals2::connection dropped_conn_;

int32_t retry_timer_handle_;
bool needs_retry_;
Expand Down
5 changes: 4 additions & 1 deletion clients/roscpp/src/libros/connection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -337,7 +337,10 @@ void Connection::drop(DropReason reason)

if (did_drop)
{
drop_signal_(shared_from_this(), reason);
{
boost::recursive_mutex::scoped_lock lock(drop_mutex_);
drop_signal_(shared_from_this(), reason);
}
transport_->close();
}
}
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/service_server_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,15 +340,15 @@ bool ServiceServerLink::call(const SerializedMessage& req, SerializedMessage& re

bool immediate = false;
{
boost::mutex::scoped_lock lock(call_queue_mutex_);

if (connection_->isDropped())
{
ROSCPP_LOG_DEBUG("ServiceServerLink::call called on dropped connection for service [%s]", service_name_.c_str());
info->call_finished_ = true;
return false;
}

boost::mutex::scoped_lock lock(call_queue_mutex_);

if (call_queue_.empty() && header_written_ && header_read_)
{
immediate = true;
Expand Down
3 changes: 2 additions & 1 deletion clients/roscpp/src/libros/transport_publisher_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ TransportPublisherLink::~TransportPublisherLink()
}

connection_->drop(Connection::Destructing);
connection_->removeDropListener(dropped_conn_);
}

bool TransportPublisherLink::initialize(const ConnectionPtr& connection)
Expand All @@ -82,7 +83,7 @@ bool TransportPublisherLink::initialize(const ConnectionPtr& connection)
// and disconnect when this class' reference count is decremented to 0. It increments
// then decrements the shared_from_this reference count around calls to the
// onConnectionDropped function, preventing a coredump in the middle of execution.
connection_->addDropListener(Connection::DropSignal::slot_type(&TransportPublisherLink::onConnectionDropped, this, _1, _2).track(shared_from_this()));
dropped_conn_ = connection_->addDropListener(Connection::DropSignal::slot_type(&TransportPublisherLink::onConnectionDropped, this, _1, _2).track(shared_from_this()));

if (connection_->getTransport()->requiresHeader())
{
Expand Down
1 change: 1 addition & 0 deletions clients/roscpp/src/libros/transport_subscriber_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ TransportSubscriberLink::TransportSubscriberLink()
TransportSubscriberLink::~TransportSubscriberLink()
{
drop();
connection_->removeDropListener(dropped_conn_);
}

bool TransportSubscriberLink::initialize(const ConnectionPtr& connection)
Expand Down

0 comments on commit 5f8d76d

Please sign in to comment.