Skip to content

Commit 4bf1cb8

Browse files
committed
deprecate rclcpp::spin_some and rclcpp::spin_all
1 parent a0bef23 commit 4bf1cb8

14 files changed

+222
-74
lines changed

rclcpp/include/rclcpp/executors.hpp

Lines changed: 62 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -28,24 +28,82 @@
2828
namespace rclcpp
2929
{
3030

31-
/// Create a default single-threaded executor and execute all available work exhaustively.
32-
/** \param[in] node_ptr Shared pointer to the node to spin. */
31+
/**
32+
* @brief Create a default single-threaded executor and execute all available work exhaustively.
33+
* @param node_ptr Shared pointer to the base interface of the node to spin.
34+
* @param max_duration max duration to spin
35+
*
36+
* This method is deprecated because it can lead to very bad performance if used in a loop:
37+
* each call will create a new executor and register the node, which is an expensive operation.
38+
* It's recommended to always manually instantiate an executor and call the methods with
39+
* the same name on it.
40+
* For example:
41+
* SingleThreadedExecutor executor;
42+
* executor.add_node(node_ptr);
43+
* executor.spin_all(max_duration);
44+
* If you are using a non-default context, this should be passed to the executor's constructor.
45+
*/
46+
[[deprecated("use SingleThreadedExecutor::spin_all instead")]]
3347
RCLCPP_PUBLIC
3448
void
3549
spin_all(
3650
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
3751
std::chrono::nanoseconds max_duration);
3852

53+
/**
54+
* @brief Create a default single-threaded executor and execute all available work exhaustively.
55+
* @param node_ptr Shared pointer to the node to spin.
56+
* @param max_duration max duration to spin
57+
*
58+
* This method is deprecated because it can lead to very bad performance if used in a loop:
59+
* each call will create a new executor and register the node, which is an expensive operation.
60+
* It's recommended to always manually instantiate an executor and call the methods with
61+
* the same name on it.
62+
* For example:
63+
* SingleThreadedExecutor executor;
64+
* executor.add_node(node_ptr);
65+
* executor.spin_all(max_duration);
66+
* If you are using a non-default context, this should be passed to the executor's constructor.
67+
*/
68+
[[deprecated("use SingleThreadedExecutor::spin_all instead")]]
3969
RCLCPP_PUBLIC
4070
void
4171
spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration);
4272

43-
/// Create a default single-threaded executor and execute any immediately available work.
44-
/** \param[in] node_ptr Shared pointer to the node to spin. */
73+
/**
74+
* @brief Create a default single-threaded executor and execute any immediately available work.
75+
* @param node_ptr Shared pointer to the base interface of the node to spin.
76+
*
77+
* This method is deprecated because it can lead to very bad performance if used in a loop:
78+
* each call will create a new executor and register the node, which is an expensive operation.
79+
* It's recommended to always manually instantiate an executor and call the methods with
80+
* the same name on it.
81+
* For example:
82+
* SingleThreadedExecutor executor;
83+
* executor.add_node(node_ptr);
84+
* executor.spin_some();
85+
* If you are using a non-default context, this should be passed to the executor's constructor.
86+
*/
87+
[[deprecated("use SingleThreadedExecutor::spin_some instead")]]
4588
RCLCPP_PUBLIC
4689
void
4790
spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
4891

92+
/**
93+
* @brief Create a default single-threaded executor and execute any immediately available work.
94+
* @param node_ptr Shared pointer to the node to spin.
95+
*
96+
* This method is deprecated because it can lead to very bad performance if used in a loop:
97+
* each call will create a new executor and register the node, which is an expensive operation.
98+
* It's recommended to always manually instantiate an executor and call the methods with
99+
* the same name on it.
100+
* For example:
101+
* SingleThreadedExecutor executor;
102+
* executor.add_node(node_ptr);
103+
* executor.spin_some();
104+
* If you are using a non-default context, this should be passed to the executor's constructor.
105+
*/
106+
[[deprecated("use SingleThreadedExecutor::spin_some instead")]]
49107
RCLCPP_PUBLIC
50108
void
51109
spin_some(rclcpp::Node::SharedPtr node_ptr);

rclcpp/src/rclcpp/executor.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ class rclcpp::ExecutorImplementation {};
5252

