Skip to content

Commit dfaaf47

Browse files
alsoraAlberto Soragna
andauthored
deprecate the static single threaded executor (#2598)
* deprecate the static single threded executor Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> * suppress deprecation warning for static executor and remove benchmark tests Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> * fix uncrustify linter errors Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> * 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 <alberto.soragna@gmail.com> * update test_reinitialized_timers.cpp to use the executor test utilities Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> * do not use executor pointer Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> --------- Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com> Co-authored-by: Alberto Soragna <asoragna@irobot.com>
1 parent e6b6faf commit dfaaf47

9 files changed

+80
-171
lines changed

rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,9 +31,15 @@ namespace executors
3131
/// Static executor implementation
3232
/**
3333
* This executor is a static version of the original single threaded executor.
34-
* It's static because it doesn't reconstruct the executable list for every iteration.
34+
* It contains some performance optimization to avoid unnecessary reconstructions of
35+
* the executable list for every iteration.
3536
* All nodes, callbackgroups, timers, subscriptions etc. are created before
3637
* spin() is called, and modified only when an entity is added/removed to/from a node.
38+
* This executor is deprecated because these performance improvements have now been
39+
* applied to all other executors.
40+
* This executor is also considered unstable due to known bugs.
41+
* See the unit-tests that are only applied to `StandardExecutors` for information
42+
* on the known limitations.
3743
*
3844
* To run this executor instead of SingleThreadedExecutor replace:
3945
* rclcpp::executors::SingleThreadedExecutor exec;
@@ -44,7 +50,8 @@ namespace executors
4450
* exec.spin();
4551
* exec.remove_node(node);
4652
*/
47-
class StaticSingleThreadedExecutor : public rclcpp::Executor
53+
class [[deprecated("Use rclcpp::executors::SingleThreadedExecutor")]] StaticSingleThreadedExecutor
54+
: public rclcpp::Executor
4855
{
4956
public:
5057
RCLCPP_SMART_PTR_DEFINITIONS(StaticSingleThreadedExecutor)

rclcpp/test/benchmark/benchmark_executor.cpp

Lines changed: 0 additions & 89 deletions
Original file line numberDiff line numberDiff line change
@@ -189,71 +189,6 @@ BENCHMARK_F(PerformanceTestExecutorSimple, multi_thread_executor_remove_node)(be
189189
}
190190
}
191191

192-
BENCHMARK_F(
193-
PerformanceTestExecutorSimple,
194-
static_single_thread_executor_add_node)(benchmark::State & st)
195-
{
196-
rclcpp::executors::StaticSingleThreadedExecutor executor;
197-
for (auto _ : st) {
198-
(void)_;
199-
executor.add_node(node);
200-
st.PauseTiming();
201-
executor.remove_node(node);
202-
st.ResumeTiming();
203-
}
204-
}
205-
206-
BENCHMARK_F(
207-
PerformanceTestExecutorSimple,
208-
static_single_thread_executor_remove_node)(benchmark::State & st)
209-
{
210-
rclcpp::executors::StaticSingleThreadedExecutor executor;
211-
for (auto _ : st) {
212-
(void)_;
213-
st.PauseTiming();
214-
executor.add_node(node);
215-
st.ResumeTiming();
216-
executor.remove_node(node);
217-
}
218-
}
219-
220-
BENCHMARK_F(
221-
PerformanceTestExecutorSimple,
222-
static_single_thread_executor_spin_until_future_complete)(benchmark::State & st)
223-
{
224-
rclcpp::executors::StaticSingleThreadedExecutor executor;
225-
// test success of an immediately finishing future
226-
std::promise<bool> promise;
227-
std::future<bool> future = promise.get_future();
228-
promise.set_value(true);
229-
auto shared_future = future.share();
230-
231-
auto ret = executor.spin_until_future_complete(shared_future, 100ms);
232-
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
233-
st.SkipWithError(rcutils_get_error_string().str);
234-
}
235-
236-
reset_heap_counters();
237-
238-
for (auto _ : st) {
239-
(void)_;
240-
// static_single_thread_executor has a special design. We need to add/remove the node each
241-
// time you call spin
242-
st.PauseTiming();
243-
executor.add_node(node);
244-
st.ResumeTiming();
245-
246-
ret = executor.spin_until_future_complete(shared_future, 100ms);
247-
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
248-
st.SkipWithError(rcutils_get_error_string().str);
249-
break;
250-
}
251-
st.PauseTiming();
252-
executor.remove_node(node);
253-
st.ResumeTiming();
254-
}
255-
}
256-
257192
BENCHMARK_F(
258193
PerformanceTestExecutorSimple,
259194
single_thread_executor_spin_node_until_future_complete)(benchmark::State & st)
@@ -314,30 +249,6 @@ BENCHMARK_F(
314249
}
315250
}
316251

