Skip to content

Commit

Permalink
deprecate the static single threaded executor (#2598)
Browse files Browse the repository at this point in the history
* deprecate the static single threded executor

Signed-off-by: Alberto Soragna <[email protected]>

* suppress deprecation warning for static executor and remove benchmark tests

Signed-off-by: Alberto Soragna <[email protected]>

* fix uncrustify linter errors

Signed-off-by: Alberto Soragna <[email protected]>

* fix windows deprecation warnings

i created an alias to give the deprecated executor a new name; this works when the class is directly used but it doesn't work in combination with templates (like std::make_shared<DeprecatedAlias>) because the compiler needs to resolved the type behind the alias triggering the warning

Signed-off-by: Alberto Soragna <[email protected]>

* update test_reinitialized_timers.cpp to use the executor test utilities

Signed-off-by: Alberto Soragna <[email protected]>

* do not use executor pointer

Signed-off-by: Alberto Soragna <[email protected]>

---------

Signed-off-by: Alberto Soragna <[email protected]>
Co-authored-by: Alberto Soragna <[email protected]>
  • Loading branch information
alsora and Alberto Soragna authored Aug 20, 2024
1 parent e6b6faf commit dfaaf47
Show file tree
Hide file tree
Showing 9 changed files with 80 additions and 171 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,15 @@ namespace executors
/// Static executor implementation
/**
* This executor is a static version of the original single threaded executor.
* It's static because it doesn't reconstruct the executable list for every iteration.
* It contains some performance optimization to avoid unnecessary reconstructions of
* the executable list for every iteration.
* All nodes, callbackgroups, timers, subscriptions etc. are created before
* spin() is called, and modified only when an entity is added/removed to/from a node.
* This executor is deprecated because these performance improvements have now been
* applied to all other executors.
* This executor is also considered unstable due to known bugs.
* See the unit-tests that are only applied to `StandardExecutors` for information
* on the known limitations.
*
* To run this executor instead of SingleThreadedExecutor replace:
* rclcpp::executors::SingleThreadedExecutor exec;
Expand All @@ -44,7 +50,8 @@ namespace executors
* exec.spin();
* exec.remove_node(node);
*/
class StaticSingleThreadedExecutor : public rclcpp::Executor
class [[deprecated("Use rclcpp::executors::SingleThreadedExecutor")]] StaticSingleThreadedExecutor
: public rclcpp::Executor
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(StaticSingleThreadedExecutor)
Expand Down
89 changes: 0 additions & 89 deletions rclcpp/test/benchmark/benchmark_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,71 +189,6 @@ BENCHMARK_F(PerformanceTestExecutorSimple, multi_thread_executor_remove_node)(be
}
}

BENCHMARK_F(
PerformanceTestExecutorSimple,
static_single_thread_executor_add_node)(benchmark::State & st)
{
rclcpp::executors::StaticSingleThreadedExecutor executor;
for (auto _ : st) {
(void)_;
executor.add_node(node);
st.PauseTiming();
executor.remove_node(node);
st.ResumeTiming();
}
}

BENCHMARK_F(
PerformanceTestExecutorSimple,
static_single_thread_executor_remove_node)(benchmark::State & st)
{
rclcpp::executors::StaticSingleThreadedExecutor executor;
for (auto _ : st) {
(void)_;
st.PauseTiming();
executor.add_node(node);
st.ResumeTiming();
executor.remove_node(node);
}
}

BENCHMARK_F(
PerformanceTestExecutorSimple,
static_single_thread_executor_spin_until_future_complete)(benchmark::State & st)
{
rclcpp::executors::StaticSingleThreadedExecutor executor;
// test success of an immediately finishing future
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();

auto ret = executor.spin_until_future_complete(shared_future, 100ms);
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
st.SkipWithError(rcutils_get_error_string().str);
}

reset_heap_counters();

for (auto _ : st) {
(void)_;
// static_single_thread_executor has a special design. We need to add/remove the node each
// time you call spin
st.PauseTiming();
executor.add_node(node);
st.ResumeTiming();

ret = executor.spin_until_future_complete(shared_future, 100ms);
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
st.SkipWithError(rcutils_get_error_string().str);
break;
}
st.PauseTiming();
executor.remove_node(node);
st.ResumeTiming();
}
}

