From dfaaf4739a5bd549d1183ebd02fef024cfc8e2f9 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Mon, 19 Aug 2024 20:13:21 -0700 Subject: [PATCH] deprecate the static single threaded executor (#2598) * deprecate the static single threded executor Signed-off-by: Alberto Soragna * suppress deprecation warning for static executor and remove benchmark tests Signed-off-by: Alberto Soragna * fix uncrustify linter errors Signed-off-by: Alberto Soragna * 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) because the compiler needs to resolved the type behind the alias triggering the warning Signed-off-by: Alberto Soragna * update test_reinitialized_timers.cpp to use the executor test utilities Signed-off-by: Alberto Soragna * do not use executor pointer Signed-off-by: Alberto Soragna --------- Signed-off-by: Alberto Soragna Co-authored-by: Alberto Soragna --- .../static_single_threaded_executor.hpp | 11 ++- rclcpp/test/benchmark/benchmark_executor.cpp | 89 ------------------- .../test/rclcpp/executors/executor_types.hpp | 22 ++++- .../test/rclcpp/executors/test_executors.cpp | 14 +-- .../executors/test_executors_busy_waiting.cpp | 32 +++++-- .../test_executors_timer_cancel_behavior.cpp | 2 +- .../executors/test_reinitialized_timers.cpp | 24 +++-- .../test_static_single_threaded_executor.cpp | 15 ++-- .../test_add_callback_groups_to_executor.cpp | 42 +-------- 9 files changed, 80 insertions(+), 171 deletions(-) diff --git a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp index 6f22909caf..33674465a8 100644 --- a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp @@ -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; @@ -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) diff --git a/rclcpp/test/benchmark/benchmark_executor.cpp b/rclcpp/test/benchmark/benchmark_executor.cpp index 65bb3a1007..ea7afa8696 100644 --- a/rclcpp/test/benchmark/benchmark_executor.cpp +++ b/rclcpp/test/benchmark/benchmark_executor.cpp @@ -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 promise; - std::future 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) @@ -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 promise; - std::future 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 diff --git a/rclcpp/test/rclcpp/executors/executor_types.hpp b/rclcpp/test/rclcpp/executors/executor_types.hpp index 0218a9b547..02462faf5f 100644 --- a/rclcpp/test/rclcpp/executors/executor_types.hpp +++ b/rclcpp/test/rclcpp/executors/executor_types.hpp @@ -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 @@ -47,7 +65,7 @@ class ExecutorTypeNames return "MultiThreadedExecutor"; } - if (std::is_same()) { + if (std::is_same()) { return "StaticSingleThreadedExecutor"; } diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 72afee8dda..b79de72971 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -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()) + std::is_same()) { GTEST_SKIP(); } @@ -674,20 +674,20 @@ TYPED_TEST(TestExecutors, testRaceConditionAddNode) } // Create an executor - auto executor = std::make_shared(); + 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 diff --git a/rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp b/rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp index bc3ce4b62d..d481638afb 100644 --- a/rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp @@ -47,9 +47,6 @@ class TestBusyWaiting : public ::testing::Test auto waitable_interfaces = node->get_node_waitables_interface(); waitable = std::make_shared(); waitable_interfaces->add_waitable(waitable, callback_group); - - executor = std::make_shared(); - executor->add_callback_group(callback_group, node->get_node_base_interface()); } void TearDown() override @@ -108,7 +105,6 @@ class TestBusyWaiting : public ::testing::Test rclcpp::CallbackGroup::SharedPtr callback_group; std::shared_ptr waitable; std::chrono::steady_clock::time_point start_time; - std::shared_ptr executor; bool has_executed; }; @@ -116,10 +112,16 @@ 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); @@ -127,10 +129,16 @@ TYPED_TEST(TestBusyWaiting, test_spin_all) 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); @@ -138,6 +146,12 @@ TYPED_TEST(TestBusyWaiting, test_spin_some) 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; @@ -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) @@ -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); diff --git a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp index f6bbd2ccc8..72bbceecb2 100644 --- a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp @@ -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. diff --git a/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp b/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp index 55a46a78e2..d1ac90b95b 100644 --- a/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp +++ b/rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp @@ -19,12 +19,10 @@ #include #include -#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 class TestTimersLifecycle : public testing::Test { @@ -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("test_node"); - auto executor = std::make_unique(); - executor->add_node(node); + executor.add_node(node); size_t count_1 = 0; auto timer_1 = rclcpp::create_timer( @@ -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); @@ -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); diff --git a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp index 05d0b23152..a834c7b2be 100644 --- a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp @@ -20,12 +20,13 @@ #include #include "rclcpp/exceptions.hpp" +#include "rclcpp/executors.hpp" #include "rclcpp/node.hpp" #include "rclcpp/rclcpp.hpp" -#include "rclcpp/executors.hpp" #include "test_msgs/srv/empty.hpp" +#include "./executor_types.hpp" #include "../../mocking_utils/patch.hpp" #include "../../utils/rclcpp_gtest_macros.hpp" @@ -46,7 +47,7 @@ class TestStaticSingleThreadedExecutor : public ::testing::Test }; TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); @@ -61,7 +62,7 @@ TEST_F(TestStaticSingleThreadedExecutor, add_callback_group_trigger_guard_failed } TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); { @@ -74,7 +75,7 @@ TEST_F(TestStaticSingleThreadedExecutor, add_node_trigger_guard_failed) { } TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_failed) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); rclcpp::CallbackGroup::SharedPtr cb_group = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); @@ -92,7 +93,7 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_callback_group_trigger_guard_fai } TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); { @@ -105,7 +106,7 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_failed) { } TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); executor.add_node(node); @@ -120,7 +121,7 @@ TEST_F(TestStaticSingleThreadedExecutor, remove_node_trigger_guard_failed) { } TEST_F(TestStaticSingleThreadedExecutor, execute_service) { - rclcpp::executors::StaticSingleThreadedExecutor executor; + DeprecatedStaticSingleThreadedExecutor executor; auto node = std::make_shared("node", "ns"); executor.add_node(node); diff --git a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp index 6edcc2cb28..2c628e5cf8 100644 --- a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp +++ b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp @@ -29,6 +29,8 @@ #include "rclcpp/executor.hpp" #include "rclcpp/rclcpp.hpp" +#include "./executors/executor_types.hpp" + using namespace std::chrono_literals; template @@ -48,48 +50,8 @@ class TestAddCallbackGroupsToExecutor : public ::testing::Test template class TestAddCallbackGroupsToExecutorStable : public TestAddCallbackGroupsToExecutor {}; -using ExecutorTypes = - ::testing::Types< - rclcpp::executors::SingleThreadedExecutor, - rclcpp::executors::MultiThreadedExecutor, - rclcpp::executors::StaticSingleThreadedExecutor, - rclcpp::experimental::executors::EventsExecutor>; - -class ExecutorTypeNames -{ -public: - template - static std::string GetName(int idx) - { - (void)idx; - if (std::is_same()) { - return "SingleThreadedExecutor"; - } - - if (std::is_same()) { - return "MultiThreadedExecutor"; - } - - if (std::is_same()) { - return "StaticSingleThreadedExecutor"; - } - - if (std::is_same()) { - return "EventsExecutor"; - } - - return ""; - } -}; - TYPED_TEST_SUITE(TestAddCallbackGroupsToExecutor, ExecutorTypes, ExecutorTypeNames); -// StaticSingleThreadedExecutor is not included in these tests for now -using StandardExecutors = - ::testing::Types< - rclcpp::executors::SingleThreadedExecutor, - rclcpp::executors::MultiThreadedExecutor, - rclcpp::experimental::executors::EventsExecutor>; TYPED_TEST_SUITE(TestAddCallbackGroupsToExecutorStable, StandardExecutors, ExecutorTypeNames); /*