Skip to content

Commit 4409e77

Browse files
authored
[CM] Use explicit constants in controller tests. (#1356) (#1359)
1 parent 03b603e commit 4409e77

File tree

1 file changed

+32
-32
lines changed

1 file changed

+32
-32
lines changed

controller_manager/test/test_load_controller.cpp

Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,8 @@
2828
using test_controller::TEST_CONTROLLER_CLASS_NAME;
2929
using ::testing::_;
3030
using ::testing::Return;
31-
const auto controller_name1 = "test_controller1";
32-
const auto controller_name2 = "test_controller2";
31+
const auto CONTROLLER_NAME_1 = "test_controller1";
32+
const auto CONTROLLER_NAME_2 = "test_controller2";
3333
using strvec = std::vector<std::string>;
3434

3535
class TestLoadController : public ControllerManagerFixture<controller_manager::ControllerManager>
@@ -53,7 +53,7 @@ TEST_F(TestLoadController, load_controller_failed_init)
5353
TEST_F(TestLoadController, configuring_non_loaded_controller_fails)
5454
{
5555
// try configure non-loaded controller
56-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::ERROR);
56+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::ERROR);
5757
}
5858

5959
TEST_F(TestLoadController, can_set_and_get_non_default_update_rate)
@@ -82,7 +82,7 @@ class TestLoadedController : public TestLoadController
8282
{
8383
TestLoadController::SetUp();
8484

85-
controller_if = cm_->load_controller(controller_name1, TEST_CONTROLLER_CLASS_NAME);
85+
controller_if = cm_->load_controller(CONTROLLER_NAME_1, TEST_CONTROLLER_CLASS_NAME);
8686
ASSERT_NE(controller_if, nullptr);
8787
}
8888

@@ -93,7 +93,7 @@ class TestLoadedController : public TestLoadController
9393
controller_interface::return_type::OK)
9494
{
9595
switch_test_controllers(
96-
strvec{controller_name1}, strvec{}, strictness, expected_future_status,
96+
strvec{CONTROLLER_NAME_1}, strvec{}, strictness, expected_future_status,
9797
expected_interface_status);
9898
}
9999

@@ -104,7 +104,7 @@ class TestLoadedController : public TestLoadController
104104
controller_interface::return_type::OK)
105105
{
106106
switch_test_controllers(
107-
strvec{}, strvec{controller_name1}, strictness, expected_future_status,
107+
strvec{}, strvec{CONTROLLER_NAME_1}, strictness, expected_future_status,
108108
expected_interface_status);
109109
}
110110
};
@@ -121,15 +121,15 @@ TEST_P(TestLoadedControllerParametrized, load_and_configure_one_known_controller
121121
EXPECT_EQ(
122122
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, controller_if->get_state().id());
123123

124-
cm_->configure_controller(controller_name1);
124+
cm_->configure_controller(CONTROLLER_NAME_1);
125125
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if->get_state().id());
126126
}
127127

128128
TEST_P(TestLoadedControllerParametrized, can_start_configured_controller)
129129
{
130130
const auto test_param = GetParam();
131131

132-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
132+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
133133
start_test_controller(test_param.strictness);
134134
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if->get_state().id());
135135
}
@@ -138,7 +138,7 @@ TEST_P(TestLoadedControllerParametrized, can_stop_active_controller)
138138
{
139139
const auto test_param = GetParam();
140140

141-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
141+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
142142

143143
start_test_controller(test_param.strictness);
144144

@@ -164,7 +164,7 @@ TEST_P(TestLoadedControllerParametrized, starting_and_stopping_a_controller)
164164
// Activate configured controller
165165
{
166166
ControllerManagerRunner cm_runner(this);
167-
cm_->configure_controller(controller_name1);
167+
cm_->configure_controller(CONTROLLER_NAME_1);
168168
}
169169
start_test_controller(test_param.strictness);
170170
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if->get_state().id());
@@ -180,11 +180,11 @@ TEST_P(TestLoadedControllerParametrized, can_not_configure_active_controller)
180180
{
181181
const auto test_param = GetParam();
182182

183-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
183+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
184184
start_test_controller(test_param.strictness);
185185

186186
// Can not configure active controller
187-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::ERROR);
187+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::ERROR);
188188
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if->get_state().id());
189189
}
190190