5353
Executor::Executor(const std::shared_ptr<rclcpp::Context> & context)
5454
: spinning(false),
55+
context_(context),
5556
entities_need_rebuild_(true),
5657
collector_(nullptr),
5758
wait_set_({}, {}, {}, {}, {}, {}, context)
@@ -186,6 +187,12 @@ Executor::add_callback_group(
186187
void
187188
Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify)
188189
{
190+
if (node_ptr->get_context() != context_)
191+
{
192+
throw std::runtime_error(
193+
"add_node() called with a node with a different context from this executor");
194+
}
195+
189196
this->collector_.add_node(node_ptr);
190197

191198
try {

rclcpp/src/rclcpp/executors.cpp

Lines changed: 27 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,6 @@ rclcpp::spin_all(
2525
exec.spin_node_all(node_ptr, max_duration);
2626
}
2727

28-
void
29-
rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
30-
{
31-
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
32-
}
33-
3428
void
3529
rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
3630
{
@@ -40,12 +34,6 @@ rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr
4034
exec.spin_node_some(node_ptr);
4135
}
4236

43-
void
44-
rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
45-
{
46-
rclcpp::spin_some(node_ptr->get_node_base_interface());
47-
}
48-
4937
void
5038
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
5139
{
@@ -62,3 +50,30 @@ rclcpp::spin(rclcpp::Node::SharedPtr node_ptr)
6250
{
6351
rclcpp::spin(node_ptr->get_node_base_interface());
6452
}
53+
54+
#if !defined(_WIN32)
55+
# pragma GCC diagnostic push
56+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
57+
#else // !defined(_WIN32)
58+
# pragma warning(push)
59+
# pragma warning(disable: 4996)
60+
#endif
61+
62+
void
63+
rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
64+
{
65+
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
66+
}
67+
68+
void
69+
rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
70+
{
71+
rclcpp::spin_some(node_ptr->get_node_base_interface());
72+
}
73+
74+
// remove warning suppression
75+
#if !defined(_WIN32)
76+
# pragma GCC diagnostic pop
77+
#else // !defined(_WIN32)
78+
# pragma warning(pop)
79+
#endif

rclcpp/test/benchmark/benchmark_service.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -125,19 +125,21 @@ BENCHMARK_F(ServicePerformanceTest, async_send_response)(benchmark::State & stat
125125
auto service = node->create_service<test_msgs::srv::Empty>(empty_service_name, callback);
126126

127127
reset_heap_counters();
128+
rclcpp::executors::SingleThreadedExecutor executor;
129+
executor.add_node(node->get_node_base_interface());
128130
for (auto _ : state) {
129131
(void)_;
130132
state.PauseTiming();
131133
// Clear executor queue
132-
rclcpp::spin_some(node->get_node_base_interface());
134+
executor.spin_some();
133135

134136
auto request = std::make_shared<test_msgs::srv::Empty::Request>();
135137
auto future = empty_client->async_send_request(request);
136138
state.ResumeTiming();
137139
benchmark::DoNotOptimize(service);
138140
benchmark::ClobberMemory();
139141

140-
rclcpp::spin_until_future_complete(node->get_node_base_interface(), future);
142+
executor.spin_until_future_complete(future);
141143
}
142144
if (callback_count == 0) {
143145
state.SkipWithError("Service callback was not called");

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -804,27 +804,33 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr)
804804
}
805805

806806
// Check spin functions with non default context
807-
TEST(TestExecutors, testSpinWithNonDefaultContext)
807+
TYPED_TEST(TestExecutors, testSpinWithNonDefaultContext)
808808
{
809+
using ExecutorType = TypeParam;
810+
809811
auto non_default_context = std::make_shared<rclcpp::Context>();
810812
non_default_context->init(0, nullptr);
811813

812814
{
813815
auto node =
814816
std::make_unique<rclcpp::Node>("node", rclcpp::NodeOptions().context(non_default_context));
815817

816-
EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface()));
818+
rclcpp::ExecutorOptions options;
819+
options.context = non_default_context;
820+
ExecutorType executor(options);
821+
EXPECT_NO_THROW(executor.add_node(node->get_node_base_interface()));
822+
823+
EXPECT_NO_THROW(executor.spin_some());
817824

818-
EXPECT_NO_THROW(rclcpp::spin_all(node->get_node_base_interface(), 1s));
825+
EXPECT_NO_THROW(executor.spin_all(1s));
819826

820827
auto check_spin_until_future_complete = [&]() {
821828
std::promise<bool> promise;
822829
std::future<bool> future = promise.get_future();
823830
promise.set_value(true);
824831

825832
auto shared_future = future.share();
826-
auto ret = rclcpp::spin_until_future_complete(
827-
node->get_node_base_interface(), shared_future, 1s);
833+
auto ret = executor.spin_until_future_complete(shared_future, 1s);
828834
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
829835
};
830836
EXPECT_NO_THROW(check_spin_until_future_complete());

rclcpp/test/rclcpp/test_client_common.cpp

Lines changed: 18 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -112,10 +112,12 @@ class TestAllClientTypesWithServer : public ::testing::Test
112112
auto req_id = client->async_send_request(request, std::move(callback));
113113

114114
auto start = std::chrono::steady_clock::now();
115+
rclcpp::executors::SingleThreadedExecutor executor;
116+
executor.add_node(node);
115117
while (!received_response &&
116118
(std::chrono::steady_clock::now() - start) < timeout)
117119
{
118-
rclcpp::spin_some(node);
120+
executor.spin_some();
119121
}
120122

121123
if (!received_response) {
@@ -356,10 +358,12 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)
356358

357359
this->template async_send_request<ClientType, test_msgs::srv::Empty::Request>(client, request);
358360
auto start = std::chrono::steady_clock::now();
361+
rclcpp::executors::SingleThreadedExecutor executor;
362+
executor.add_node(server_node);
359363
while (server_requests_count == 0 &&
360364
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
361365
{
362-
rclcpp::spin_some(server_node);
366+
executor.spin_some();
363367
}
364368

365369
ASSERT_EQ(server_requests_count, 1u);
@@ -380,7 +384,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)
380384
while (server_requests_count == 1 &&
381385
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
382386
{
383-
rclcpp::spin_some(server_node);
387+
executor.spin_some();
384388
}
385389

386390
ASSERT_EQ(server_requests_count, 2u);
@@ -402,7 +406,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)
402406
while (server_requests_count < 5 &&
403407
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
404408
{
405-
rclcpp::spin_some(server_node);
409+
executor.spin_some();
406410
}
407411

408412
ASSERT_EQ(server_requests_count, 5u);
@@ -492,10 +496,12 @@ void client_async_send_request_callback_with_request(
492496
auto req_id = client->async_send_request(request, std::move(callback));
493497

494498
auto start = std::chrono::steady_clock::now();
499+
rclcpp::executors::SingleThreadedExecutor executor;
500+
executor.add_node(node);
495501
while (!received_response &&
496502
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(1))
497503
{
498-
rclcpp::spin_some(node);
504+
executor.spin_some();
499505
}
500506
EXPECT_TRUE(received_response);
501507
EXPECT_FALSE(client->remove_pending_request(req_id));
@@ -553,25 +559,29 @@ void client_qos_depth(rclcpp::Node::SharedPtr node)
553559
}
554560

555561
auto start = std::chrono::steady_clock::now();
562+
rclcpp::executors::SingleThreadedExecutor server_executor;
563+
server_executor.add_node(server_node);
556564
while ((server_cb_count_ < client_requests) &&
557565
(std::chrono::steady_clock::now() - start) < 2s)
558566
{
559-
rclcpp::spin_some(server_node);
567+
server_executor.spin_some();
560568
std::this_thread::sleep_for(2ms);
561569
}
562570

563571
EXPECT_GT(server_cb_count_, client_qos_profile.depth());
564572

565573
start = std::chrono::steady_clock::now();
574+
rclcpp::executors::SingleThreadedExecutor client_executor;
575+
client_executor.add_node(node);
566576
while ((client_cb_count_ < client_qos_profile.depth()) &&
567577
(std::chrono::steady_clock::now() - start) < 1s)
568578
{
569-
rclcpp::spin_some(node);
579+
client_executor.spin_some();
570580
}
571581

572582
// Spin an extra time to check if client QoS depth has been ignored,
573583
// so more client callbacks might be called than expected.
574-
rclcpp::spin_some(node);
584+
client_executor.spin_some();
575585

576586
EXPECT_EQ(client_cb_count_, client_qos_profile.depth());
577587
}

rclcpp/test/rclcpp/test_create_timer.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,9 @@ TEST(TestCreateTimer, timer_executes)
4242
timer->cancel();
4343
});
4444

45-
rclcpp::spin_some(node);
45+
rclcpp::executors::SingleThreadedExecutor executor;
46+
executor.add_node(node);
47+
executor.spin_some();
4648

4749
ASSERT_TRUE(got_callback);
4850
rclcpp::shutdown();

rclcpp/test/rclcpp/test_generic_pubsub.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -77,8 +77,10 @@ class RclcppGenericNodeFixture : public Test
7777
counter++;
7878
});
7979

