Skip to content

Commit 8c68c71

Browse files
wjwwoodjmachowinski
authored andcommitted
use futures to make the test rebust to spurious spins
Signed-off-by: William Woodall <[email protected]>
1 parent a4ff2fe commit 8c68c71

File tree

1 file changed

+34
-3
lines changed

1 file changed

+34
-3
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 34 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -454,6 +454,14 @@ class TestWaitable : public rclcpp::Waitable
454454
(void) data;
455455
count_++;
456456
std::this_thread::sleep_for(3ms);
457+
try {
458+
std::lock_guard<std::mutex> lock(execute_promise_mutex_);
459+
execute_promise_.set_value();
460+
} catch (const std::future_error & future_error) {
461+
if (future_error.code() != std::future_errc::promise_already_satisfied) {
462+
throw;
463+
}
464+
}
457465
}
458466

459467
void
@@ -480,8 +488,18 @@ class TestWaitable : public rclcpp::Waitable
480488
return count_;
481489
}
482490

491+
std::future<void>
492+
reset_execute_promise_and_get_future()
493+
{
494+
std::lock_guard<std::mutex> lock(execute_promise_mutex_);
495+
execute_promise_ = std::promise<void>();
496+
return execute_promise_.get_future();
497+
}
498+
483499
private:
484500
bool is_ready_called_before_take_data = false;
501+
std::promise<void> execute_promise_;
502+
std::mutex execute_promise_mutex_;
485503
size_t count_ = 0;
486504
rclcpp::GuardCondition gc_;
487505
};
@@ -670,6 +688,7 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
670688
rclcpp::CallbackGroupType::MutuallyExclusive,
671689
false);
672690

691+
std::chrono::seconds max_spin_duration(2);
673692
auto waitable_interfaces = node->get_node_waitables_interface();
674693
auto my_waitable = std::make_shared<TestWaitable>();
675694
auto my_waitable2 = std::make_shared<TestWaitable>();
@@ -680,7 +699,10 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
680699
my_waitable->trigger();
681700
my_waitable2->trigger();
682701

683-
executor.spin_once(std::chrono::milliseconds(10));
702+
{
703+
auto my_waitable_execute_future = my_waitable->reset_execute_promise_and_get_future();
704+
executor.spin_until_future_complete(my_waitable_execute_future, max_spin_duration);
705+
}
684706

685707
EXPECT_EQ(1u, my_waitable->get_count());
686708
EXPECT_EQ(0u, my_waitable2->get_count());
@@ -690,7 +712,13 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
690712
callback_group->can_be_taken_from().exchange(false);
691713

692714
// now there should be no ready event
693-
executor.spin_once(std::chrono::milliseconds(10));
715+
{
716+
auto my_waitable2_execute_future = my_waitable2->reset_execute_promise_and_get_future();
717+
auto future_code = executor.spin_until_future_complete(
718+
my_waitable2_execute_future,
719+
std::chrono::milliseconds(100)); // expected to timeout
720+
EXPECT_EQ(future_code, rclcpp::FutureReturnCode::TIMEOUT);
721+
}
694722

695723
EXPECT_EQ(1u, my_waitable->get_count());
696724
EXPECT_EQ(0u, my_waitable2->get_count());
@@ -699,7 +727,10 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
699727
callback_group->can_be_taken_from().exchange(true);
700728

701729
// now the second waitable should get processed
702-
executor.spin_once(std::chrono::milliseconds(10));
730+
{
731+
auto my_waitable2_execute_future = my_waitable2->reset_execute_promise_and_get_future();
732+
executor.spin_until_future_complete(my_waitable2_execute_future, max_spin_duration);
733+
}
703734

704735
EXPECT_EQ(1u, my_waitable->get_count());
705736
EXPECT_EQ(1u, my_waitable2->get_count());

0 commit comments

Comments
 (0)