Skip to content

Commit 575573f

Browse files
committed
fixup due to changes on rolling
Signed-off-by: William Woodall <[email protected]>
1 parent 8e7fdc2 commit 575573f

File tree

2 files changed

+7
-7
lines changed

2 files changed

+7
-7
lines changed

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,7 @@ class SubscriptionIntraProcess
103103

104104
RCLCPP_PUBLIC
105105
void
106-
add_to_wait_set(rcl_wait_set_t * wait_set) override
106+
add_to_wait_set(rcl_wait_set_t & wait_set) override
107107
{
108108
// This block is necessary when the guard condition wakes the wait set, but
109109
// the intra process waitable was not handled before the wait set is waited

rclcpp/test/rclcpp/waitables/waitable_test_helpers.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -61,15 +61,15 @@ do_test_that_waitable_stays_ready_after_second_wait(
6161
wait_set.add_waitable(waitable);
6262

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

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

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

@@ -89,12 +89,12 @@ do_test_that_waitable_stays_ready_after_second_wait(
8989
if (expected_to_stay_ready) {
9090
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Ready)
9191
<< "wait set was not ready on a second wait on the waitable";
92-
EXPECT_TRUE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
92+
EXPECT_TRUE(waitable->is_ready(wait_set.get_rcl_wait_set()))
9393
<< "waitable unexpectedly not ready after second wait";
9494
} else {
9595
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout)
9696
<< "wait set did not time out after the waitable should have no longer been ready";
97-
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
97+
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
9898
<< "waitable was ready after waiting a second time, which was not expected";
9999
}
100100
}
@@ -105,7 +105,7 @@ do_test_that_waitable_stays_ready_after_second_wait(
105105
auto wait_result = wait_set.wait(std::chrono::seconds(0));
106106
EXPECT_EQ(wait_result.kind(), rclcpp::WaitResultKind::Timeout)
107107
<< "wait set did not time out after the waitable should have no longer been ready";
108-
EXPECT_FALSE(waitable->is_ready(&wait_set.get_rcl_wait_set()))
108+
EXPECT_FALSE(waitable->is_ready(wait_set.get_rcl_wait_set()))
109109
<< "waitable was unexpectedly ready after a take_data and execute";
110110
}
111111
}

0 commit comments

Comments
 (0)