@@ -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