Skip to content

Commit 59ff73b

Browse files
Replace deprecated spin_some in realtime_tools (#448)
1 parent e668fb5 commit 59ff73b

File tree

2 files changed

+21
-7
lines changed

2 files changed

+21
-7
lines changed

realtime_tools/test/realtime_publisher_tests.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,8 +88,11 @@ TEST(RealtimePublisher, rt_can_try_publish)
8888
auto sub = node->create_subscription<StringMsg>(
8989
"~/rt_publish", qos,
9090
std::bind(&StringCallback::callback, &str_callback, std::placeholders::_1));
91+
92+
rclcpp::executors::SingleThreadedExecutor exec;
93+
exec.add_node(node);
9194
for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.string_value.empty(); ++i) {
92-
rclcpp::spin_some(node);
95+
exec.spin_some();
9396
std::this_thread::sleep_for(DELAY);
9497
}
9598
EXPECT_STREQ(expected_msg, str_callback.msg_.string_value.c_str());

realtime_tools/test/realtime_server_goal_handle_tests.cpp

Lines changed: 17 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,10 @@ struct ActionServerCallbacks
7676

7777
bool wait_for_handle(rclcpp::Node::SharedPtr node)
7878
{
79+
rclcpp::executors::SingleThreadedExecutor executor;
80+
executor.add_node(node);
7981
for (size_t i = 0; i < ATTEMPTS; ++i) {
80-
rclcpp::spin_some(node);
82+
executor.spin_some();
8183
std::this_thread::sleep_for(DELAY);
8284
std::unique_lock<std::mutex> lock(mtx_);
8385
if (have_handle_) {
@@ -109,8 +111,10 @@ struct ActionClientCallbacks
109111

110112
bool wait_for_feedback(rclcpp::Node::SharedPtr node)
111113
{
114+
rclcpp::executors::SingleThreadedExecutor executor;
115+
executor.add_node(node);
112116
for (size_t i = 0; i < ATTEMPTS; ++i) {
113-
rclcpp::spin_some(node);
117+
executor.spin_some();
114118
std::this_thread::sleep_for(DELAY);
115119
std::unique_lock<std::mutex> lock(mtx_);
116120
if (have_feedback_) {
@@ -126,10 +130,15 @@ std::shared_ptr<ClientGoalHandle> send_goal(
126130
rclcpp::Node::SharedPtr node, std::shared_ptr<rclcpp_action::Client<Fibonacci>> ac,
127131
const std::string & /*server_name*/, ActionClientCallbacks & client_callbacks)
128132
{
129-
for (size_t i = 0; i < ATTEMPTS && !ac->action_server_is_ready(); ++i) {
130-
rclcpp::spin_some(node);
131-
std::this_thread::sleep_for(DELAY);
133+
{
134+
rclcpp::executors::SingleThreadedExecutor executor;
135+
executor.add_node(node);
136+
for (size_t i = 0; i < ATTEMPTS && !ac->action_server_is_ready(); ++i) {
137+
executor.spin_some();
138+
std::this_thread::sleep_for(DELAY);
139+
}
132140
}
141+
133142
if (ac->action_server_is_ready()) {
134143
Fibonacci::Goal goal;
135144
goal.order = 10;
@@ -229,7 +238,9 @@ TEST(RealtimeServerGoalHandle, set_canceled)
229238
if (callbacks.handle_->is_canceling()) {
230239
break;
231240
}
232-
rclcpp::spin_some(node);
241+
rclcpp::executors::SingleThreadedExecutor exec;
242+
exec.add_node(node);
243+
exec.spin_some();
233244
std::this_thread::sleep_for(DELAY);
234245
}
235246

0 commit comments

Comments
 (0)