Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

executor could take more than once incorrectly #383

Merged
merged 7 commits into from
Jun 19, 2018
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,14 @@ if(BUILD_TESTING)
"rcl")
target_link_libraries(test_utilities ${PROJECT_NAME})
endif()

ament_add_gtest(test_multi_threaded_executor test/executors/test_multi_threaded_executor.cpp
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this need to be wrapped in if(UNIX) due to sched_setscheduler() in the test?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added an #ifdef around the corresponding sched_setscheduler(), because the bug originally manifested on OSX, so we wanted to test against that. That trick additionally isn't necessary on OSX because the bug shows up with the default scheduler.

APPEND_LIBRARY_DIRS "${append_library_dirs}")
if(TARGET test_multi_threaded_executor)
ament_target_dependencies(test_multi_threaded_executor
"rcl")
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
endif()
endif()

ament_package(
Expand Down
20 changes: 19 additions & 1 deletion rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,9 @@
#ifndef RCLCPP__EXECUTORS__MULTI_THREADED_EXECUTOR_HPP_
#define RCLCPP__EXECUTORS__MULTI_THREADED_EXECUTOR_HPP_

#include <memory>
#include <mutex>
#include <set>
#include <thread>
#include <unordered_map>

Expand All @@ -34,10 +36,22 @@ class MultiThreadedExecutor : public executor::Executor
public:
RCLCPP_SMART_PTR_DEFINITIONS(MultiThreadedExecutor)

/// Constructor for MultiThreadedExecutor.
/**
* For the yield_before_execute option, when true std::this_thread::yield()
* will be called after acquiring work (as an AnyExecutable) and after
* releasing the spinning lock, but before executing the work.
* This is useful for reproducing some bugs related to taking work more than
* once.
*
* \param args common arguments for all executors
* \param yield_before_execute if true std::this_thread::yield() is called
*/
RCLCPP_PUBLIC
MultiThreadedExecutor(
const executor::ExecutorArgs & args = rclcpp::executor::create_default_executor_arguments(),
size_t number_of_threads = 0);
size_t number_of_threads = 0,
bool yield_before_execute = false);

RCLCPP_PUBLIC
virtual ~MultiThreadedExecutor();
Expand All @@ -60,6 +74,10 @@ class MultiThreadedExecutor : public executor::Executor

std::mutex wait_mutex_;
size_t number_of_threads_;
bool yield_before_execute_;

std::mutex scheduled_timers_mutex_;
std::set<TimerBase::SharedPtr> scheduled_timers_;
};

} // namespace executors
Expand Down
26 changes: 24 additions & 2 deletions rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <chrono>
#include <functional>
#include <memory>
#include <vector>

#include "rclcpp/utilities.hpp"
Expand All @@ -25,8 +26,9 @@ using rclcpp::executors::MultiThreadedExecutor;

MultiThreadedExecutor::MultiThreadedExecutor(
const rclcpp::executor::ExecutorArgs & args,
size_t number_of_threads)
: executor::Executor(args)
size_t number_of_threads,
bool yield_before_execute)
: executor::Executor(args), yield_before_execute_(yield_before_execute)
{
number_of_threads_ = number_of_threads ? number_of_threads : std::thread::hardware_concurrency();
if (number_of_threads_ == 0) {
Expand Down Expand Up @@ -78,7 +80,27 @@ MultiThreadedExecutor::run(size_t)
if (!get_next_executable(any_exec)) {
continue;
}
if (any_exec.timer) {
// Guard against multiple threads getting the same timer.
std::lock_guard<std::mutex> lock(scheduled_timers_mutex_);
if (scheduled_timers_.count(any_exec.timer) != 0) {
continue;
}
scheduled_timers_.insert(any_exec.timer);
}
}
if (yield_before_execute_) {
std::this_thread::yield();
}

execute_any_executable(any_exec);

if (any_exec.timer) {
std::lock_guard<std::mutex> lock(scheduled_timers_mutex_);
auto it = scheduled_timers_.find(any_exec.timer);
if (it != scheduled_timers_.end()) {
scheduled_timers_.erase(it);
}
}
}
}
100 changes: 100 additions & 0 deletions rclcpp/test/executors/test_multi_threaded_executor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include <chrono>
#include <string>
#include <memory>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/executors.hpp"

#include "rcl_interfaces/msg/intra_process_message.hpp"

using namespace std::chrono_literals;

using rcl_interfaces::msg::IntraProcessMessage;

class TestMultiThreadedExecutor : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
};

/*
Test that timers are not taken multiple times when using reentrant callback groups.
*/
TEST_F(TestMultiThreadedExecutor, timer_over_take) {
#ifdef __linux__
// This seems to be the most effective way to force the bug to happen on Linux.
// This is unnecessary on MacOS, since the default scheduler causes it.
struct sched_param param;
param.sched_priority = 0;
if (sched_setscheduler(0, SCHED_BATCH, &param) != 0) {
perror("sched_setscheduler");
}
#endif

bool yield_before_execute = true;

rclcpp::executors::MultiThreadedExecutor executor(
rclcpp::executor::create_default_executor_arguments(), 2u, yield_before_execute);

ASSERT_GT(executor.get_number_of_threads(), 1u);

std::shared_ptr<rclcpp::Node> node =
std::make_shared<rclcpp::Node>("test_multi_threaded_executor_timer_over_take");

auto cbg = node->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant);

rclcpp::Clock system_clock(RCL_STEADY_TIME);
std::mutex last_mutex;
auto last = system_clock.now();

std::atomic_int timer_count {0};

auto timer_callback = [&timer_count, &executor, &system_clock, &last_mutex, &last]() {
const double PERIOD = 0.1f;
const double TOLERANCE = 0.01f;

rclcpp::Time now = system_clock.now();
timer_count++;

if (timer_count > 5) {
executor.cancel();
}

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

if (diff < PERIOD - TOLERANCE || diff > PERIOD + TOLERANCE) {
executor.cancel();
ASSERT_TRUE(diff > PERIOD - TOLERANCE);
ASSERT_TRUE(diff < PERIOD + TOLERANCE);
}
}
};

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