Skip to content

Commit dca8f45

Browse files
authored
Fix: Remove deprecated rclcpp::spin_some(node) (#1928)
1 parent 57b6ef6 commit dca8f45

File tree

5 files changed

+30
-25
lines changed

5 files changed

+30
-25
lines changed

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ class TestDiffDriveController : public ::testing::Test
130130
}
131131

132132
/// \brief wait for the subscriber and publisher to completely setup
133-
void waitForSetup()
133+
void waitForSetup(rclcpp::Executor & executor)
134134
{
135135
constexpr std::chrono::seconds TIMEOUT{2};
136136
auto clock = pub_node->get_clock();
@@ -141,7 +141,8 @@ class TestDiffDriveController : public ::testing::Test
141141
{
142142
FAIL();
143143
}
144-
rclcpp::spin_some(pub_node);
144+
executor.spin_some();
145+
std::this_thread::sleep_for(std::chrono::microseconds(10));
145146
}
146147
}
147148

@@ -532,7 +533,7 @@ TEST_F(TestDiffDriveController, test_speed_limiter)
532533
state = controller_->get_node()->activate();
533534
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
534535

535-
waitForSetup();
536+
waitForSetup(executor);
536537

537538
// send msg
538539
publish(0.0, 0.0);
@@ -773,7 +774,7 @@ TEST_F(TestDiffDriveController, cleanup)
773774
state = controller_->get_node()->activate();
774775
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
775776

776-
waitForSetup();
777+
waitForSetup(executor);
777778

778779
// send msg
779780
const double linear = 1.0;
@@ -894,7 +895,7 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
894895
state = controller_->get_node()->activate();
895896
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
896897

897-
waitForSetup();
898+
waitForSetup(executor);
898899

899900
// Reference interfaces should be NaN on initialization
900901
// (Note: reference_interfaces_ is protected, but this is
@@ -990,7 +991,7 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
990991
state = controller_->get_node()->activate();
991992
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
992993

993-
waitForSetup();
994+
waitForSetup(executor);
994995

995996
// Reference interfaces should be NaN on initialization
996997
for (const auto & interface : controller_->reference_interfaces_)
@@ -1094,7 +1095,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
10941095
state = controller_->get_node()->activate();
10951096
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
10961097

1097-
waitForSetup();
1098+
waitForSetup(executor);
10981099

10991100
// Reference interfaces should be NaN on initialization
11001101
// (Note: reference_interfaces_ is protected, but this is
@@ -1138,7 +1139,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
11381139
state = controller_->get_node()->activate();
11391140
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
11401141

1141-
waitForSetup();
1142+
waitForSetup(executor);
11421143

11431144
// (Note: reference_interfaces_ is protected, but this is
11441145
// a FRIEND_TEST so we can use it)
@@ -1192,7 +1193,7 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war
11921193
state = controller_->get_node()->activate();
11931194
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
11941195

1195-
waitForSetup();
1196+
waitForSetup(executor);
11961197

11971198
// published command message with zero timestamp sets the command interfaces to the correct values
11981199
const double linear = 1.0;

omni_wheel_drive_controller/test/test_omni_wheel_drive_controller.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -322,7 +322,7 @@ TEST_F(OmniWheelDriveControllerTest, chainable_controller_unchained_mode)
322322
state = controller_->get_node()->activate();
323323
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
324324

325-
waitForSetup();
325+
waitForSetup(executor);
326326

327327
// Reference interfaces should be NaN on initialization
328328
for (const auto & interface : controller_->reference_interfaces_)
@@ -410,7 +410,7 @@ TEST_F(OmniWheelDriveControllerTest, chainable_controller_chained_mode)
410410
state = controller_->get_node()->activate();
411411
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
412412

413-
waitForSetup();
413+
waitForSetup(executor);
414414

415415
// Reference interfaces should be NaN on initialization
416416
for (const auto & interface : controller_->reference_interfaces_)
@@ -478,7 +478,7 @@ TEST_F(OmniWheelDriveControllerTest, deactivate_then_activate)
478478
state = controller_->get_node()->activate();
479479
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
480480

481-
waitForSetup();
481+
waitForSetup(executor);
482482

483483
// Reference interfaces should be NaN on initialization
484484
for (const auto & interface : controller_->reference_interfaces_)
@@ -523,7 +523,7 @@ TEST_F(OmniWheelDriveControllerTest, deactivate_then_activate)
523523
state = controller_->get_node()->activate();
524524
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
525525

526-
waitForSetup();
526+
waitForSetup(executor);
527527