@@ -205,15 +205,15 @@ TEST_P(TestLoadedControllerParametrized, can_not_start_finalized_controller)
205205
test_param.strictness, std::future_status::ready, test_param.expected_return);
206206

207207
// Can not configure finalize controller
208-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::ERROR);
208+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::ERROR);
209209
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, controller_if->get_state().id());
210210
}
211211

212212
TEST_P(TestLoadedControllerParametrized, inactive_controller_cannot_be_cleaned_up)
213213
{
214214
const auto test_param = GetParam();
215215

216-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
216+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
217217

218218
start_test_controller(test_param.strictness);
219219

@@ -227,7 +227,7 @@ TEST_P(TestLoadedControllerParametrized, inactive_controller_cannot_be_cleaned_u
227227
test_controller->cleanup_calls = &cleanup_calls;
228228
// Configure from inactive state: controller can no be cleaned-up
229229
test_controller->simulate_cleanup_failure = true;
230-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::ERROR);
230+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::ERROR);
231231
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if->get_state().id());
232232
EXPECT_EQ(0u, cleanup_calls);
233233
}
@@ -236,7 +236,7 @@ TEST_P(TestLoadedControllerParametrized, inactive_controller_cannot_be_configure
236236
{
237237
const auto test_param = GetParam();
238238

239-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
239+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
240240

241241
start_test_controller(test_param.strictness);
242242

@@ -251,7 +251,7 @@ TEST_P(TestLoadedControllerParametrized, inactive_controller_cannot_be_configure
251251
test_controller->simulate_cleanup_failure = false;
252252
{
253253
ControllerManagerRunner cm_runner(this);
254-
EXPECT_EQ(cm_->configure_controller(controller_name1), controller_interface::return_type::OK);
254+
EXPECT_EQ(cm_->configure_controller(CONTROLLER_NAME_1), controller_interface::return_type::OK);
255255
}
256256
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if->get_state().id());
257257
EXPECT_EQ(1u, cleanup_calls);
@@ -270,8 +270,8 @@ class SwitchTest
270270
const auto UNSPECIFIED = 0;
271271
const auto EMPTY_STR_VEC = strvec{};
272272
const auto NONEXISTENT_CONTROLLER = strvec{"nonexistent_controller"};
273-
const auto VALID_CONTROLLER = strvec{controller_name1};
274-
const auto VALID_PLUS_NONEXISTENT_CONTROLLERS = strvec{controller_name1, "nonexistent_controller"};
273+
const auto VALID_CONTROLLER = strvec{CONTROLLER_NAME_1};
274+
const auto VALID_PLUS_NONEXISTENT_CONTROLLERS = strvec{CONTROLLER_NAME_1, "nonexistent_controller"};
275275

276276
TEST_P(SwitchTest, EmptyListOrNonExistentTest)
277277
{
@@ -375,10 +375,10 @@ class TestTwoLoadedControllers : public TestLoadController,
375375
void SetUp() override
376376
{
377377
TestLoadController::SetUp();
378-
controller_if1 = cm_->load_controller(controller_name1, TEST_CONTROLLER_CLASS_NAME);
378+
controller_if1 = cm_->load_controller(CONTROLLER_NAME_1, TEST_CONTROLLER_CLASS_NAME);
379379
ASSERT_NE(controller_if1, nullptr);
380380
EXPECT_EQ(1u, cm_->get_loaded_controllers().size());
381-
controller_if2 = cm_->load_controller(controller_name2, TEST_CONTROLLER_CLASS_NAME);
381+
controller_if2 = cm_->load_controller(CONTROLLER_NAME_2, TEST_CONTROLLER_CLASS_NAME);
382382
ASSERT_NE(controller_if2, nullptr);
383383
EXPECT_EQ(2u, cm_->get_loaded_controllers().size());
384384
ASSERT_EQ(
@@ -390,22 +390,22 @@ class TestTwoLoadedControllers : public TestLoadController,
390390

391391
TEST_F(TestTwoLoadedControllers, load_and_configure_two_known_controllers)
392392
{
393-
cm_->configure_controller(controller_name1);
393+
cm_->configure_controller(CONTROLLER_NAME_1);
394394
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if1->get_state().id());
395395

396-
cm_->configure_controller(controller_name2);
396+
cm_->configure_controller(CONTROLLER_NAME_2);
397397
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if2->get_state().id());
398398
}
399399

400400
TEST_P(TestTwoLoadedControllers, switch_multiple_controllers)
401401
{
402402
const auto test_param = GetParam();
403403

404-
cm_->configure_controller(controller_name1);
404+
cm_->configure_controller(CONTROLLER_NAME_1);
405405

406406
// Start controller #1
407407
RCLCPP_INFO(cm_->get_logger(), "Starting stopped controller #1");
408-
switch_test_controllers(strvec{controller_name1}, strvec{}, test_param.strictness);
408+
switch_test_controllers(strvec{CONTROLLER_NAME_1}, strvec{}, test_param.strictness);
409409
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if1->get_state().id());
410410
ASSERT_EQ(
411411
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, controller_if2->get_state().id());
@@ -418,42 +418,42 @@ TEST_P(TestTwoLoadedControllers, switch_multiple_controllers)
418418
// TODO(destogl): fix this test for BEST_EFFORT - probably related to:
419419
// https://github.com/ros-controls/ros2_control/pull/582#issuecomment-1029931561
420420
// switch_test_controllers(
421-
// strvec{controller_name2}, strvec{controller_name1}, test_param.strictness,
421+
// strvec{CONTROLLER_NAME_2}, strvec{CONTROLLER_NAME_1}, test_param.strictness,
422422
// std::future_status::ready, controller_interface::return_type::ERROR);
423423
switch_test_controllers(
424-
strvec{controller_name2}, strvec{controller_name1}, STRICT, std::future_status::ready,
424+
strvec{CONTROLLER_NAME_2}, strvec{CONTROLLER_NAME_1}, STRICT, std::future_status::ready,
425425
controller_interface::return_type::ERROR);
426426
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if1->get_state().id());
427427
ASSERT_EQ(
428428
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, controller_if2->get_state().id());
429429

430430
{
431431
ControllerManagerRunner cm_runner(this);
432-
cm_->configure_controller(controller_name2);
432+
cm_->configure_controller(CONTROLLER_NAME_2);
433433
}
434434

435435
// Stop controller 1
436436
RCLCPP_INFO(cm_->get_logger(), "Stopping controller #1");
437-
switch_test_controllers(strvec{}, strvec{controller_name1}, test_param.strictness);
437+
switch_test_controllers(strvec{}, strvec{CONTROLLER_NAME_1}, test_param.strictness);
438438
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if1->get_state().id());
439439
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if2->get_state().id());
440440

