Skip to content

Commit dcdb56d

Browse files
MichaelOrlovmorlov-apexai
authored andcommitted
Address CI warnings about usage of deprecated rclcpp::spin_some(node)
- Use spin_some() from the rclcpp::executors::SingleThreadedExecutor directly. Signed-off-by: Michael Orlov <[email protected]>
1 parent 976b2dd commit dcdb56d

File tree

2 files changed

+21
-10
lines changed

2 files changed

+21
-10
lines changed

rclcpp/test/rclcpp/test_generic_pubsub.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
#include "rcl/graph.h"
3030

31+
#include "rclcpp/executors/single_threaded_executor.hpp"
3132
#include "rclcpp/generic_publisher.hpp"
3233
#include "rclcpp/generic_subscription.hpp"
3334
#include "rclcpp/rclcpp.hpp"
@@ -338,12 +339,15 @@ TEST_F(RclcppGenericNodeFixture, disable_enable_subscription_callbacks)
338339
};
339340
ASSERT_TRUE(wait_for(connected, 10s));
340341

342+
rclcpp::executors::SingleThreadedExecutor executor;
343+
executor.add_node(node_);
344+
341345
// Publish and verify callback is called
342346
publisher->publish(serialize_message<std::string, test_msgs::msg::Strings>("test1"));
343347

344348
auto start = std::chrono::steady_clock::now();
345349
while (callback_count.load() == 0 && std::chrono::steady_clock::now() - start < 30s) {
346-
rclcpp::spin_some(node_);
350+
executor.spin_some();
347351
std::this_thread::sleep_for(10ms);
348352
}
349353
EXPECT_EQ(1, callback_count.load());
@@ -357,7 +361,7 @@ TEST_F(RclcppGenericNodeFixture, disable_enable_subscription_callbacks)
357361
start = std::chrono::steady_clock::now();
358362
auto initial_count = callback_count.load();
359363
while (std::chrono::steady_clock::now() - start < 500ms) {
360-
rclcpp::spin_some(node_);
364+
executor.spin_some();
361365
std::this_thread::sleep_for(10ms);
362366
}
363367
EXPECT_EQ(initial_count, callback_count.load()); // Should not increase
@@ -370,7 +374,7 @@ TEST_F(RclcppGenericNodeFixture, disable_enable_subscription_callbacks)
370374

371375
start = std::chrono::steady_clock::now();
372376
while (callback_count.load() == initial_count && std::chrono::steady_clock::now() - start < 30s) {
373-
rclcpp::spin_some(node_);
377+
executor.spin_some();
374378
std::this_thread::sleep_for(10ms);
375379
}
376380
EXPECT_EQ(callback_count.load(), initial_count + 1);

rclcpp/test/rclcpp/test_subscription.cpp

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <vector>
2626

2727
#include "rclcpp/exceptions.hpp"
28+
#include "rclcpp/executors/single_threaded_executor.hpp"
2829
#include "rclcpp/rclcpp.hpp"
2930

3031
#include "../mocking_utils/patch.hpp"
@@ -692,12 +693,15 @@ TEST_F(TestSubscription, disable_enable_callbacks)
692693
pub_options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
693694
auto pub = node_->create_publisher<test_msgs::msg::Empty>(topic_name, 10U, pub_options);
694695

696+
rclcpp::executors::SingleThreadedExecutor executor;
697+
executor.add_node(node_);
698+
695699
// Wait for discovery
696700
auto start = std::chrono::steady_clock::now();
697701
while ((pub->get_subscription_count() == 0U || sub->get_publisher_count() == 0U) &&
698702
std::chrono::steady_clock::now() - start < 10s)
699703
{
700-
rclcpp::spin_some(node_);
704+
executor.spin_some();
701705
std::this_thread::sleep_for(10ms);
702706
}
703707

@@ -709,7 +713,7 @@ TEST_F(TestSubscription, disable_enable_callbacks)
709713

710714
start = std::chrono::steady_clock::now();
711715
while (callback_count.load() == 0 && std::chrono::steady_clock::now() - start < 30s) {
712-
rclcpp::spin_some(node_);
716+
executor.spin_some();
713717
std::this_thread::sleep_for(10ms);
714718
}
715719
EXPECT_EQ(1, callback_count.load());
@@ -726,7 +730,7 @@ TEST_F(TestSubscription, disable_enable_callbacks)
726730
start = std::chrono::steady_clock::now();
727731
auto initial_count = callback_count.load();
728732
while (std::chrono::steady_clock::now() - start < 500ms) {
729-
rclcpp::spin_some(node_);
733+
executor.spin_some();
730734
std::this_thread::sleep_for(10ms);
731735
}
732736
EXPECT_EQ(initial_count, callback_count.load()); // Should not increase
@@ -742,7 +746,7 @@ TEST_F(TestSubscription, disable_enable_callbacks)
742746

743747
start = std::chrono::steady_clock::now();
744748
while (callback_count.load() == initial_count && std::chrono::steady_clock::now() - start < 30s) {
745-
rclcpp::spin_some(node_);
749+
executor.spin_some();
746750
std::this_thread::sleep_for(10ms);
747751
}
748752
EXPECT_EQ(callback_count.load(), initial_count + 1);
@@ -761,6 +765,9 @@ TEST_F(TestSubscription, disable_enable_callbacks_intra_process)
761765
auto sub = node_->create_subscription<test_msgs::msg::Empty>(topic_name, 10U, callback);
762766
auto pub = node_->create_publisher<test_msgs::msg::Empty>(topic_name, 10U);
763767

768+
rclcpp::executors::SingleThreadedExecutor executor;
769+
executor.add_node(node_);
770+
764771
// Publish and verify callback is called
765772
{
766773
test_msgs::msg::Empty msg;
@@ -769,7 +776,7 @@ TEST_F(TestSubscription, disable_enable_callbacks_intra_process)
769776

770777
auto start = std::chrono::steady_clock::now();
771778
while (callback_count.load() == 0 && std::chrono::steady_clock::now() - start < 30s) {
772-
rclcpp::spin_some(node_);
779+
executor.spin_some();
773780
std::this_thread::sleep_for(10ms);
774781
}
775782
EXPECT_EQ(1, callback_count.load());
@@ -786,7 +793,7 @@ TEST_F(TestSubscription, disable_enable_callbacks_intra_process)
786793
start = std::chrono::steady_clock::now();
787794
auto initial_count = callback_count.load();
788795
while (std::chrono::steady_clock::now() - start < 500ms) {
789-
rclcpp::spin_some(node_);
796+
executor.spin_some();
790797
std::this_thread::sleep_for(10ms);
791798
}
792799
EXPECT_EQ(initial_count, callback_count.load());
@@ -802,7 +809,7 @@ TEST_F(TestSubscription, disable_enable_callbacks_intra_process)
802809

803810
start = std::chrono::steady_clock::now();
804811
while (callback_count.load() == initial_count && std::chrono::steady_clock::now() - start < 30s) {
805-
rclcpp::spin_some(node_);
812+
executor.spin_some();
806813
std::this_thread::sleep_for(10ms);
807814
}
808815
EXPECT_EQ(callback_count.load(), initial_count + 1);

0 commit comments

Comments
 (0)