528528
for (const auto & interface : controller_->reference_interfaces_)
529529
{
@@ -572,7 +572,7 @@ TEST_F(OmniWheelDriveControllerTest, command_with_zero_timestamp_is_accepted_wit
572572
state = controller_->get_node()->activate();
573573
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
574574

575-
waitForSetup();
575+
waitForSetup(executor);
576576

577577
// published command message with zero timestamp sets the command interfaces to the correct values
578578
publish_twist_timestamped(rclcpp::Time(0, 0, RCL_ROS_TIME));
@@ -615,7 +615,7 @@ TEST_F(OmniWheelDriveControllerTest, 3_wheel_test)
615615
state = controller_->get_node()->activate();
616616
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
617617

618-
waitForSetup();
618+
waitForSetup(executor);
619619

620620
// Reference interfaces should be NaN on initialization
621621
for (const auto & interface : controller_->reference_interfaces_)
@@ -683,7 +683,7 @@ TEST_F(OmniWheelDriveControllerTest, 3_wheel_rot_test)
683683
state = controller_->get_node()->activate();
684684
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
685685

686-
waitForSetup();
686+
waitForSetup(executor);
687687

688688
// Reference interfaces should be NaN on initialization
689689
for (const auto & interface : controller_->reference_interfaces_)
@@ -751,7 +751,7 @@ TEST_F(OmniWheelDriveControllerTest, 4_wheel_rot_test)
751751
state = controller_->get_node()->activate();
752752
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
753753

754-
waitForSetup();
754+
waitForSetup(executor);
755755

756756
// Reference interfaces should be NaN on initialization
757757
for (const auto & interface : controller_->reference_interfaces_)
@@ -819,7 +819,7 @@ TEST_F(OmniWheelDriveControllerTest, 5_wheel_test)
819819
state = controller_->get_node()->activate();
820820
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
821821

822-
waitForSetup();
822+
waitForSetup(executor);
823823

824824
// Reference interfaces should be NaN on initialization
825825
for (const auto & interface : controller_->reference_interfaces_)

omni_wheel_drive_controller/test/test_omni_wheel_drive_controller.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,7 @@ class OmniWheelDriveControllerFixture : public ::testing::Test
139139
}
140140

141141
/// \brief wait for the subscriber and publisher to completely setup
142-
void waitForSetup()
142+
void waitForSetup(rclcpp::Executor & executor)
143143
{
144144
constexpr std::chrono::seconds TIMEOUT{2};
145145
auto clock = cmd_vel_publisher_node_->get_clock();
@@ -150,7 +150,8 @@ class OmniWheelDriveControllerFixture : public ::testing::Test
150150
{
151151
FAIL();
152152
}
153-
rclcpp::spin_some(cmd_vel_publisher_node_);
153+
executor.spin_some();
154+
std::this_thread::sleep_for(std::chrono::microseconds(10));
154155
}
155156
}
156157

parallel_gripper_controller/test/test_parallel_gripper_controller.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,11 @@ TEST_F(GripperControllerTest, ConfigureParamsSuccess)
8080
{
8181
this->SetUpController();
8282

83-
this->controller_->get_node()->set_parameter({"joint", "joint1"});
83+
rclcpp::executors::SingleThreadedExecutor executor;
84+
executor.add_node(controller_->get_node()->get_node_base_interface());
8485

85-
rclcpp::spin_some(this->controller_->get_node()->get_node_base_interface());
86+
this->controller_->get_node()->set_parameter({"joint", "joint1"});
87+
executor.spin_some();
8688

8789
// configure successful
8890
ASSERT_EQ(

tricycle_controller/test/test_tricycle_controller.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ class TestTricycleController : public ::testing::Test
120120
}
121121

122122
/// \brief wait for the subscriber and publisher to completely setup
123-
void waitForSetup()
123+
void waitForSetup(rclcpp::Executor & executor)
124124
{
125125
constexpr std::chrono::seconds TIMEOUT{2};
126126
auto clock = pub_node->get_clock();
@@ -131,7 +131,8 @@ class TestTricycleController : public ::testing::Test
131131
{
132132
FAIL();
133133
}
134-
rclcpp::spin_some(pub_node);
134+
executor.spin_some();
135+
std::this_thread::sleep_for(std::chrono::microseconds(10));
135136
}
136137
}
137138

@@ -268,7 +269,7 @@ TEST_F(TestTricycleController, cleanup)
268269
state = controller_->get_node()->activate();
269270
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
270271

271-
waitForSetup();
272+
waitForSetup(executor);
272273

273274
// send msg
274275
const double linear = 1.0;

0 commit comments

Comments
 (0)