Skip to content

Commit 8cac8cc

Browse files
Check interface_configuration_type for other ctrls
1 parent 678cc1f commit 8cac8cc

16 files changed

+153
-139
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -46,41 +46,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
4646
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
4747
}
4848

49-
TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
49+
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5050
{
5151
SetUpController();
5252

5353
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5454

55-
auto command_intefaces = controller_->command_interface_configuration();
56-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
55+
auto cmd_if_conf = controller_->command_interface_configuration();
56+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5757
EXPECT_EQ(
58-
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
58+
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
5959
rear_wheels_names_[0] + "/" + traction_interface_name_);
6060
EXPECT_EQ(
61-
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
61+
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
6262
rear_wheels_names_[1] + "/" + traction_interface_name_);
6363
EXPECT_EQ(
64-
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
64+
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
6565
front_wheels_names_[0] + "/" + steering_interface_name_);
6666
EXPECT_EQ(
67-
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
67+
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
6868
front_wheels_names_[1] + "/" + steering_interface_name_);
69+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6970

70-
auto state_intefaces = controller_->state_interface_configuration();
71-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
71+
auto state_if_conf = controller_->state_interface_configuration();
72+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7273
EXPECT_EQ(
73-
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
74+
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
7475
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7576
EXPECT_EQ(
76-
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
77+
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
7778
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
7879
EXPECT_EQ(
79-
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
80+
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
8081
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
8182
EXPECT_EQ(
82-
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
83+
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
8384
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
85+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8486

8587
// check ref itfsTIME
8688
auto reference_interfaces = controller_->export_reference_interfaces();

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class TestableAckermannSteeringController
6262
: public ackermann_steering_controller::AckermannSteeringController
6363
{
6464
FRIEND_TEST(AckermannSteeringControllerTest, all_parameters_set_configure_success);
65-
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_intefaces);
65+
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_interfaces);
6666
FRIEND_TEST(AckermannSteeringControllerTest, activate_success);
6767
FRIEND_TEST(AckermannSteeringControllerTest, update_success);
6868
FRIEND_TEST(AckermannSteeringControllerTest, deactivate_success);

ackermann_steering_controller/test/test_ackermann_steering_controller_preceeding.cpp

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -48,41 +48,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
4848
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
4949
}
5050

51-
TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
51+
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
5252
{
5353
SetUpController();
5454

5555
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5656

57-
auto command_intefaces = controller_->command_interface_configuration();
58-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
57+
auto cmd_if_conf = controller_->command_interface_configuration();
58+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5959
EXPECT_EQ(
60-
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
60+
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
6161
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
6262
EXPECT_EQ(
63-
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
63+
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
6464
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
6565
EXPECT_EQ(
66-
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
66+
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
6767
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
6868
EXPECT_EQ(
69-
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
69+
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
7070
preceeding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
71+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7172

72-
auto state_intefaces = controller_->state_interface_configuration();
73-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
73+
auto state_if_conf = controller_->state_interface_configuration();
74+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
7475
EXPECT_EQ(
75-
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
76+
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
7677
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7778
EXPECT_EQ(
78-
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
79+
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
7980
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
8081
EXPECT_EQ(
81-
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
82+
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
8283
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
8384
EXPECT_EQ(
84-
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
85+
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
8586
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
87+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8688

8789
// check ref itfs
8890
auto reference_interfaces = controller_->export_reference_interfaces();

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -157,12 +157,15 @@ TEST_F(AdmittanceControllerTest, check_interfaces)
157157

158158
auto command_interfaces = controller_->command_interface_configuration();
159159
ASSERT_EQ(command_interfaces.names.size(), joint_command_values_.size());
160+
EXPECT_EQ(
161+
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
160162

161163
ASSERT_EQ(
162164
controller_->command_interfaces_.size(), command_interface_types_.size() * joint_names_.size());
163165

164166
auto state_interfaces = controller_->state_interface_configuration();
165167
ASSERT_EQ(state_interfaces.names.size(), joint_state_values_.size() + fts_state_values_.size());
168+
EXPECT_EQ(state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
166169

167170
ASSERT_EQ(
168171
controller_->state_interfaces_.size(),

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -44,29 +44,29 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
4444
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
4545
}
4646

47-
TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
47+
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
4848
{
4949
SetUpController();
5050

5151
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5252

53-
auto command_intefaces = controller_->command_interface_configuration();
54-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
53+
auto cmd_if_conf = controller_->command_interface_configuration();
54+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5555
EXPECT_EQ(
56-
command_intefaces.names[CMD_TRACTION_WHEEL],
57-
rear_wheels_names_[0] + "/" + traction_interface_name_);
56+
cmd_if_conf.names[CMD_TRACTION_WHEEL], rear_wheels_names_[0] + "/" + traction_interface_name_);
5857
EXPECT_EQ(
59-
command_intefaces.names[CMD_STEER_WHEEL],
60-
front_wheels_names_[0] + "/" + steering_interface_name_);
58+
cmd_if_conf.names[CMD_STEER_WHEEL], front_wheels_names_[0] + "/" + steering_interface_name_);
59+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6160

62-
auto state_intefaces = controller_->state_interface_configuration();
63-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
61+
auto state_if_conf = controller_->state_interface_configuration();
62+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
6463
EXPECT_EQ(
65-
state_intefaces.names[STATE_TRACTION_WHEEL],
64+
state_if_conf.names[STATE_TRACTION_WHEEL],
6665
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
6766
EXPECT_EQ(
68-
state_intefaces.names[STATE_STEER_AXIS],
67+
state_if_conf.names[STATE_STEER_AXIS],
6968
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
69+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7070

7171
// check ref itfsTIME
7272
auto reference_interfaces = controller_->export_reference_interfaces();

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class TestableBicycleSteeringController
6060
: public bicycle_steering_controller::BicycleSteeringController
6161
{
6262
FRIEND_TEST(BicycleSteeringControllerTest, all_parameters_set_configure_success);
63-
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_intefaces);
63+
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_interfaces);
6464
FRIEND_TEST(BicycleSteeringControllerTest, activate_success);
6565
FRIEND_TEST(BicycleSteeringControllerTest, update_success);
6666
FRIEND_TEST(BicycleSteeringControllerTest, deactivate_success);

bicycle_steering_controller/test/test_bicycle_steering_controller_preceeding.cpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -46,31 +46,31 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
4646
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
4747
}
4848

49-
TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
49+
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
5050
{
5151
SetUpController();
5252

5353
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
5454

55-
auto command_intefaces = controller_->command_interface_configuration();
56-
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
55+
auto cmd_if_conf = controller_->command_interface_configuration();
56+
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
5757
EXPECT_EQ(
58-
command_intefaces.names[CMD_TRACTION_WHEEL],
58+
cmd_if_conf.names[CMD_TRACTION_WHEEL],
5959
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
60-
6160
EXPECT_EQ(
62-
command_intefaces.names[CMD_STEER_WHEEL],
61+
cmd_if_conf.names[CMD_STEER_WHEEL],
6362
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
63+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
6464

65-
auto state_intefaces = controller_->state_interface_configuration();
66-
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
67-
65+
auto state_if_conf = controller_->state_interface_configuration();
66+
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
6867
EXPECT_EQ(
69-
state_intefaces.names[STATE_TRACTION_WHEEL],
68+
state_if_conf.names[STATE_TRACTION_WHEEL],
7069
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
7170
EXPECT_EQ(
72-
state_intefaces.names[STATE_STEER_AXIS],
71+
state_if_conf.names[STATE_STEER_AXIS],
7372
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
73+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7474

7575
// check ref itfs
7676
auto reference_interfaces = controller_->export_reference_interfaces();

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -249,12 +249,12 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)
249249

250250
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
251251

252-
ASSERT_THAT(
253-
controller_->state_interface_configuration().names,
254-
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
255-
ASSERT_THAT(
256-
controller_->command_interface_configuration().names,
257-
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
252+
auto state_if_conf = controller_->state_interface_configuration();
253+
ASSERT_THAT(state_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
254+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
255+
auto cmd_if_conf = controller_->command_interface_configuration();
256+
ASSERT_THAT(cmd_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
257+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
258258
}
259259

260260
TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_namespace)

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -120,13 +120,13 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
120120
auto state = traj_controller_->get_node()->configure();
121121
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
122122

123-
auto cmd_interface_config = traj_controller_->command_interface_configuration();
124-
ASSERT_EQ(
125-
cmd_interface_config.names.size(), joint_names_.size() * command_interface_types_.size());
123+
auto cmd_if_conf = traj_controller_->command_interface_configuration();
124+
ASSERT_EQ(cmd_if_conf.names.size(), joint_names_.size() * command_interface_types_.size());
125+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
126126

127-
auto state_interface_config = traj_controller_->state_interface_configuration();
128-
ASSERT_EQ(
129-
state_interface_config.names.size(), joint_names_.size() * state_interface_types_.size());
127+
auto state_if_conf = traj_controller_->state_interface_configuration();
128+
ASSERT_EQ(state_if_conf.names.size(), joint_names_.size() * state_interface_types_.size());
129+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
130130

131131
state = ActivateTrajectoryController();
132132
ASSERT_EQ(state.id(), State::PRIMARY_STATE_ACTIVE);

pid_controller/test/test_pid_controller.cpp

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -61,45 +61,46 @@ TEST_F(PidControllerTest, all_parameters_set_configure_success)
6161
ASSERT_FALSE(controller_->params_.use_external_measured_states);
6262
}
6363

64-
TEST_F(PidControllerTest, check_exported_intefaces)
64+
TEST_F(PidControllerTest, check_exported_interfaces)
6565
{
6666
SetUpController();
6767

6868
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
6969

70-
auto command_interfaces = controller_->command_interface_configuration();
71-
ASSERT_EQ(command_interfaces.names.size(), dof_command_values_.size());
72-
for (size_t i = 0; i < command_interfaces.names.size(); ++i)
70+
auto cmd_if_conf = controller_->command_interface_configuration();
71+
ASSERT_EQ(cmd_if_conf.names.size(), dof_command_values_.size());
72+
for (size_t i = 0; i < cmd_if_conf.names.size(); ++i)
7373
{
74-
EXPECT_EQ(command_interfaces.names[i], dof_names_[i] + "/" + command_interface_);
74+
EXPECT_EQ(cmd_if_conf.names[i], dof_names_[i] + "/" + command_interface_);
7575
}
76+
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
7677

77-
auto state_intefaces = controller_->state_interface_configuration();
78-
ASSERT_EQ(state_intefaces.names.size(), dof_state_values_.size());
78+
auto state_if_conf = controller_->state_interface_configuration();
79+
ASSERT_EQ(state_if_conf.names.size(), dof_state_values_.size());
7980
size_t si_index = 0;
8081
for (const auto & interface : state_interfaces_)
8182
{
8283
for (const auto & dof_name : dof_names_)
8384
{
84-
EXPECT_EQ(state_intefaces.names[si_index], dof_name + "/" + interface);
85+
EXPECT_EQ(state_if_conf.names[si_index], dof_name + "/" + interface);
8586
++si_index;
8687
}
8788
}
89+
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
8890

8991
// check ref itfs
90-
auto reference_interfaces = controller_->export_reference_interfaces();
91-
ASSERT_EQ(reference_interfaces.size(), dof_state_values_.size());
92+
auto ref_if_conf = controller_->export_reference_interfaces();
93+
ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size());
9294
size_t ri_index = 0;
9395
for (const auto & interface : state_interfaces_)
9496
{
9597
for (const auto & dof_name : dof_names_)
9698
{
9799
const std::string ref_itf_name =
98100
std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface;
99-
EXPECT_EQ(reference_interfaces[ri_index].get_name(), ref_itf_name);
100-
EXPECT_EQ(
101-
reference_interfaces[ri_index].get_prefix_name(), controller_->get_node()->get_name());
102-
EXPECT_EQ(reference_interfaces[ri_index].get_interface_name(), dof_name + "/" + interface);
101+
EXPECT_EQ(ref_if_conf[ri_index].get_name(), ref_itf_name);
102+
EXPECT_EQ(ref_if_conf[ri_index].get_prefix_name(), controller_->get_node()->get_name());
103+
EXPECT_EQ(ref_if_conf[ri_index].get_interface_name(), dof_name + "/" + interface);
103104
++ri_index;
104105
}
105106
}

0 commit comments

Comments
 (0)