Skip to content

Commit 18c4b12

Browse files
Replace deprecated rclcpp::spin_some() (#541)
1 parent d12a587 commit 18c4b12

File tree

2 files changed

+33
-13
lines changed

2 files changed

+33
-13
lines changed

control_toolbox/test/pid_ros_parameters_tests.cpp

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -240,6 +240,9 @@ TEST(PidParametersTest, SetParametersTest)
240240
{
241241
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("pid_parameters_test");
242242

243+
rclcpp::executors::SingleThreadedExecutor executor;
244+
executor.add_node(node);
245+
243246
TestablePidROS pid(node, "", "", false);
244247

245248
const double P = 1.0;
@@ -295,8 +298,7 @@ TEST(PidParametersTest, SetParametersTest)
295298
set_result = node->set_parameter(rclcpp::Parameter("activate_state_publisher", true)));
296299
ASSERT_TRUE(set_result.successful);
297300

298-
// process callbacks
299-
rclcpp::spin_some(node->get_node_base_interface());
301+
executor.spin_some();
300302

301303
// check gains were set using the parameters
302304
control_toolbox::Pid::Gains gains = pid.get_gains();
@@ -315,6 +317,9 @@ TEST(PidParametersTest, SetBadParametersTest)
315317
{
316318
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("pid_parameters_test");
317319

320+
rclcpp::executors::SingleThreadedExecutor executor;
321+
executor.add_node(node);
322+
318323
TestablePidROS pid(node, "", "", false);
319324

320325
const double P = 1.0;
@@ -370,7 +375,7 @@ TEST(PidParametersTest, SetBadParametersTest)
370375
ASSERT_TRUE(set_result.successful);
371376

372377
// process callbacks
373-
rclcpp::spin_some(node->get_node_base_interface());
378+
executor.spin_some();
374379

375380
// check gains were NOT set using the parameters but the u_max and u_min
376381
// were set to infinity as saturation is false
@@ -393,7 +398,7 @@ TEST(PidParametersTest, SetBadParametersTest)
393398
ASSERT_TRUE(set_result.successful);
394399

395400
// process callbacks
396-
rclcpp::spin_some(node->get_node_base_interface());
401+
executor.spin_some();
397402

398403
// Setting good gains doesn't help, as the saturation is still false
399404
gains = pid.get_gains();
@@ -412,7 +417,7 @@ TEST(PidParametersTest, SetBadParametersTest)
412417
ASSERT_TRUE(set_result.successful);
413418

414419
// process callbacks
415-
rclcpp::spin_some(node->get_node_base_interface());
420+
executor.spin_some();
416421

417422
// check gains were NOT set using the parameters
418423
control_toolbox::Pid::Gains updated_gains = pid.get_gains();

control_toolbox/test/pid_ros_publisher_tests.cpp

Lines changed: 23 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,9 @@ TEST(PidPublisherTest, PublishTest)
3838

3939
auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");
4040

41+
rclcpp::executors::SingleThreadedExecutor executor;
42+
executor.add_node(node);
43+
4144
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", true);
4245

4346
AntiWindupStrategy antiwindup_strat;
@@ -66,7 +69,7 @@ TEST(PidPublisherTest, PublishTest)
6669
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
6770
{
6871
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
69-
rclcpp::spin_some(node);
72+
executor.spin_some();
7073
std::this_thread::sleep_for(DELAY);
7174
}
7275

@@ -82,6 +85,9 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
8285

8386
auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");
8487

88+
rclcpp::executors::SingleThreadedExecutor executor;
89+
executor.add_node(node);
90+
8591
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", false);
8692

8793
AntiWindupStrategy antiwindup_strat;
@@ -110,7 +116,7 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
110116
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
111117
{
112118
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
113-
rclcpp::spin_some(node);
119+
executor.spin_some();
114120
std::this_thread::sleep_for(DELAY);
115121
}
116122
ASSERT_FALSE(callback_called);
@@ -126,7 +132,7 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
126132
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
127133
{
128134
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
129-
rclcpp::spin_some(node);
135+
executor.spin_some();
130136
std::this_thread::sleep_for(DELAY);
131137
}
132138
ASSERT_TRUE(callback_called);
@@ -135,15 +141,15 @@ TEST(PidPublisherTest, PublishTest_start_deactivated)
135141
ASSERT_NO_THROW(
136142
set_result = node->set_parameter(rclcpp::Parameter("activate_state_publisher", false)));
137143
ASSERT_TRUE(set_result.successful);
138-
rclcpp::spin_some(node); // process callbacks to ensure that no further messages are received
144+
executor.spin_some(); // process callbacks to ensure that no further messages are received
139145
callback_called = false;
140146
last_state_msg.reset();
141147

142148
// wait for callback
143149
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
144150
{
145151
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
146-
rclcpp::spin_some(node);
152+
executor.spin_some();
147153
std::this_thread::sleep_for(DELAY);
148154
}
149155
ASSERT_FALSE(callback_called);
@@ -157,6 +163,9 @@ TEST(PidPublisherTest, PublishTest_prefix)
157163

158164
auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");
159165

166+
rclcpp::executors::SingleThreadedExecutor executor;
167+
executor.add_node(node);
168+
160169
// test with a prefix for the topic without trailing / (should be auto-added)
161170
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "global", true);
162171

@@ -186,7 +195,7 @@ TEST(PidPublisherTest, PublishTest_prefix)
186195
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
187196
{
188197
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
189-
rclcpp::spin_some(node);
198+
executor.spin_some();
190199
std::this_thread::sleep_for(DELAY);
191200
}
192201

@@ -202,6 +211,9 @@ TEST(PidPublisherTest, PublishTest_local_prefix)
202211

203212
auto node = std::make_shared<rclcpp::Node>("pid_publisher_test");
204213

214+
rclcpp::executors::SingleThreadedExecutor executor;
215+
executor.add_node(node);
216+
205217
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "~/local/", true);
206218

207219
AntiWindupStrategy antiwindup_strat;
@@ -230,7 +242,7 @@ TEST(PidPublisherTest, PublishTest_local_prefix)
230242
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
231243
{
232244
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
233-
rclcpp::spin_some(node);
245+
executor.spin_some();
234246
std::this_thread::sleep_for(DELAY);
235247
}
236248

@@ -302,6 +314,9 @@ TEST(PidPublisherTest, PublishTestLifecycle)
302314

303315
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("pid_publisher_test");
304316

317+
rclcpp::executors::SingleThreadedExecutor executor;
318+
executor.add_node(node->get_node_base_interface());
319+
305320
control_toolbox::PidROS pid_ros(node, "", "", true);
306321

307322
auto state_pub_lifecycle_ =
@@ -334,7 +349,7 @@ TEST(PidPublisherTest, PublishTestLifecycle)
334349
for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i)
335350
{
336351
pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0));
337-
rclcpp::spin_some(node->get_node_base_interface());
352+
executor.spin_some();
338353
std::this_thread::sleep_for(DELAY);
339354
}
340355
ASSERT_TRUE(callback_called);

0 commit comments

Comments
 (0)