Skip to content

Commit

Permalink
rollback strict error checking for backwards compatibility
Browse files Browse the repository at this point in the history
* allow spinning in any case, when current thread matches the first
  thread that started a spinner (old behavior)
* don't throw exceptions
* disabled corresponding unittests
  • Loading branch information
rhaschke committed Sep 16, 2016
1 parent a0c78a0 commit 47ed5e9
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 15 deletions.
37 changes: 26 additions & 11 deletions clients/roscpp/src/libros/spinner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,11 @@

namespace {

const std::string DEFAULT_ERROR_MESSAGE =
"\nAttempt to spin a callback queue from two spinners, one of them being single-threaded."
"\nThis will probably result in callbacks being executed out-of-order."
"\nIn future this will throw an exception!";

/** class to monitor running single-threaded spinners.
*
* Calling the callbacks of a callback queue _in order_, requires a unique SingleThreadedSpinner
Expand All @@ -55,9 +60,11 @@ struct SpinnerMonitor
*/
struct Entry
{
Entry(const boost::thread::id &tid) : tid(tid), num_multi_threaded(0) {}
Entry(const boost::thread::id &tid,
const boost::thread::id &initial_tid) : tid(tid), initial_tid(initial_tid), num_multi_threaded(0) {}

boost::thread::id tid; // thread id of single-threaded spinner
boost::thread::id initial_tid; // to retain old, but wrong behaviour
unsigned int num_multi_threaded; // number of multi-threaded spinners
};

Expand All @@ -66,17 +73,28 @@ struct SpinnerMonitor
{
boost::mutex::scoped_lock lock(mutex_);

boost::thread::id current_tid = boost::this_thread::get_id();
boost::thread::id tid;
if (single_threaded)
tid = boost::this_thread::get_id();
tid = current_tid;

std::map<ros::CallbackQueue*, Entry>::iterator it = spinning_queues_.find(queue);
bool can_spin = ( it == spinning_queues_.end() || it->second.tid == tid );

if (!can_spin)
return false;
{
// Previous behavior (up to Kinetic) was to accept multiple spinners on a queue
// as long as they were started from the same thread. Although this is wrong behavior,
// we retain it here for backwards compatibility, i.e. we allow spinning in any case
// when the initial thread id is identical to current thread id.
if (it->second.initial_tid == current_tid)
ROS_ERROR_STREAM("SpinnerMonitor: " << DEFAULT_ERROR_MESSAGE);
else
return false;
}

if (it == spinning_queues_.end())
it = spinning_queues_.insert(it, std::make_pair(queue, Entry(tid)));
it = spinning_queues_.insert(it, std::make_pair(queue, Entry(tid, current_tid)));

if (!single_threaded) // increment number of multi-threaded spinners
it->second.num_multi_threaded += 1;
Expand Down Expand Up @@ -114,9 +132,6 @@ struct SpinnerMonitor
};

SpinnerMonitor spinner_monitor;
const std::string DEFAULT_ERROR_MESSAGE =
"Attempt to spin a callback queue from two spinners, one of them being single-threaded. "
"This will probably result in callbacks being executed out-of-order.";
}

namespace ros
Expand All @@ -132,8 +147,8 @@ void SingleThreadedSpinner::spin(CallbackQueue* queue)

if (!spinner_monitor.add(queue, true))
{
ROS_FATAL_STREAM("SingleThreadedSpinner: " << DEFAULT_ERROR_MESSAGE);
throw std::runtime_error("There is already another spinner on this queue");
ROS_ERROR_STREAM("SingleThreadedSpinner: " << DEFAULT_ERROR_MESSAGE);
return;
}

ros::WallDuration timeout(0.1f);
Expand Down Expand Up @@ -222,8 +237,8 @@ void AsyncSpinnerImpl::start()

if (!spinner_monitor.add(callback_queue_, false))
{
ROS_FATAL_STREAM("AsyncSpinnerImpl: " << DEFAULT_ERROR_MESSAGE);
throw std::runtime_error("There is already a single-threaded spinner on this queue");
ROS_ERROR_STREAM("AsyncSpinnerImpl: " << DEFAULT_ERROR_MESSAGE);
return;
}

continue_ = true;
Expand Down
4 changes: 0 additions & 4 deletions test/test_roscpp/test/launch/spinners.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
<launch>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_spin" args="--gtest_filter=Spinners.spin"/>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_spinfail" args="--gtest_filter=Spinners.spinfail"/>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_singlefail" args="--gtest_filter=Spinners.singlefail"/>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_multi" args="--gtest_filter=Spinners.multi"/>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_multifail" args="--gtest_filter=Spinners.multifail"/>
<test pkg="test_roscpp" type="test_roscpp-spinners" test-name="Spinners_async" args="--gtest_filter=Spinners.async"/>
</launch>

0 comments on commit 47ed5e9

Please sign in to comment.