@@ -357,8 +357,13 @@ class TestWaitable : public rclcpp::Waitable
357357 bool
358358 is_ready (rcl_wait_set_t * wait_set) override
359359 {
360- (void )wait_set;
361- return true ;
360+ for (size_t i = 0 ; i < wait_set->size_of_guard_conditions ; ++i) {
361+ auto rcl_guard_condition = wait_set->guard_conditions [i];
362+ if (&gc_.get_rcl_guard_condition () == rcl_guard_condition) {
363+ return true ;
364+ }
365+ }
366+ return false ;
362367 }
363368
364369 std::shared_ptr<void >
@@ -578,13 +583,12 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
578583{
579584 using ExecutorType = TypeParam;
580585
581- // TODO(wjwwood): The `StaticSingleThreadedExecutor` and the `EventsExecutor`
586+ // TODO(wjwwood): The `StaticSingleThreadedExecutor`
582587 // do not properly implement max_duration (it seems), so disable this test
583588 // for them in the meantime.
584589 // see: https://github.com/ros2/rclcpp/issues/2462
585590 if (
586- std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>() ||
587- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
591+ std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>())
588592 {
589593 GTEST_SKIP ();
590594 }
@@ -617,6 +621,9 @@ TYPED_TEST(TestExecutors, spin_some_max_duration)
617621 my_waitable2->set_on_execute_callback (long_running_callback);
618622 waitable_interfaces->add_waitable (my_waitable2, isolated_callback_group);
619623
624+ my_waitable1->trigger ();
625+ my_waitable2->trigger ();
626+
620627 ExecutorType executor;
621628 executor.add_callback_group (isolated_callback_group, this ->node ->get_node_base_interface ());
622629
0 commit comments