BENCHMARK_F(
PerformanceTestExecutorSimple,
single_thread_executor_spin_node_until_future_complete)(benchmark::State & st)
Expand Down Expand Up @@ -314,30 +249,6 @@ BENCHMARK_F(
}
}

BENCHMARK_F(
PerformanceTestExecutorSimple,
static_single_thread_executor_spin_node_until_future_complete)(benchmark::State & st)
{
rclcpp::executors::StaticSingleThreadedExecutor executor;
// test success of an immediately finishing future
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);
auto shared_future = future.share();

reset_heap_counters();

for (auto _ : st) {
(void)_;
auto ret = rclcpp::executors::spin_node_until_future_complete(
executor, node, shared_future, 1s);
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
st.SkipWithError(rcutils_get_error_string().str);
break;
}
}
}

BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_future_complete)(benchmark::State & st)
{
// test success of an immediately finishing future
Expand Down
22 changes: 20 additions & 2 deletions rclcpp/test/rclcpp/executors/executor_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,29 @@
#include "rclcpp/executors/static_single_threaded_executor.hpp"
#include "rclcpp/executors/multi_threaded_executor.hpp"

// suppress deprecated StaticSingleThreadedExecutor warning
// we define an alias that explicitly indicates that this class is deprecated, while avoiding
// polluting a lot of files the gcc pragmas
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
using DeprecatedStaticSingleThreadedExecutor = rclcpp::executors::StaticSingleThreadedExecutor;
// remove warning suppression
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif

using ExecutorTypes =
::testing::Types<
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::StaticSingleThreadedExecutor,
DeprecatedStaticSingleThreadedExecutor,
rclcpp::experimental::executors::EventsExecutor>;

class ExecutorTypeNames
Expand All @@ -47,7 +65,7 @@ class ExecutorTypeNames
return "MultiThreadedExecutor";
}

if (std::is_same<T, rclcpp::executors::StaticSingleThreadedExecutor>()) {
if (std::is_same<T, DeprecatedStaticSingleThreadedExecutor>()) {
return "StaticSingleThreadedExecutor";
}

Expand Down
14 changes: 7 additions & 7 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -489,7 +489,7 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
// for them in the meantime.
// see: https://github.com/ros2/rclcpp/issues/2462
if (
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>())
std::is_same<ExecutorType, DeprecatedStaticSingleThreadedExecutor>())
{
GTEST_SKIP();
}
Expand Down Expand Up @@ -674,20 +674,20 @@ TYPED_TEST(TestExecutors, testRaceConditionAddNode)
}

// Create an executor
auto executor = std::make_shared<ExecutorType>();
ExecutorType executor;
// Start spinning
auto executor_thread = std::thread(
[executor]() {
executor->spin();
[&executor]() {
executor.spin();
});
// Add a node to the executor
executor->add_node(this->node);
executor.add_node(this->node);

// Cancel the executor (make sure that it's already spinning first)
while (!executor->is_spinning() && rclcpp::ok()) {
while (!executor.is_spinning() && rclcpp::ok()) {
continue;
}
executor->cancel();
executor.cancel();

// Try to join the thread after cancelling the executor
// This is the "test". We want to make sure that we can still cancel the executor
Expand Down
32 changes: 23 additions & 9 deletions rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,6 @@ class TestBusyWaiting : public ::testing::Test
auto waitable_interfaces = node->get_node_waitables_interface();
waitable = std::make_shared<TestWaitable>();
waitable_interfaces->add_waitable(waitable, callback_group);

executor = std::make_shared<T>();
executor->add_callback_group(callback_group, node->get_node_base_interface());
}

void TearDown() override
Expand Down Expand Up @@ -108,36 +105,53 @@ class TestBusyWaiting : public ::testing::Test
rclcpp::CallbackGroup::SharedPtr callback_group;
std::shared_ptr<TestWaitable> waitable;
std::chrono::steady_clock::time_point start_time;
std::shared_ptr<T> executor;
bool has_executed;
};

TYPED_TEST_SUITE(TestBusyWaiting, ExecutorTypes, ExecutorTypeNames);

