Skip to content

Commit

Permalink
Add locking and test happy-path exit conditions.
Browse files Browse the repository at this point in the history
  • Loading branch information
mjcarroll committed Mar 28, 2018
1 parent c94c152 commit 73c408b
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 13 deletions.
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,6 +352,8 @@ class Executor
RCLCPP_DISABLE_COPY(Executor)

std::vector<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr> weak_nodes_;

std::mutex taken_timers_mutex_;
std::set<rclcpp::TimerBase::SharedPtr> taken_timers_;
};

Expand Down
6 changes: 5 additions & 1 deletion rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -251,6 +251,8 @@ Executor::execute_any_executable(AnyExecutable::SharedPtr any_exec)
}
if (any_exec->timer) {
execute_timer(any_exec->timer);

std::lock_guard<std::mutex> lock(taken_timers_mutex_);
auto it = taken_timers_.find(any_exec->timer);
if (it != taken_timers_.end()) {
taken_timers_.erase(it);
Expand Down Expand Up @@ -525,9 +527,11 @@ Executor::get_next_timer(AnyExecutable::SharedPtr any_exec)
continue;
}
for (auto & timer_ref : group->get_timer_ptrs()) {
std::lock_guard<std::mutex> lock(taken_timers_mutex_);
auto timer = timer_ref.lock();

if (timer && timer->is_ready() && taken_timers_.count(timer) == 0) {
bool is_not_scheduled = (taken_timers_.count(timer) == 0);
if (timer && timer->is_ready() && is_not_scheduled) {
any_exec->timer = timer;
any_exec->callback_group = group;
node = get_node_by_group(group);
Expand Down
31 changes: 19 additions & 12 deletions rclcpp/test/executors/test_multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using namespace std::chrono_literals;

using rcl_interfaces::msg::IntraProcessMessage;

class TestMultiThreadedExecutor : public::testing::Test
class TestMultiThreadedExecutor : public ::testing::Test
{
protected:
static void SetUpTestCase()
Expand Down Expand Up @@ -64,21 +64,28 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) {
std::mutex last_mutex;
auto last = system_clock.now();

auto timer_callback = [&executor, &system_clock, &last_mutex, &last]() {
rclcpp::Time now = system_clock.now();
std::atomic_int timer_count {0};

{
std::lock_guard<std::mutex> lock(last_mutex);
double diff = labs((now - last).nanoseconds()) / 1.0e9;
last = now;
auto timer_callback = [&timer_count, &executor, &system_clock, &last_mutex, &last]() {
rclcpp::Time now = system_clock.now();
timer_count++;

if (diff < 0.09 || diff > 0.11) {
if (timer_count > 20) {
executor.cancel();
ASSERT_TRUE(diff > 0.09);
ASSERT_TRUE(diff < 0.11);
}
}
};

{
std::lock_guard<std::mutex> lock(last_mutex);
double diff = labs((now - last).nanoseconds()) / 1.0e9;
last = now;

if (diff < 0.09 || diff > 0.11) {
executor.cancel();
ASSERT_TRUE(diff > 0.09);
ASSERT_TRUE(diff < 0.11);
}
}
};

auto timer = node->create_wall_timer(100ms, timer_callback, cbg);
executor.add_node(node);
Expand Down

0 comments on commit 73c408b

Please sign in to comment.