317-
BENCHMARK_F(
318-
PerformanceTestExecutorSimple,
319-
static_single_thread_executor_spin_node_until_future_complete)(benchmark::State & st)
320-
{
321-
rclcpp::executors::StaticSingleThreadedExecutor executor;
322-
// test success of an immediately finishing future
323-
std::promise<bool> promise;
324-
std::future<bool> future = promise.get_future();
325-
promise.set_value(true);
326-
auto shared_future = future.share();
327-
328-
reset_heap_counters();
329-
330-
for (auto _ : st) {
331-
(void)_;
332-
auto ret = rclcpp::executors::spin_node_until_future_complete(
333-
executor, node, shared_future, 1s);
334-
if (ret != rclcpp::FutureReturnCode::SUCCESS) {
335-
st.SkipWithError(rcutils_get_error_string().str);
336-
break;
337-
}
338-
}
339-
}
340-
341252
BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_future_complete)(benchmark::State & st)
342253
{
343254
// test success of an immediately finishing future

rclcpp/test/rclcpp/executors/executor_types.hpp

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,11 +25,29 @@
2525
#include "rclcpp/executors/static_single_threaded_executor.hpp"
2626
#include "rclcpp/executors/multi_threaded_executor.hpp"
2727

28+
// suppress deprecated StaticSingleThreadedExecutor warning
29+
// we define an alias that explicitly indicates that this class is deprecated, while avoiding
30+
// polluting a lot of files the gcc pragmas
31+
#if !defined(_WIN32)
32+
# pragma GCC diagnostic push
33+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
34+
#else // !defined(_WIN32)
35+
# pragma warning(push)
36+
# pragma warning(disable: 4996)
37+
#endif
38+
using DeprecatedStaticSingleThreadedExecutor = rclcpp::executors::StaticSingleThreadedExecutor;
39+
// remove warning suppression
40+
#if !defined(_WIN32)
41+
# pragma GCC diagnostic pop
42+
#else // !defined(_WIN32)
43+
# pragma warning(pop)
44+
#endif
45+
2846
using ExecutorTypes =
2947
::testing::Types<
3048
rclcpp::executors::SingleThreadedExecutor,
3149
rclcpp::executors::MultiThreadedExecutor,
32-
rclcpp::executors::StaticSingleThreadedExecutor,
50+
DeprecatedStaticSingleThreadedExecutor,
3351
rclcpp::experimental::executors::EventsExecutor>;
3452

3553
class ExecutorTypeNames
@@ -47,7 +65,7 @@ class ExecutorTypeNames
4765
return "MultiThreadedExecutor";
4866
}
4967

50-
if (std::is_same<T, rclcpp::executors::StaticSingleThreadedExecutor>()) {
68+
if (std::is_same<T, DeprecatedStaticSingleThreadedExecutor>()) {
5169
return "StaticSingleThreadedExecutor";
5270
}
5371

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -489,7 +489,7 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
489489
// for them in the meantime.
490490
// see: https://github.com/ros2/rclcpp/issues/2462
491491
if (
492-
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>())
492+
std::is_same<ExecutorType, DeprecatedStaticSingleThreadedExecutor>())
493493
{
494494
GTEST_SKIP();
495495
}
@@ -674,20 +674,20 @@ TYPED_TEST(TestExecutors, testRaceConditionAddNode)
674674
}
675675

676676
// Create an executor
677-
auto executor = std::make_shared<ExecutorType>();
677+
ExecutorType executor;
678678
// Start spinning
679679
auto executor_thread = std::thread(
680-
[executor]() {
681-
executor->spin();
680+
[&executor]() {
681+
executor.spin();
682682
});
683683
// Add a node to the executor
684-
executor->add_node(this->node);
684+
executor.add_node(this->node);
685685

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

692692
// Try to join the thread after cancelling the executor
693693
// This is the "test". We want to make sure that we can still cancel the executor

rclcpp/test/rclcpp/executors/test_executors_busy_waiting.cpp

Lines changed: 23 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -47,9 +47,6 @@ class TestBusyWaiting : public ::testing::Test
4747
auto waitable_interfaces = node->get_node_waitables_interface();
4848
waitable = std::make_shared<TestWaitable>();
4949
waitable_interfaces->add_waitable(waitable, callback_group);
50-
51-
executor = std::make_shared<T>();
52-
executor->add_callback_group(callback_group, node->get_node_base_interface());
5350
}
5451

5552
void TearDown() override
@@ -108,36 +105,53 @@ class TestBusyWaiting : public ::testing::Test
108105
rclcpp::CallbackGroup::SharedPtr callback_group;
109106
std::shared_ptr<TestWaitable> waitable;
110107
std::chrono::steady_clock::time_point start_time;
111-
std::shared_ptr<T> executor;
112108
bool has_executed;
113109
};
114110