TYPED_TEST(TestBusyWaiting, test_spin_all)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_callback_group(
this->callback_group,
this->node->get_node_base_interface());

this->set_up_and_trigger_waitable();

auto start_time = std::chrono::steady_clock::now();
this->executor->spin_all(this->max_duration);
executor.spin_all(this->max_duration);
this->check_for_busy_waits(start_time);
// this should get the initial trigger, and the follow up from in the callback
ASSERT_EQ(this->waitable->get_count(), 2u);
}

TYPED_TEST(TestBusyWaiting, test_spin_some)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_callback_group(
this->callback_group,
this->node->get_node_base_interface());

this->set_up_and_trigger_waitable();

auto start_time = std::chrono::steady_clock::now();
this->executor->spin_some(this->max_duration);
executor.spin_some(this->max_duration);
this->check_for_busy_waits(start_time);
// this should get the inital trigger, but not the follow up in the callback
ASSERT_EQ(this->waitable->get_count(), 1u);
}

TYPED_TEST(TestBusyWaiting, test_spin)
{
using ExecutorType = TypeParam;
ExecutorType executor;
executor.add_callback_group(
this->callback_group,
this->node->get_node_base_interface());

std::condition_variable cv;
std::mutex cv_m;
bool first_check_passed = false;
Expand All @@ -151,8 +165,8 @@ TYPED_TEST(TestBusyWaiting, test_spin)
});

auto start_time = std::chrono::steady_clock::now();
std::thread t([this]() {
this->executor->spin();
std::thread t([&executor]() {
executor.spin();
});

// wait until thread has started (first execute of waitable)
Expand All @@ -172,7 +186,7 @@ TYPED_TEST(TestBusyWaiting, test_spin)
}
EXPECT_EQ(this->waitable->get_count(), 2u);

this->executor->cancel();
executor.cancel();
t.join();

this->check_for_busy_waits(start_time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -286,7 +286,7 @@ using MainExecutorTypes =
::testing::Types<
rclcpp::executors::SingleThreadedExecutor,
rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::StaticSingleThreadedExecutor>;
DeprecatedStaticSingleThreadedExecutor>;

// TODO(@fujitatomoya): this test excludes EventExecutor because it does not
// support simulation time used for this test to relax the racy condition.
Expand Down
24 changes: 10 additions & 14 deletions rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,10 @@
#include <memory>
#include <thread>

#include "rclcpp/executors/multi_threaded_executor.hpp"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/executors/static_single_threaded_executor.hpp"
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
#include "rclcpp/rclcpp.hpp"

#include "./executor_types.hpp"

template<typename ExecutorType>
class TestTimersLifecycle : public testing::Test
{
Expand All @@ -34,19 +32,17 @@ class TestTimersLifecycle : public testing::Test
void TearDown() override {rclcpp::shutdown();}
};

using ExecutorTypes = ::testing::Types<
rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor,
rclcpp::executors::StaticSingleThreadedExecutor, rclcpp::experimental::executors::EventsExecutor>;

TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes);

TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
{
using ExecutorType = TypeParam;
ExecutorType executor;

auto timers_period = std::chrono::milliseconds(50);
auto node = std::make_shared<rclcpp::Node>("test_node");
auto executor = std::make_unique<TypeParam>();

executor->add_node(node);
executor.add_node(node);

size_t count_1 = 0;
auto timer_1 = rclcpp::create_timer(
Expand All @@ -57,12 +53,12 @@ TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_2]() {count_2++;});

{
std::thread executor_thread([&executor]() {executor->spin();});
std::thread executor_thread([&executor]() {executor.spin();});

while (count_2 < 10u) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
executor->cancel();
executor.cancel();
executor_thread.join();

EXPECT_GE(count_2, 10u);
Expand All @@ -78,12 +74,12 @@ TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
node, node->get_clock(), rclcpp::Duration(timers_period), [&count_2]() {count_2++;});

{
std::thread executor_thread([&executor]() {executor->spin();});
std::thread executor_thread([&executor]() {executor.spin();});

while (count_2 < 10u) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
executor->cancel();
executor.cancel();
executor_thread.join();

EXPECT_GE(count_2, 10u);
Expand Down
Loading

0 comments on commit dfaaf47

Please sign in to comment.