Skip to content

Commit

Permalink
fix publishing latched message many times leads to crash bug
Browse files Browse the repository at this point in the history
  • Loading branch information
fengjingchao-cn authored and ycool committed Dec 22, 2017
1 parent 039a5c0 commit 33cb2e6
Showing 1 changed file with 11 additions and 8 deletions.
19 changes: 11 additions & 8 deletions ros/ros_comm/roscpp/src/libros/subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -680,16 +680,19 @@ uint32_t Subscription::handleMessage(const SerializedMessage& m, bool ser, bool
}
}

for (V_PublisherLink::iterator it = publisher_links_.begin(); it != publisher_links_.end(); ++it)
{
if ((*it)->isLatched())
boost::mutex::scoped_lock lock(publisher_links_mutex_);
for (V_PublisherLink::iterator it = publisher_links_.begin(); it != publisher_links_.end(); ++it)
{
LatchInfo li;
li.connection_header = connection_header;
li.link = (*it);
li.message = m;
li.receipt_time = receipt_time;
latched_messages_[(*it)] = li;
if ((*it)->isLatched())
{
LatchInfo li;
li.connection_header = connection_header;
li.link = (*it);
li.message = m;
li.receipt_time = receipt_time;
latched_messages_[(*it)] = li;
}
}
}

Expand Down

0 comments on commit 33cb2e6

Please sign in to comment.