115111
TYPED_TEST_SUITE(TestBusyWaiting, ExecutorTypes, ExecutorTypeNames);
116112

117113
TYPED_TEST(TestBusyWaiting, test_spin_all)
118114
{
115+
using ExecutorType = TypeParam;
116+
ExecutorType executor;
117+
executor.add_callback_group(
118+
this->callback_group,
119+
this->node->get_node_base_interface());
120+
119121
this->set_up_and_trigger_waitable();
120122

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

128130
TYPED_TEST(TestBusyWaiting, test_spin_some)
129131
{
132+
using ExecutorType = TypeParam;
133+
ExecutorType executor;
134+
executor.add_callback_group(
135+
this->callback_group,
136+
this->node->get_node_base_interface());
137+
130138
this->set_up_and_trigger_waitable();
131139

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

139147
TYPED_TEST(TestBusyWaiting, test_spin)
140148
{
149+
using ExecutorType = TypeParam;
150+
ExecutorType executor;
151+
executor.add_callback_group(
152+
this->callback_group,
153+
this->node->get_node_base_interface());
154+
141155
std::condition_variable cv;
142156
std::mutex cv_m;
143157
bool first_check_passed = false;
@@ -151,8 +165,8 @@ TYPED_TEST(TestBusyWaiting, test_spin)
151165
});
152166

153167
auto start_time = std::chrono::steady_clock::now();
154-
std::thread t([this]() {
155-
this->executor->spin();
168+
std::thread t([&executor]() {
169+
executor.spin();
156170
});
157171

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

175-
this->executor->cancel();
189+
executor.cancel();
176190
t.join();
177191

178192
this->check_for_busy_waits(start_time);

rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -286,7 +286,7 @@ using MainExecutorTypes =
286286
::testing::Types<
287287
rclcpp::executors::SingleThreadedExecutor,
288288
rclcpp::executors::MultiThreadedExecutor,
289-
rclcpp::executors::StaticSingleThreadedExecutor>;
289+
DeprecatedStaticSingleThreadedExecutor>;
290290

291291
// TODO(@fujitatomoya): this test excludes EventExecutor because it does not
292292
// support simulation time used for this test to relax the racy condition.

rclcpp/test/rclcpp/executors/test_reinitialized_timers.cpp

Lines changed: 10 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -19,12 +19,10 @@
1919
#include <memory>
2020
#include <thread>
2121

22-
#include "rclcpp/executors/multi_threaded_executor.hpp"
23-
#include "rclcpp/executors/single_threaded_executor.hpp"
24-
#include "rclcpp/executors/static_single_threaded_executor.hpp"
25-
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
2622
#include "rclcpp/rclcpp.hpp"
2723

24+
#include "./executor_types.hpp"
25+
2826
template<typename ExecutorType>
2927
class TestTimersLifecycle : public testing::Test
3028
{
@@ -34,19 +32,17 @@ class TestTimersLifecycle : public testing::Test
3432
void TearDown() override {rclcpp::shutdown();}
3533
};
3634

37-
using ExecutorTypes = ::testing::Types<
38-
rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor,
39-
rclcpp::executors::StaticSingleThreadedExecutor, rclcpp::experimental::executors::EventsExecutor>;
40-
4135
TYPED_TEST_SUITE(TestTimersLifecycle, ExecutorTypes);
4236

4337
TYPED_TEST(TestTimersLifecycle, timers_lifecycle_reinitialized_object)
4438
{
39+
using ExecutorType = TypeParam;
40+
ExecutorType executor;
41+
4542
auto timers_period = std::chrono::milliseconds(50);
4643
auto node = std::make_shared<rclcpp::Node>("test_node");
47-
auto executor = std::make_unique<TypeParam>();
4844

49-
executor->add_node(node);
45+
executor.add_node(node);
5046

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

5955
{
60-
std::thread executor_thread([&executor]() {executor->spin();});
56+
std::thread executor_thread([&executor]() {executor.spin();});
6157

6258
while (count_2 < 10u) {
6359
std::this_thread::sleep_for(std::chrono::milliseconds(10));
6460
}
65-
executor->cancel();
61+
executor.cancel();
6662
executor_thread.join();
6763

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

8076
{
81-
std::thread executor_thread([&executor]() {executor->spin();});
77+
std::thread executor_thread([&executor]() {executor.spin();});
8278

8379
while (count_2 < 10u) {
8480
std::this_thread::sleep_for(std::chrono::milliseconds(10));
8581
}
86-
executor->cancel();
82+
executor.cancel();
8783
executor_thread.join();
8884

8985
EXPECT_GE(count_2, 10u);

0 commit comments

Comments
 (0)