From 25e9c9ca5d9ddd054b698b94de66d06aa43aa1e3 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Sat, 17 May 2025 10:13:26 +0200 Subject: [PATCH 1/7] reorder events executor constructor arguments to have the first args match the other executors Signed-off-by: Alberto Soragna --- .../executors/events_executor/events_executor.hpp | 14 +++++++------- .../executors/events_executor/events_executor.cpp | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp b/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp index 163d8d2367..0d2daec1b2 100644 --- a/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp +++ b/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp @@ -64,17 +64,17 @@ class EventsExecutor : public rclcpp::Executor /// Default constructor. See the default constructor for Executor. /** + * \param[in] options Options used to configure the executor. * \param[in] events_queue The queue used to store events. * \param[in] execute_timers_separate_thread If true, timers are executed in a separate * thread. If false, timers are executed in the same thread as all other entities. - * \param[in] options Options used to configure the executor. */ - RCLCPP_PUBLIC - EventsExecutor( - rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique< - rclcpp::experimental::executors::SimpleEventsQueue>(), - bool execute_timers_separate_thread = false, - const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions()); + RCLCPP_PUBLIC + EventsExecutor( + const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions(), + rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique< + rclcpp::experimental::executors::SimpleEventsQueue>(), + bool execute_timers_separate_thread = false); /// Default destructor. RCLCPP_PUBLIC diff --git a/rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp b/rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp index 8f39c0fbb1..4a3f8f796f 100644 --- a/rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp +++ b/rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp @@ -25,9 +25,9 @@ using namespace std::chrono_literals; using rclcpp::experimental::executors::EventsExecutor; EventsExecutor::EventsExecutor( + const rclcpp::ExecutorOptions & options, rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue, - bool execute_timers_separate_thread, - const rclcpp::ExecutorOptions & options) + bool execute_timers_separate_thread) : rclcpp::Executor(options) { // Get ownership of the queue used to store events. From 20b2abb2edc01897d59eeb6d16415bbd0cde54c2 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Sat, 17 May 2025 10:13:44 +0200 Subject: [PATCH 2/7] deprecate rclcpp::spin_some and rclcpp::spin_all Signed-off-by: Alberto Soragna --- rclcpp/include/rclcpp/executors.hpp | 66 +++++++++++++++++-- rclcpp/src/rclcpp/executor.cpp | 7 ++ rclcpp/src/rclcpp/executors.cpp | 39 +++++++---- rclcpp/test/benchmark/benchmark_service.cpp | 6 +- .../test/rclcpp/executors/test_executors.cpp | 16 +++-- rclcpp/test/rclcpp/test_client_common.cpp | 26 +++++--- rclcpp/test/rclcpp/test_create_timer.cpp | 4 +- rclcpp/test/rclcpp/test_generic_pubsub.cpp | 8 ++- rclcpp/test/rclcpp/test_generic_service.cpp | 6 +- rclcpp/test/rclcpp/test_service.cpp | 7 +- .../rclcpp/test_service_introspection.cpp | 26 +++++--- .../test_subscription_content_filter.cpp | 4 +- rclcpp_action/test/test_server.cpp | 49 ++++++++++---- .../test/test_lifecycle_service_client.cpp | 32 +++++---- 14 files changed, 222 insertions(+), 74 deletions(-) diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index 1cd4d8666b..6e10a7ae98 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -28,24 +28,82 @@ namespace rclcpp { -/// Create a default single-threaded executor and execute all available work exhaustively. -/** \param[in] node_ptr Shared pointer to the node to spin. */ +/** + * @brief Create a default single-threaded executor and execute all available work exhaustively. + * @param node_ptr Shared pointer to the base interface of the node to spin. + * @param max_duration max duration to spin + * + * This method is deprecated because it can lead to very bad performance if used in a loop: + * each call will create a new executor and register the node, which is an expensive operation. + * It's recommended to always manually instantiate an executor and call the methods with + * the same name on it. + * For example: + * SingleThreadedExecutor executor; + * executor.add_node(node_ptr); + * executor.spin_all(max_duration); + * If you are using a non-default context, this should be passed to the executor's constructor. + */ +[[deprecated("use SingleThreadedExecutor::spin_all instead")]] RCLCPP_PUBLIC void spin_all( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::chrono::nanoseconds max_duration); +/** + * @brief Create a default single-threaded executor and execute all available work exhaustively. + * @param node_ptr Shared pointer to the node to spin. + * @param max_duration max duration to spin + * + * This method is deprecated because it can lead to very bad performance if used in a loop: + * each call will create a new executor and register the node, which is an expensive operation. + * It's recommended to always manually instantiate an executor and call the methods with + * the same name on it. + * For example: + * SingleThreadedExecutor executor; + * executor.add_node(node_ptr); + * executor.spin_all(max_duration); + * If you are using a non-default context, this should be passed to the executor's constructor. + */ +[[deprecated("use SingleThreadedExecutor::spin_all instead")]] RCLCPP_PUBLIC void spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration); -/// Create a default single-threaded executor and execute any immediately available work. -/** \param[in] node_ptr Shared pointer to the node to spin. */ +/** + * @brief Create a default single-threaded executor and execute any immediately available work. + * @param node_ptr Shared pointer to the base interface of the node to spin. + * + * This method is deprecated because it can lead to very bad performance if used in a loop: + * each call will create a new executor and register the node, which is an expensive operation. + * It's recommended to always manually instantiate an executor and call the methods with + * the same name on it. + * For example: + * SingleThreadedExecutor executor; + * executor.add_node(node_ptr); + * executor.spin_some(); + * If you are using a non-default context, this should be passed to the executor's constructor. + */ + [[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); +/** + * @brief Create a default single-threaded executor and execute any immediately available work. + * @param node_ptr Shared pointer to the node to spin. + * + * This method is deprecated because it can lead to very bad performance if used in a loop: + * each call will create a new executor and register the node, which is an expensive operation. + * It's recommended to always manually instantiate an executor and call the methods with + * the same name on it. + * For example: + * SingleThreadedExecutor executor; + * executor.add_node(node_ptr); + * executor.spin_some(); + * If you are using a non-default context, this should be passed to the executor's constructor. + */ + [[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void spin_some(rclcpp::Node::SharedPtr node_ptr); diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 70e2f69989..265b8a85d5 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -52,6 +52,7 @@ class rclcpp::ExecutorImplementation {}; Executor::Executor(const std::shared_ptr & context) : spinning(false), + context_(context), entities_need_rebuild_(true), collector_(nullptr), wait_set_({}, {}, {}, {}, {}, {}, context) @@ -186,6 +187,12 @@ Executor::add_callback_group( void Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify) { + if (node_ptr->get_context() != context_) + { + throw std::runtime_error( + "add_node() called with a node with a different context from this executor"); + } + this->collector_.add_node(node_ptr); try { diff --git a/rclcpp/src/rclcpp/executors.cpp b/rclcpp/src/rclcpp/executors.cpp index 94137d50bc..a40ba81440 100644 --- a/rclcpp/src/rclcpp/executors.cpp +++ b/rclcpp/src/rclcpp/executors.cpp @@ -25,12 +25,6 @@ rclcpp::spin_all( exec.spin_node_all(node_ptr, max_duration); } -void -rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration) -{ - rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration); -} - void rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) { @@ -40,12 +34,6 @@ rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr exec.spin_node_some(node_ptr); } -void -rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) -{ - rclcpp::spin_some(node_ptr->get_node_base_interface()); -} - void rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) { @@ -62,3 +50,30 @@ rclcpp::spin(rclcpp::Node::SharedPtr node_ptr) { rclcpp::spin(node_ptr->get_node_base_interface()); } + +#if !defined(_WIN32) +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#else // !defined(_WIN32) +# pragma warning(push) +# pragma warning(disable: 4996) +#endif + +void +rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration) +{ + rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration); +} + +void +rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) +{ + rclcpp::spin_some(node_ptr->get_node_base_interface()); +} + +// remove warning suppression +#if !defined(_WIN32) +# pragma GCC diagnostic pop +#else // !defined(_WIN32) +# pragma warning(pop) +#endif diff --git a/rclcpp/test/benchmark/benchmark_service.cpp b/rclcpp/test/benchmark/benchmark_service.cpp index a42723da90..4d00567da5 100644 --- a/rclcpp/test/benchmark/benchmark_service.cpp +++ b/rclcpp/test/benchmark/benchmark_service.cpp @@ -125,11 +125,13 @@ BENCHMARK_F(ServicePerformanceTest, async_send_response)(benchmark::State & stat auto service = node->create_service(empty_service_name, callback); reset_heap_counters(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node->get_node_base_interface()); for (auto _ : state) { (void)_; state.PauseTiming(); // Clear executor queue - rclcpp::spin_some(node->get_node_base_interface()); + executor.spin_some(); auto request = std::make_shared(); auto future = empty_client->async_send_request(request); @@ -137,7 +139,7 @@ BENCHMARK_F(ServicePerformanceTest, async_send_response)(benchmark::State & stat benchmark::DoNotOptimize(service); benchmark::ClobberMemory(); - rclcpp::spin_until_future_complete(node->get_node_base_interface(), future); + executor.spin_until_future_complete(future); } if (callback_count == 0) { state.SkipWithError("Service callback was not called"); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 2fdd576096..ffaa4df919 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -804,8 +804,10 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) } // Check spin functions with non default context -TEST(TestExecutors, testSpinWithNonDefaultContext) +TYPED_TEST(TestExecutors, testSpinWithNonDefaultContext) { + using ExecutorType = TypeParam; + auto non_default_context = std::make_shared(); non_default_context->init(0, nullptr); @@ -813,9 +815,14 @@ TEST(TestExecutors, testSpinWithNonDefaultContext) auto node = std::make_unique("node", rclcpp::NodeOptions().context(non_default_context)); - EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface())); + rclcpp::ExecutorOptions options; + options.context = non_default_context; + ExecutorType executor(options); + EXPECT_NO_THROW(executor.add_node(node->get_node_base_interface())); + + EXPECT_NO_THROW(executor.spin_some()); - EXPECT_NO_THROW(rclcpp::spin_all(node->get_node_base_interface(), 1s)); + EXPECT_NO_THROW(executor.spin_all(1s)); auto check_spin_until_future_complete = [&]() { std::promise promise; @@ -823,8 +830,7 @@ TEST(TestExecutors, testSpinWithNonDefaultContext) promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::spin_until_future_complete( - node->get_node_base_interface(), shared_future, 1s); + auto ret = executor.spin_until_future_complete(shared_future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); }; EXPECT_NO_THROW(check_spin_until_future_complete()); diff --git a/rclcpp/test/rclcpp/test_client_common.cpp b/rclcpp/test/rclcpp/test_client_common.cpp index 83b0232e94..1a45ae8884 100644 --- a/rclcpp/test/rclcpp/test_client_common.cpp +++ b/rclcpp/test/rclcpp/test_client_common.cpp @@ -112,10 +112,12 @@ class TestAllClientTypesWithServer : public ::testing::Test auto req_id = client->async_send_request(request, std::move(callback)); auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); while (!received_response && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } if (!received_response) { @@ -356,10 +358,12 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback) this->template async_send_request(client, request); auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(server_node); while (server_requests_count == 0 && (std::chrono::steady_clock::now() - start) < std::chrono::seconds(10)) { - rclcpp::spin_some(server_node); + executor.spin_some(); } ASSERT_EQ(server_requests_count, 1u); @@ -380,7 +384,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback) while (server_requests_count == 1 && (std::chrono::steady_clock::now() - start) < std::chrono::seconds(10)) { - rclcpp::spin_some(server_node); + executor.spin_some(); } ASSERT_EQ(server_requests_count, 2u); @@ -402,7 +406,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback) while (server_requests_count < 5 && (std::chrono::steady_clock::now() - start) < std::chrono::seconds(10)) { - rclcpp::spin_some(server_node); + executor.spin_some(); } ASSERT_EQ(server_requests_count, 5u); @@ -492,10 +496,12 @@ void client_async_send_request_callback_with_request( auto req_id = client->async_send_request(request, std::move(callback)); auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); while (!received_response && (std::chrono::steady_clock::now() - start) < std::chrono::seconds(1)) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_TRUE(received_response); EXPECT_FALSE(client->remove_pending_request(req_id)); @@ -553,25 +559,29 @@ void client_qos_depth(rclcpp::Node::SharedPtr node) } auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor server_executor; + server_executor.add_node(server_node); while ((server_cb_count_ < client_requests) && (std::chrono::steady_clock::now() - start) < 2s) { - rclcpp::spin_some(server_node); + server_executor.spin_some(); std::this_thread::sleep_for(2ms); } EXPECT_GT(server_cb_count_, client_qos_profile.depth()); start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor client_executor; + client_executor.add_node(node); while ((client_cb_count_ < client_qos_profile.depth()) && (std::chrono::steady_clock::now() - start) < 1s) { - rclcpp::spin_some(node); + client_executor.spin_some(); } // Spin an extra time to check if client QoS depth has been ignored, // so more client callbacks might be called than expected. - rclcpp::spin_some(node); + client_executor.spin_some(); EXPECT_EQ(client_cb_count_, client_qos_profile.depth()); } diff --git a/rclcpp/test/rclcpp/test_create_timer.cpp b/rclcpp/test/rclcpp/test_create_timer.cpp index c4dc1f7e61..9995c7136c 100644 --- a/rclcpp/test/rclcpp/test_create_timer.cpp +++ b/rclcpp/test/rclcpp/test_create_timer.cpp @@ -42,7 +42,9 @@ TEST(TestCreateTimer, timer_executes) timer->cancel(); }); - rclcpp::spin_some(node); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + executor.spin_some(); ASSERT_TRUE(got_callback); rclcpp::shutdown(); diff --git a/rclcpp/test/rclcpp/test_generic_pubsub.cpp b/rclcpp/test/rclcpp/test_generic_pubsub.cpp index 46dd397c37..9c788370eb 100644 --- a/rclcpp/test/rclcpp/test_generic_pubsub.cpp +++ b/rclcpp/test/rclcpp/test_generic_pubsub.cpp @@ -78,8 +78,10 @@ class RclcppGenericNodeFixture : public Test counter++; }); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node_); while (counter < expected_recv_msg_count) { - rclcpp::spin_some(node_); + executor.spin_some(); } return messages; } @@ -107,11 +109,13 @@ class RclcppGenericNodeFixture : public Test { using clock = std::chrono::system_clock; auto start = clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node_); while (!condition()) { if ((clock::now() - start) > timeout) { return false; } - rclcpp::spin_some(node_); + executor.spin_some(); } return true; } diff --git a/rclcpp/test/rclcpp/test_generic_service.cpp b/rclcpp/test/rclcpp/test_generic_service.cpp index dd75120c1b..5cbe11db05 100644 --- a/rclcpp/test/rclcpp/test_generic_service.cpp +++ b/rclcpp/test/rclcpp/test_generic_service.cpp @@ -372,16 +372,18 @@ TEST_F(TestGenericService, generic_service_qos_depth) { } auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(server_node); while ((server_cb_count_ < server_qos_profile.depth()) && (std::chrono::steady_clock::now() - start) < 1s) { - rclcpp::spin_some(server_node); + executor.spin_some(); std::this_thread::sleep_for(1ms); } // Spin an extra time to check if server QoS depth has been ignored, // so more server responses might be processed than expected. - rclcpp::spin_some(server_node); + executor.spin_some(); EXPECT_EQ(server_cb_count_, server_qos_profile.depth()); } diff --git a/rclcpp/test/rclcpp/test_service.cpp b/rclcpp/test/rclcpp/test_service.cpp index 1b7d89e9de..fabfc5ae6c 100644 --- a/rclcpp/test/rclcpp/test_service.cpp +++ b/rclcpp/test/rclcpp/test_service.cpp @@ -386,17 +386,20 @@ TEST_F(TestService, server_qos_depth) { std::this_thread::sleep_for(10ms); } + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(server_node); + auto start = std::chrono::steady_clock::now(); while ((server_cb_count_ < server_qos_profile.depth()) && (std::chrono::steady_clock::now() - start) < 1s) { - rclcpp::spin_some(server_node); + executor.spin_some(); std::this_thread::sleep_for(1ms); } // Spin an extra time to check if server QoS depth has been ignored, // so more server responses might be processed than expected. - rclcpp::spin_some(server_node); + executor.spin_some(); EXPECT_EQ(server_cb_count_, server_qos_profile.depth()); } diff --git a/rclcpp/test/rclcpp/test_service_introspection.cpp b/rclcpp/test/rclcpp/test_service_introspection.cpp index 306d76a005..2bdc4ab992 100644 --- a/rclcpp/test/rclcpp/test_service_introspection.cpp +++ b/rclcpp/test/rclcpp/test_service_introspection.cpp @@ -114,8 +114,10 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal) // wrap up work to get all the service_event messages auto start = std::chrono::steady_clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } std::map> event_map; @@ -174,6 +176,9 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) service->configure_introspection( node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_OFF); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + ASSERT_EQ(sub->get_publisher_count(), 0); auto request = std::make_shared(); @@ -185,7 +190,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) rclcpp::spin_until_future_complete(node, future, timeout)); auto start = std::chrono::steady_clock::now(); while ((std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 0U); @@ -209,7 +214,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 2 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 2U); @@ -233,7 +238,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 2 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 2U); @@ -257,7 +262,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 4U); } @@ -269,6 +274,9 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont service->configure_introspection( node->get_clock(), rclcpp::ServicesQoS(), RCL_SERVICE_INTROSPECTION_METADATA); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + // Wait for the introspection to attach to our subscription size_t tries = 1000; while (this->sub->get_publisher_count() < 2 && tries-- > 0) { @@ -285,7 +293,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont rclcpp::spin_until_future_complete(node, future, timeout)); auto start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 4U); for (const auto & event : events) { @@ -313,7 +321,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 4U); for (const auto & event : events) { @@ -353,7 +361,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 4U); for (const auto & event : events) { @@ -393,7 +401,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont rclcpp::spin_until_future_complete(node, future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { - rclcpp::spin_some(node); + executor.spin_some(); } EXPECT_EQ(events.size(), 4U); for (const auto & event : events) { diff --git a/rclcpp/test/rclcpp/test_subscription_content_filter.cpp b/rclcpp/test/rclcpp/test_subscription_content_filter.cpp index 95a1874d4e..7fa3507ff7 100644 --- a/rclcpp/test/rclcpp/test_subscription_content_filter.cpp +++ b/rclcpp/test/rclcpp/test_subscription_content_filter.cpp @@ -69,11 +69,13 @@ class TestContentFilterSubscription : public ::testing::Test { using clock = std::chrono::system_clock; auto start = clock::now(); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); while (!condition()) { if ((clock::now() - start) > timeout) { return false; } - rclcpp::spin_some(node); + executor.spin_some(); } return true; } diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index cc0aa015d1..6cb15b7391 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -518,9 +518,11 @@ TEST_F(TestServer, publish_status_accepted) // 10 seconds const size_t max_tries = 10 * 1000 / 100; + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); for (size_t retry = 0; retry < max_tries && received_msgs.size() != 1u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_LT(0u, received_msgs.size()); @@ -582,9 +584,11 @@ TEST_F(TestServer, publish_status_canceling) // 10 seconds const size_t max_tries = 10 * 1000 / 100; + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); for (size_t retry = 0; retry < max_tries && received_msgs.size() < 2u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_LT(0u, received_msgs.size()); @@ -640,10 +644,12 @@ TEST_F(TestServer, publish_status_canceled) received_handle->canceled(std::make_shared()); // 10 seconds + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); const size_t max_tries = 10 * 1000 / 100; for (size_t retry = 0; retry < max_tries && received_msgs.size() < 3u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_LT(0u, received_msgs.size()); @@ -697,10 +703,12 @@ TEST_F(TestServer, publish_status_succeeded) received_handle->succeed(std::make_shared()); // 10 seconds + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); const size_t max_tries = 10 * 1000 / 100; for (size_t retry = 0; retry < max_tries && received_msgs.size() < 2u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_LT(0u, received_msgs.size()); @@ -754,10 +762,12 @@ TEST_F(TestServer, publish_status_aborted) received_handle->abort(std::make_shared()); // 10 seconds + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); const size_t max_tries = 10 * 1000 / 100; for (size_t retry = 0; retry < max_tries && received_msgs.size() < 2u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_LT(0u, received_msgs.size()); @@ -814,10 +824,12 @@ TEST_F(TestServer, publish_feedback) received_handle->publish_feedback(sent_message); // 10 seconds + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); const size_t max_tries = 10 * 1000 / 100; for (size_t retry = 0; retry < max_tries && received_msgs.size() < 1u; ++retry) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node); + executor.spin_some(); } ASSERT_EQ(1u, received_msgs.size()); @@ -878,10 +890,13 @@ TEST_F(TestServer, get_result) result->sequence = {5, 8, 13, 21}; received_handle->succeed(result); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + executor.spin_until_future_complete(future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -891,13 +906,13 @@ TEST_F(TestServer, get_result) rclcpp::sleep_for(2 * result_timeout); // Allow for expiration to take place - rclcpp::spin_some(node); + executor.spin_some(); // Send and wait for another result request future = result_client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + executor.spin_until_future_complete(future)); response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_UNKNOWN, response->status); @@ -946,9 +961,12 @@ TEST_F(TestServer, get_result_deferred) request->goal_id.uuid = uuid; auto future = result_client->async_send_request(request); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + // Process request first rclcpp::sleep_for(std::chrono::milliseconds(10)); // Give a chance for the request to be served - rclcpp::spin_some(node); + executor.spin_some(); // Send a result auto result = std::make_shared(); @@ -958,7 +976,7 @@ TEST_F(TestServer, get_result_deferred) // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + executor.spin_until_future_complete(future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -1042,10 +1060,13 @@ class TestBasicServer : public TestServer result->sequence = {5, 8, 13, 21}; goal_handle_->succeed(result); + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node_); + // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node_, future)); + executor.spin_until_future_complete(future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -1055,13 +1076,13 @@ class TestBasicServer : public TestServer rclcpp::sleep_for(std::chrono::milliseconds(100)); // Allow for expiration to take place - rclcpp::spin_some(node_); + executor.spin_some(); // Send and wait for another result request future = result_client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node_, future)); + executor.spin_until_future_complete(future)); } protected: diff --git a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp index fc3f86e573..662dcb8bb5 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp @@ -240,14 +240,17 @@ class TestLifecycleServiceClient : public ::testing::Test void spin() { + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(lifecycle_node_->get_node_base_interface()); + executor.add_node(lifecycle_client_); + while (true) { { std::lock_guard guard(shutdown_mutex_); if (!rclcpp::ok()) { break; } - rclcpp::spin_some(lifecycle_node_->get_node_base_interface()); - rclcpp::spin_some(lifecycle_client_); + executor.spin_some(); } std::this_thread::sleep_for(std::chrono::milliseconds(10)); } @@ -455,34 +458,39 @@ TEST_F(TestLifecycleServiceClientRCLErrors, call_services_rcl_errors) { auto mock = mocking_utils::patch_and_return( "lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_is_initialized, RCL_RET_ERROR); + rclcpp::executors::SingleThreadedExecutor lifecycle_node_executor; + lifecycle_node_executor.add_node(lifecycle_node->get_node_base_interface()); + rclcpp::executors::SingleThreadedExecutor client_executor; + client_executor.add_node(lifecycle_client); + // on_change_state lifecycle_client->change_state( lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); - rclcpp::spin_some(lifecycle_client); + client_executor.spin_some(); EXPECT_THROW( - rclcpp::spin_some(lifecycle_node->get_node_base_interface()), std::runtime_error); + lifecycle_node_executore.spin_some(), std::runtime_error); // on_get_state lifecycle_client->get_state(); - rclcpp::spin_some(lifecycle_client); + client_executor.spin_some(); EXPECT_THROW( - rclcpp::spin_some(lifecycle_node->get_node_base_interface()), std::runtime_error); + lifecycle_node_executore.spin_some(), std::runtime_error); // on_get_avilable_states lifecycle_client->get_available_states(); - rclcpp::spin_some(lifecycle_client); + client_executor.spin_some(); EXPECT_THROW( - rclcpp::spin_some(lifecycle_node->get_node_base_interface()), std::runtime_error); + lifecycle_node_executore.spin_some(), std::runtime_error); // on_get_available_transitions lifecycle_client->get_available_transitions(); - rclcpp::spin_some(lifecycle_client); + client_executor.spin_some(); EXPECT_THROW( - rclcpp::spin_some(lifecycle_node->get_node_base_interface()), std::runtime_error); + lifecycle_node_executore.spin_some(), std::runtime_error); // on_get_transition_graph lifecycle_client->get_transition_graph(); - rclcpp::spin_some(lifecycle_client); + client_executor.spin_some(); EXPECT_THROW( - rclcpp::spin_some(lifecycle_node->get_node_base_interface()), std::runtime_error); + lifecycle_node_executore.spin_some(), std::runtime_error); } From c35493dc0b85f402624d3bba003de4a4c56330d0 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Sat, 7 Jun 2025 14:33:24 +0200 Subject: [PATCH 3/7] use rcpputils to ignore deprecation and remove deprecated APIs from comments Signed-off-by: Alberto Soragna --- rclcpp/include/rclcpp/rclcpp.hpp | 2 -- rclcpp/src/rclcpp/executors.cpp | 20 +++++--------------- 2 files changed, 5 insertions(+), 17 deletions(-) diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 50af3f1a89..8ad1e92414 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -68,8 +68,6 @@ * * - Executors (responsible for execution of callbacks through a blocking spin): * - rclcpp::spin() - * - rclcpp::spin_some() - * - rclcpp::spin_until_future_complete() * - rclcpp::executors::SingleThreadedExecutor * - rclcpp::executors::SingleThreadedExecutor::add_node() * - rclcpp::executors::SingleThreadedExecutor::spin() diff --git a/rclcpp/src/rclcpp/executors.cpp b/rclcpp/src/rclcpp/executors.cpp index a40ba81440..cd3180697f 100644 --- a/rclcpp/src/rclcpp/executors.cpp +++ b/rclcpp/src/rclcpp/executors.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "rclcpp/executors.hpp" +#include "rcpputils/compile_warnings.hpp" void rclcpp::spin_all( @@ -51,29 +52,18 @@ rclcpp::spin(rclcpp::Node::SharedPtr node_ptr) rclcpp::spin(node_ptr->get_node_base_interface()); } -#if !defined(_WIN32) -# pragma GCC diagnostic push -# pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#else // !defined(_WIN32) -# pragma warning(push) -# pragma warning(disable: 4996) -#endif - void rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration) { + RCPPUTILS_DEPRECATION_WARNING_OFF_START rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration); + RCPPUTILS_DEPRECATION_WARNING_OFF_STOP } void rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) { + RCPPUTILS_DEPRECATION_WARNING_OFF_START rclcpp::spin_some(node_ptr->get_node_base_interface()); + RCPPUTILS_DEPRECATION_WARNING_OFF_STOP } - -// remove warning suppression -#if !defined(_WIN32) -# pragma GCC diagnostic pop -#else // !defined(_WIN32) -# pragma warning(pop) -#endif From dabdfc370a279ae9ec2c6a16e506151ed027bb3c Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 20 Aug 2025 15:53:22 +0900 Subject: [PATCH 4/7] fix rclcpp_lifecycle build failures. Signed-off-by: Tomoya Fujita --- .../test/test_lifecycle_service_client.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp index 662dcb8bb5..7f073618b6 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp @@ -468,29 +468,29 @@ TEST_F(TestLifecycleServiceClientRCLErrors, call_services_rcl_errors) { lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE); client_executor.spin_some(); EXPECT_THROW( - lifecycle_node_executore.spin_some(), std::runtime_error); + lifecycle_node_executor.spin_some(), std::runtime_error); // on_get_state lifecycle_client->get_state(); client_executor.spin_some(); EXPECT_THROW( - lifecycle_node_executore.spin_some(), std::runtime_error); + lifecycle_node_executor.spin_some(), std::runtime_error); // on_get_avilable_states lifecycle_client->get_available_states(); client_executor.spin_some(); EXPECT_THROW( - lifecycle_node_executore.spin_some(), std::runtime_error); + lifecycle_node_executor.spin_some(), std::runtime_error); // on_get_available_transitions lifecycle_client->get_available_transitions(); client_executor.spin_some(); EXPECT_THROW( - lifecycle_node_executore.spin_some(), std::runtime_error); + lifecycle_node_executor.spin_some(), std::runtime_error); // on_get_transition_graph lifecycle_client->get_transition_graph(); client_executor.spin_some(); EXPECT_THROW( - lifecycle_node_executore.spin_some(), std::runtime_error); + lifecycle_node_executor.spin_some(), std::runtime_error); } From 70bbe8a83f30b7dcd9d5e99dfe6e9eb9443e4e36 Mon Sep 17 00:00:00 2001 From: Alejandro Hernandez Cordero Date: Thu, 21 Aug 2025 12:56:31 +0200 Subject: [PATCH 5/7] make linters happy Signed-off-by: Alejandro Hernandez Cordero --- rclcpp/include/rclcpp/executors.hpp | 4 ++-- .../executors/events_executor/events_executor.hpp | 10 +++++----- rclcpp/src/rclcpp/executor.cpp | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index 6e10a7ae98..3466b90b3d 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -84,7 +84,7 @@ spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration * executor.spin_some(); * If you are using a non-default context, this should be passed to the executor's constructor. */ - [[deprecated("use SingleThreadedExecutor::spin_some instead")]] +[[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); @@ -103,7 +103,7 @@ spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); * executor.spin_some(); * If you are using a non-default context, this should be passed to the executor's constructor. */ - [[deprecated("use SingleThreadedExecutor::spin_some instead")]] +[[deprecated("use SingleThreadedExecutor::spin_some instead")]] RCLCPP_PUBLIC void spin_some(rclcpp::Node::SharedPtr node_ptr); diff --git a/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp b/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp index 0d2daec1b2..aede14dbc9 100644 --- a/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp +++ b/rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor.hpp @@ -69,12 +69,12 @@ class EventsExecutor : public rclcpp::Executor * \param[in] execute_timers_separate_thread If true, timers are executed in a separate * thread. If false, timers are executed in the same thread as all other entities. */ - RCLCPP_PUBLIC - EventsExecutor( + RCLCPP_PUBLIC + EventsExecutor( const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions(), - rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique< - rclcpp::experimental::executors::SimpleEventsQueue>(), - bool execute_timers_separate_thread = false); + rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique< + rclcpp::experimental::executors::SimpleEventsQueue>(), + bool execute_timers_separate_thread = false); /// Default destructor. RCLCPP_PUBLIC diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 265b8a85d5..2f6bc54972 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include #include @@ -187,8 +188,7 @@ Executor::add_callback_group( void Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify) { - if (node_ptr->get_context() != context_) - { + if (node_ptr->get_context() != context_) { throw std::runtime_error( "add_node() called with a node with a different context from this executor"); } From 79d5fe9b75cbe291e3185b7ad769a9aaf6022158 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Fri, 22 Aug 2025 21:51:52 +0200 Subject: [PATCH 6/7] fix test_service_introspection Signed-off-by: Alberto Soragna --- .../rclcpp/test_service_introspection.cpp | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/rclcpp/test/rclcpp/test_service_introspection.cpp b/rclcpp/test/rclcpp/test_service_introspection.cpp index 2bdc4ab992..1055adb420 100644 --- a/rclcpp/test/rclcpp/test_service_introspection.cpp +++ b/rclcpp/test/rclcpp/test_service_introspection.cpp @@ -87,6 +87,9 @@ class TestServiceIntrospection : public ::testing::Test TEST_F(TestServiceIntrospection, service_introspection_nominal) { + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + auto request = std::make_shared(); request->set__bool_value(true); request->set__int64_value(42); @@ -106,7 +109,7 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal) auto future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); BasicTypes::Response::SharedPtr response = future.get(); ASSERT_EQ(response->bool_value, false); @@ -114,8 +117,6 @@ TEST_F(TestServiceIntrospection, service_introspection_nominal) // wrap up work to get all the service_event messages auto start = std::chrono::steady_clock::now(); - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(node); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); } @@ -187,7 +188,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) auto future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); auto start = std::chrono::steady_clock::now(); while ((std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -211,7 +212,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 2 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -235,7 +236,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 2 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -259,7 +260,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_events) future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -290,7 +291,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont auto future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); auto start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -318,7 +319,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -358,7 +359,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); @@ -398,7 +399,7 @@ TEST_F(TestServiceIntrospection, service_introspection_enable_disable_event_cont future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future, timeout)); + executor.spin_until_future_complete(future, timeout)); start = std::chrono::steady_clock::now(); while (events.size() < 4 && (std::chrono::steady_clock::now() - start) < timeout) { executor.spin_some(); From c8c7b06c1d499305dbe228306a2e8a1ff3714d28 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Sat, 23 Aug 2025 11:32:23 +0200 Subject: [PATCH 7/7] fix lifecycle unit-test Signed-off-by: Alberto Soragna --- .../test/test_lifecycle_service_client.cpp | 35 +++++++------------ 1 file changed, 12 insertions(+), 23 deletions(-) diff --git a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp index 7f073618b6..dfa2125478 100644 --- a/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp +++ b/rclcpp_lifecycle/test/test_lifecycle_service_client.cpp @@ -226,39 +226,28 @@ class TestLifecycleServiceClient : public ::testing::Test rclcpp::init(0, nullptr); lifecycle_node_ = std::make_shared(); lifecycle_client_ = std::make_shared("client"); - spinner_ = std::thread(&TestLifecycleServiceClient::spin, this); + + executor_ = std::make_shared(); + spinner_ = std::thread([this]() { + executor_->add_node(lifecycle_node_->get_node_base_interface()); + executor_->add_node(lifecycle_client_); + executor_->spin(); + }); } void TearDown() override { - { - std::lock_guard guard(shutdown_mutex_); - rclcpp::shutdown(); + while(!executor_->is_spinning()) { + std::this_thread::sleep_for(std::chrono::milliseconds(1)); } + executor_->cancel(); spinner_.join(); - } - - void spin() - { - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(lifecycle_node_->get_node_base_interface()); - executor.add_node(lifecycle_client_); - - while (true) { - { - std::lock_guard guard(shutdown_mutex_); - if (!rclcpp::ok()) { - break; - } - executor.spin_some(); - } - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } + rclcpp::shutdown(); } std::shared_ptr lifecycle_node_; std::shared_ptr lifecycle_client_; - std::mutex shutdown_mutex_; + std::shared_ptr executor_; std::thread spinner_; };