From 42810ee3be16621208e2439cd6257a584d827759 Mon Sep 17 00:00:00 2001 From: Alberto Soragna Date: Tue, 26 Mar 2024 06:34:28 -0700 Subject: [PATCH] fix spin_some_max_duration unit-test for events-executor (#2465) Signed-off-by: Alberto Soragna --- rclcpp/test/rclcpp/executors/test_executors.cpp | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 87ed9350dd..da4b087607 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -352,8 +352,13 @@ class TestWaitable : public rclcpp::Waitable bool is_ready(rcl_wait_set_t * wait_set) override { - (void)wait_set; - return true; + for (size_t i = 0; i < wait_set->size_of_guard_conditions; ++i) { + auto rcl_guard_condition = wait_set->guard_conditions[i]; + if (&gc_.get_rcl_guard_condition() == rcl_guard_condition) { + return true; + } + } + return false; } std::shared_ptr @@ -571,13 +576,12 @@ TYPED_TEST(TestExecutors, spin_some_max_duration) { using ExecutorType = TypeParam; - // TODO(wjwwood): The `StaticSingleThreadedExecutor` and the `EventsExecutor` + // TODO(wjwwood): The `StaticSingleThreadedExecutor` // do not properly implement max_duration (it seems), so disable this test // for them in the meantime. // see: https://github.com/ros2/rclcpp/issues/2462 if ( - std::is_same() || - std::is_same()) + std::is_same()) { GTEST_SKIP(); } @@ -610,6 +614,9 @@ TYPED_TEST(TestExecutors, spin_some_max_duration) my_waitable2->set_on_execute_callback(long_running_callback); waitable_interfaces->add_waitable(my_waitable2, isolated_callback_group); + my_waitable1->trigger(); + my_waitable2->trigger(); + ExecutorType executor; executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());