Skip to content

Commit

Permalink
fix spin_some_max_duration unit-test for events-executor (#2465)
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Soragna <[email protected]>
  • Loading branch information
alsora authored Mar 26, 2024
1 parent b50f9ab commit 42810ee
Showing 1 changed file with 12 additions and 5 deletions.
17 changes: 12 additions & 5 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<void>
Expand Down Expand Up @@ -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<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>() ||
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>())
{
GTEST_SKIP();
}
Expand Down Expand Up @@ -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());

Expand Down

0 comments on commit 42810ee

Please sign in to comment.