Skip to content

Commit

Permalink
fixup due to changes on rolling
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Apr 3, 2024
1 parent 8e7fdc2 commit 575573f
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ class SubscriptionIntraProcess

RCLCPP_PUBLIC
void
add_to_wait_set(rcl_wait_set_t * wait_set) override
add_to_wait_set(rcl_wait_set_t & wait_set) override
{
// This block is necessary when the guard condition wakes the wait set, but
// the intra process waitable was not handled before the wait set is waited
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/test/rclcpp/waitables/waitable_test_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,15 +61,15 @@ do_test_that_waitable_stays_ready_after_second_wait(
wait_set.add_waitable(waitable);

// not ready initially
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable is unexpectedly ready before waiting";

// not ready after a wait that timesout
{
auto wait_result = wait_set.wait(std::chrono::seconds(0));
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout)
<< "wait set did not timeout as expected";
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable is unexpectedly ready after waiting, but before making ready";
}

Expand All @@ -79,7 +79,7 @@ do_test_that_waitable_stays_ready_after_second_wait(
auto wait_result = wait_set.wait(wait_timeout);
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Ready)
<< "wait set was not ready after the waitable should have been made ready";
EXPECT_TRUE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_TRUE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable is unexpectedly not ready after making it ready and waiting";
}

Expand All @@ -89,12 +89,12 @@ do_test_that_waitable_stays_ready_after_second_wait(
if (expected_to_stay_ready) {
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Ready)
<< "wait set was not ready on a second wait on the waitable";
EXPECT_TRUE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_TRUE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable unexpectedly not ready after second wait";
} else {
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout)
<< "wait set did not time out after the waitable should have no longer been ready";
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable was ready after waiting a second time, which was not expected";
}
}
Expand All @@ -105,7 +105,7 @@ do_test_that_waitable_stays_ready_after_second_wait(
auto wait_result = wait_set.wait(std::chrono::seconds(0));
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout)
<< "wait set did not time out after the waitable should have no longer been ready";
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
<< "waitable was unexpectedly ready after a take_data and execute";
}
}
Expand Down

0 comments on commit 575573f

Please sign in to comment.