Skip to content

Commit 8c649a3

Browse files
Call configure() of base class instead of node (#1659)
1 parent 496e39d commit 8c649a3

File tree

9 files changed

+26
-26
lines changed

9 files changed

+26
-26
lines changed

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -487,7 +487,7 @@ TEST_F(TestDiffDriveController, test_speed_limiter)
487487

488488
rclcpp::executors::SingleThreadedExecutor executor;
489489
executor.add_node(controller_->get_node()->get_node_base_interface());
490-
auto state = controller_->get_node()->configure();
490+
auto state = controller_->configure();
491491
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
492492
assignResourcesPosFeedback();
493493

@@ -700,7 +700,7 @@ TEST_F(TestDiffDriveController, cleanup)
700700

701701
rclcpp::executors::SingleThreadedExecutor executor;
702702
executor.add_node(controller_->get_node()->get_node_base_interface());
703-
auto state = controller_->get_node()->configure();
703+
auto state = controller_->configure();
704704
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
705705
assignResourcesPosFeedback();
706706

@@ -753,7 +753,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
753753
rclcpp::executors::SingleThreadedExecutor executor;
754754
executor.add_node(controller_->get_node()->get_node_base_interface());
755755

756-
auto state = controller_->get_node()->configure();
756+
auto state = controller_->configure();
757757
assignResourcesPosFeedback();
758758

759759
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
@@ -795,7 +795,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
795795
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value());
796796
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value());
797797

798-
state = controller_->get_node()->configure();
798+
state = controller_->configure();
799799
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
800800
executor.cancel();
801801
}
@@ -821,7 +821,7 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
821821
ASSERT_TRUE(controller_->set_chained_mode(false));
822822
ASSERT_FALSE(controller_->is_in_chained_mode());
823823

824-
auto state = controller_->get_node()->configure();
824+
auto state = controller_->configure();
825825
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
826826
assignResourcesPosFeedback();
827827

@@ -892,7 +892,7 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
892892
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value())
893893
<< "Wheels should be halted on cleanup()";
894894

895-
state = controller_->get_node()->configure();
895+
state = controller_->configure();
896896
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
897897
executor.cancel();
898898
}
@@ -917,7 +917,7 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
917917
ASSERT_TRUE(controller_->set_chained_mode(true));
918918
ASSERT_TRUE(controller_->is_in_chained_mode());
919919

920-
auto state = controller_->get_node()->configure();
920+
auto state = controller_->configure();
921921
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
922922
assignResourcesPosFeedback();
923923

@@ -971,7 +971,7 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
971971
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value())
972972
<< "Wheels should be halted on cleanup()";
973973

974-
state = controller_->get_node()->configure();
974+
state = controller_->configure();
975975
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
976976
executor.cancel();
977977
}
@@ -1021,7 +1021,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
10211021

10221022
ASSERT_TRUE(controller_->set_chained_mode(false));
10231023

1024-
auto state = controller_->get_node()->configure();
1024+
auto state = controller_->configure();
10251025
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
10261026
assignResourcesPosFeedback();
10271027

@@ -1119,7 +1119,7 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war
11191119

11201120
ASSERT_TRUE(controller_->set_chained_mode(false));
11211121

1122-
auto state = controller_->get_node()->configure();
1122+
auto state = controller_->configure();
11231123
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
11241124
assignResourcesPosFeedback();
11251125

effort_controllers/test/test_joint_group_effort_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -175,7 +175,7 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
175175
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
176176
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
177177

178-
auto node_state = controller_->get_node()->configure();
178+
auto node_state = controller_->configure();
179179
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
180180

181181
node_state = controller_->get_node()->activate();

forward_command_controller/test/test_forward_command_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -294,7 +294,7 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
294294
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
295295
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
296296

297-
auto node_state = controller_->get_node()->configure();
297+
auto node_state = controller_->configure();
298298
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
299299

300300
node_state = controller_->get_node()->activate();

forward_command_controller/test/test_multi_interface_forward_command_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ void MultiInterfaceForwardCommandControllerTest::SetParametersAndActivateControl
7676
controller_->get_node()->set_parameter(
7777
{"interface_names", std::vector<std::string>{"position", "velocity", "effort"}});
7878

79-
auto node_state = controller_->get_node()->configure();
79+
auto node_state = controller_->configure();
8080
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
8181
node_state = controller_->get_node()->activate();
8282
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);