441441
// Start controller 1 again
442442
RCLCPP_INFO(cm_->get_logger(), "Starting stopped controller #1");
443-
switch_test_controllers(strvec{controller_name1}, strvec{}, test_param.strictness);
443+
switch_test_controllers(strvec{CONTROLLER_NAME_1}, strvec{}, test_param.strictness);
444444
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if1->get_state().id());
445445
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if2->get_state().id());
446446

447447
// Stop controller 1, start controller 2
448448
RCLCPP_INFO(cm_->get_logger(), "Stopping controller #1, starting controller #2");
449449
switch_test_controllers(
450-
strvec{controller_name2}, strvec{controller_name1}, test_param.strictness);
450+
strvec{CONTROLLER_NAME_2}, strvec{CONTROLLER_NAME_1}, test_param.strictness);
451451
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if1->get_state().id());
452452
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, controller_if2->get_state().id());
453453

454454
// Stop controller 2
455455
RCLCPP_INFO(cm_->get_logger(), "Stopping controller #2");
456-
switch_test_controllers(strvec{}, strvec{controller_name2}, test_param.strictness);
456+
switch_test_controllers(strvec{}, strvec{CONTROLLER_NAME_2}, test_param.strictness);
457457
ASSERT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, controller_if2->get_state().id());
458458
}
459459

0 commit comments

Comments
 (0)