80+
rclcpp::executors::SingleThreadedExecutor executor;
81+
executor.add_node(node_);
8082
while (counter < expected_recv_msg_count) {
81-
rclcpp::spin_some(node_);
83+
executor.spin_some();
8284
}
8385
return messages;
8486
}
@@ -106,11 +108,13 @@ class RclcppGenericNodeFixture : public Test
106108
{
107109
using clock = std::chrono::system_clock;
108110
auto start = clock::now();
111+
rclcpp::executors::SingleThreadedExecutor executor;
112+
executor.add_node(node_);
109113
while (!condition()) {
110114
if ((clock::now() - start) > timeout) {
111115
return false;
112116
}
113-
rclcpp::spin_some(node_);
117+
executor.spin_some();
114118
}
115119
return true;
116120
}

rclcpp/test/rclcpp/test_generic_service.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -372,16 +372,18 @@ TEST_F(TestGenericService, generic_service_qos_depth) {
372372
}
373373

374374
auto start = std::chrono::steady_clock::now();
375+
rclcpp::executors::SingleThreadedExecutor executor;
376+
executor.add_node(server_node);
375377
while ((server_cb_count_ < server_qos_profile.depth()) &&
376378
(std::chrono::steady_clock::now() - start) < 1s)
377379
{
378-
rclcpp::spin_some(server_node);
380+
executor.spin_some();
379381
std::this_thread::sleep_for(1ms);
380382
}
381383

382384
// Spin an extra time to check if server QoS depth has been ignored,
383385
// so more server responses might be processed than expected.
384-
rclcpp::spin_some(server_node);
386+
executor.spin_some();
385387

386388
EXPECT_EQ(server_cb_count_, server_qos_profile.depth());
387389
}

0 commit comments

Comments
 (0)