joint_state_broadcaster/test/test_joint_state_broadcaster.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -934,7 +934,7 @@ TEST_F(JointStateBroadcasterTest, UpdateTest)
934934
{
935935
SetUpStateBroadcaster();
936936

937-
auto node_state = state_broadcaster_->get_node()->configure();
937+
auto node_state = state_broadcaster_->configure();
938938
node_state = state_broadcaster_->get_node()->activate();
939939
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
940940
ASSERT_EQ(
@@ -1015,7 +1015,7 @@ TEST_F(JointStateBroadcasterTest, UpdatePerformanceTest)
10151015

10161016
state_broadcaster_->assign_interfaces({}, std::move(state_interfaces));
10171017

1018-
auto node_state = state_broadcaster_->get_node()->configure();
1018+
auto node_state = state_broadcaster_->configure();
10191019
node_state = state_broadcaster_->get_node()->activate();
10201020
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
10211021

@@ -1058,7 +1058,7 @@ TEST_F(JointStateBroadcasterTest, UpdatePerformanceTest)
10581058
void JointStateBroadcasterTest::activate_and_get_joint_state_message(
10591059
const std::string & topic, sensor_msgs::msg::JointState & joint_state_msg)
10601060
{
1061-
auto node_state = state_broadcaster_->get_node()->configure();
1061+
auto node_state = state_broadcaster_->configure();
10621062
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
10631063

10641064
node_state = state_broadcaster_->get_node()->activate();
@@ -1135,7 +1135,7 @@ TEST_F(JointStateBroadcasterTest, JointStatePublishTestLocalTopic)
11351135
void JointStateBroadcasterTest::test_published_dynamic_joint_state_message(
11361136
const std::string & topic)
11371137
{
1138-
auto node_state = state_broadcaster_->get_node()->configure();
1138+
auto node_state = state_broadcaster_->configure();
11391139
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
11401140

11411141
node_state = state_broadcaster_->get_node()->activate();

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ TEST_P(
8686
const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names);
8787
SetUpTrajectoryController(executor, {command_joint_names_param});
8888

89-
const auto state = traj_controller_->get_node()->configure();
89+
const auto state = traj_controller_->configure();
9090
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
9191

9292
compare_joints(joint_names_, command_joint_names);
@@ -102,7 +102,7 @@ TEST_P(
102102
const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names);
103103
SetUpTrajectoryController(executor, {command_joint_names_param});
104104

105-
const auto state = traj_controller_->get_node()->configure();
105+
const auto state = traj_controller_->configure();
106106
ASSERT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED);
107107
}
108108

@@ -116,7 +116,7 @@ TEST_P(
116116
const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names);
117117
SetUpTrajectoryController(executor, {command_joint_names_param});
118118

119-
const auto state = traj_controller_->get_node()->configure();
119+
const auto state = traj_controller_->configure();
120120
ASSERT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED);
121121
}
122122

@@ -2643,7 +2643,7 @@ TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parame
26432643
command_interface_types_ = {"effort", "position"};
26442644
state_interface_types_ = {"position"};
26452645
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK);
2646-
state = traj_controller_->get_node()->configure();
2646+
state = traj_controller_->configure();
26472647
EXPECT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED);
26482648
state_interface_types_ = {"velocity"};
26492649
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

position_controllers/test/test_joint_group_position_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -175,7 +175,7 @@ TEST_F(JointGroupPositionControllerTest, CommandCallbackTest)
175175
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
176176
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
177177

178-
auto node_state = controller_->get_node()->configure();
178+
auto node_state = controller_->configure();
179179
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
180180

181181
node_state = controller_->get_node()->activate();

tricycle_controller/test/test_tricycle_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -261,7 +261,7 @@ TEST_F(TestTricycleController, cleanup)
261261

262262
rclcpp::executors::SingleThreadedExecutor executor;
263263
executor.add_node(controller_->get_node()->get_node_base_interface());
264-
auto state = controller_->get_node()->configure();
264+
auto state = controller_->configure();
265265
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
266266
assignResources();
267267

@@ -308,7 +308,7 @@ TEST_F(TestTricycleController, correct_initialization_using_parameters)
308308
rclcpp::executors::SingleThreadedExecutor executor;
309309
executor.add_node(controller_->get_node()->get_node_base_interface());
310310

311-
auto state = controller_->get_node()->configure();
311+
auto state = controller_->configure();
312312
assignResources();
313313

314314
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
@@ -349,7 +349,7 @@ TEST_F(TestTricycleController, correct_initialization_using_parameters)
349349
EXPECT_EQ(0.0, steering_joint_pos_cmd_.get_value());
350350
EXPECT_EQ(0.0, traction_joint_vel_cmd_.get_value());
351351

352-
state = controller_->get_node()->configure();
352+
state = controller_->configure();
353353
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
354354
executor.cancel();
355355
}

velocity_controllers/test/test_joint_group_velocity_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -175,7 +175,7 @@ TEST_F(JointGroupVelocityControllerTest, CommandCallbackTest)
175175
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
176176
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
177177

178-
auto node_state = controller_->get_node()->configure();
178+
auto node_state = controller_->configure();
179179
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
180180

181181
node_state = controller_->get_node()->activate();

0 commit comments

Comments
 (0)