Skip to content

Commit 42810ee

Browse files
authored
fix spin_some_max_duration unit-test for events-executor (#2465)
Signed-off-by: Alberto Soragna <[email protected]>
1 parent b50f9ab commit 42810ee

File tree

1 file changed

+12
-5
lines changed

1 file changed

+12
-5
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -352,8 +352,13 @@ class TestWaitable : public rclcpp::Waitable
352352
bool
353353
is_ready(rcl_wait_set_t * wait_set) override
354354
{
355-
(void)wait_set;
356-
return true;
355+
for (size_t i = 0; i < wait_set->size_of_guard_conditions; ++i) {
356+
auto rcl_guard_condition = wait_set->guard_conditions[i];
357+
if (&gc_.get_rcl_guard_condition() == rcl_guard_condition) {
358+
return true;
359+
}
360+
}
361+
return false;
357362
}
358363

359364
std::shared_ptr<void>
@@ -571,13 +576,12 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
571576
{
572577
using ExecutorType = TypeParam;
573578

574-
// TODO(wjwwood): The `StaticSingleThreadedExecutor` and the `EventsExecutor`
579+
// TODO(wjwwood): The `StaticSingleThreadedExecutor`
575580
// do not properly implement max_duration (it seems), so disable this test
576581
// for them in the meantime.
577582
// see: https://github.com/ros2/rclcpp/issues/2462
578583
if (
579-
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>() ||
580-
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
584+
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>())
581585
{
582586
GTEST_SKIP();
583587
}
@@ -610,6 +614,9 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
610614
my_waitable2->set_on_execute_callback(long_running_callback);
611615
waitable_interfaces->add_waitable(my_waitable2, isolated_callback_group);
612616

617+
my_waitable1->trigger();
618+
my_waitable2->trigger();
619+
613620
ExecutorType executor;
614621
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
615622

0 commit comments

Comments
 (0)