Skip to content

Commit

Permalink
Check interface_configuration_type for other ctrls
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jan 11, 2024
1 parent 678cc1f commit 8cac8cc
Show file tree
Hide file tree
Showing 16 changed files with 153 additions and 139 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,41 +46,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
}

TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
{
SetUpController();

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

auto command_intefaces = controller_->command_interface_configuration();
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
rear_wheels_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
front_wheels_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
auto reference_interfaces = controller_->export_reference_interfaces();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class TestableAckermannSteeringController
: public ackermann_steering_controller::AckermannSteeringController
{
FRIEND_TEST(AckermannSteeringControllerTest, all_parameters_set_configure_success);
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_intefaces);
FRIEND_TEST(AckermannSteeringControllerTest, check_exported_interfaces);
FRIEND_TEST(AckermannSteeringControllerTest, activate_success);
FRIEND_TEST(AckermannSteeringControllerTest, update_success);
FRIEND_TEST(AckermannSteeringControllerTest, deactivate_success);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,41 +48,43 @@ TEST_F(AckermannSteeringControllerTest, all_parameters_set_configure_success)
ASSERT_EQ(controller_->ackermann_params_.rear_wheel_track, rear_wheel_track_);
}

TEST_F(AckermannSteeringControllerTest, check_exported_intefaces)
TEST_F(AckermannSteeringControllerTest, check_exported_interfaces)
{
SetUpController();

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

auto command_intefaces = controller_->command_interface_configuration();
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_RIGHT_WHEEL],
cmd_if_conf.names[CMD_TRACTION_RIGHT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_LEFT_WHEEL],
cmd_if_conf.names[CMD_TRACTION_LEFT_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_STEER_RIGHT_WHEEL],
cmd_if_conf.names[CMD_STEER_RIGHT_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_STEER_LEFT_WHEEL],
cmd_if_conf.names[CMD_STEER_LEFT_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_RIGHT_WHEEL],
state_if_conf.names[STATE_TRACTION_RIGHT_WHEEL],
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_LEFT_WHEEL],
state_if_conf.names[STATE_TRACTION_LEFT_WHEEL],
controller_->rear_wheels_state_names_[1] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_RIGHT_WHEEL],
state_if_conf.names[STATE_STEER_RIGHT_WHEEL],
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_LEFT_WHEEL],
state_if_conf.names[STATE_STEER_LEFT_WHEEL],
controller_->front_wheels_state_names_[1] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
Expand Down
3 changes: 3 additions & 0 deletions admittance_controller/test/test_admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,12 +157,15 @@ TEST_F(AdmittanceControllerTest, check_interfaces)

auto command_interfaces = controller_->command_interface_configuration();
ASSERT_EQ(command_interfaces.names.size(), joint_command_values_.size());
EXPECT_EQ(
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);

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

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

ASSERT_EQ(
controller_->state_interfaces_.size(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,29 +44,29 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
}

TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
{
SetUpController();

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

auto command_intefaces = controller_->command_interface_configuration();
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_WHEEL],
rear_wheels_names_[0] + "/" + traction_interface_name_);
cmd_if_conf.names[CMD_TRACTION_WHEEL], rear_wheels_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
command_intefaces.names[CMD_STEER_WHEEL],
front_wheels_names_[0] + "/" + steering_interface_name_);
cmd_if_conf.names[CMD_STEER_WHEEL], front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_WHEEL],
state_if_conf.names[STATE_TRACTION_WHEEL],
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_AXIS],
state_if_conf.names[STATE_STEER_AXIS],
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfsTIME
auto reference_interfaces = controller_->export_reference_interfaces();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class TestableBicycleSteeringController
: public bicycle_steering_controller::BicycleSteeringController
{
FRIEND_TEST(BicycleSteeringControllerTest, all_parameters_set_configure_success);
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_intefaces);
FRIEND_TEST(BicycleSteeringControllerTest, check_exported_interfaces);
FRIEND_TEST(BicycleSteeringControllerTest, activate_success);
FRIEND_TEST(BicycleSteeringControllerTest, update_success);
FRIEND_TEST(BicycleSteeringControllerTest, deactivate_success);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,31 +46,31 @@ TEST_F(BicycleSteeringControllerTest, all_parameters_set_configure_success)
ASSERT_EQ(controller_->bicycle_params_.rear_wheel_radius, rear_wheels_radius_);
}

TEST_F(BicycleSteeringControllerTest, check_exported_intefaces)
TEST_F(BicycleSteeringControllerTest, check_exported_interfaces)
{
SetUpController();

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

auto command_intefaces = controller_->command_interface_configuration();
ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
EXPECT_EQ(
command_intefaces.names[CMD_TRACTION_WHEEL],
cmd_if_conf.names[CMD_TRACTION_WHEEL],
preceeding_prefix_ + "/" + rear_wheels_names_[0] + "/" + traction_interface_name_);

EXPECT_EQ(
command_intefaces.names[CMD_STEER_WHEEL],
cmd_if_conf.names[CMD_STEER_WHEEL],
preceeding_prefix_ + "/" + front_wheels_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());

auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), joint_state_values_.size());
EXPECT_EQ(
state_intefaces.names[STATE_TRACTION_WHEEL],
state_if_conf.names[STATE_TRACTION_WHEEL],
controller_->rear_wheels_state_names_[0] + "/" + traction_interface_name_);
EXPECT_EQ(
state_intefaces.names[STATE_STEER_AXIS],
state_if_conf.names[STATE_STEER_AXIS],
controller_->front_wheels_state_names_[0] + "/" + steering_interface_name_);
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
Expand Down
12 changes: 6 additions & 6 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,12 +249,12 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified)

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

ASSERT_THAT(
controller_->state_interface_configuration().names,
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
ASSERT_THAT(
controller_->command_interface_configuration().names,
SizeIs(left_wheel_names.size() + right_wheel_names.size()));
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}

TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_namespace)
Expand Down
12 changes: 6 additions & 6 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,13 +120,13 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
auto state = traj_controller_->get_node()->configure();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);

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

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

state = ActivateTrajectoryController();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_ACTIVE);
Expand Down
29 changes: 15 additions & 14 deletions pid_controller/test/test_pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,45 +61,46 @@ TEST_F(PidControllerTest, all_parameters_set_configure_success)
ASSERT_FALSE(controller_->params_.use_external_measured_states);
}

TEST_F(PidControllerTest, check_exported_intefaces)
TEST_F(PidControllerTest, check_exported_interfaces)
{
SetUpController();

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

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

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), dof_state_values_.size());
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), dof_state_values_.size());
size_t si_index = 0;
for (const auto & interface : state_interfaces_)
{
for (const auto & dof_name : dof_names_)
{
EXPECT_EQ(state_intefaces.names[si_index], dof_name + "/" + interface);
EXPECT_EQ(state_if_conf.names[si_index], dof_name + "/" + interface);
++si_index;
}
}
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), dof_state_values_.size());
auto ref_if_conf = controller_->export_reference_interfaces();
ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size());
size_t ri_index = 0;
for (const auto & interface : state_interfaces_)
{
for (const auto & dof_name : dof_names_)
{
const std::string ref_itf_name =
std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface;
EXPECT_EQ(reference_interfaces[ri_index].get_name(), ref_itf_name);
EXPECT_EQ(
reference_interfaces[ri_index].get_prefix_name(), controller_->get_node()->get_name());
EXPECT_EQ(reference_interfaces[ri_index].get_interface_name(), dof_name + "/" + interface);
EXPECT_EQ(ref_if_conf[ri_index].get_name(), ref_itf_name);
EXPECT_EQ(ref_if_conf[ri_index].get_prefix_name(), controller_->get_node()->get_name());
EXPECT_EQ(ref_if_conf[ri_index].get_interface_name(), dof_name + "/" + interface);
++ri_index;
}
}
Expand Down
29 changes: 15 additions & 14 deletions pid_controller/test/test_pid_controller_preceding.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,45 +49,46 @@ TEST_F(PidControllerTest, all_parameters_set_configure_success)
ASSERT_EQ(controller_->params_.command_interface, command_interface_);
}

TEST_F(PidControllerTest, check_exported_intefaces)
TEST_F(PidControllerTest, check_exported_interfaces)
{
SetUpController();

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

auto command_intefaces = controller_->command_interface_configuration();
ASSERT_EQ(command_intefaces.names.size(), dof_command_values_.size());
for (size_t i = 0; i < command_intefaces.names.size(); ++i)
auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), dof_command_values_.size());
for (size_t i = 0; i < cmd_if_conf.names.size(); ++i)
{
EXPECT_EQ(command_intefaces.names[i], dof_names_[i] + "/" + command_interface_);
EXPECT_EQ(cmd_if_conf.names[i], dof_names_[i] + "/" + command_interface_);
}
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

auto state_intefaces = controller_->state_interface_configuration();
ASSERT_EQ(state_intefaces.names.size(), dof_state_values_.size());
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_EQ(state_if_conf.names.size(), dof_state_values_.size());
size_t si_index = 0;
for (const auto & interface : state_interfaces_)
{
for (const auto & dof_name : reference_and_state_dof_names_)
{
EXPECT_EQ(state_intefaces.names[si_index], dof_name + "/" + interface);
EXPECT_EQ(state_if_conf.names[si_index], dof_name + "/" + interface);
++si_index;
}
}
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// check ref itfs
auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), dof_state_values_.size());
auto ref_if_conf = controller_->export_reference_interfaces();
ASSERT_EQ(ref_if_conf.size(), dof_state_values_.size());
size_t ri_index = 0;
for (const auto & interface : state_interfaces_)
{
for (const auto & dof_name : reference_and_state_dof_names_)
{
const std::string ref_itf_name =
std::string(controller_->get_node()->get_name()) + "/" + dof_name + "/" + interface;
EXPECT_EQ(reference_interfaces[ri_index].get_name(), ref_itf_name);
EXPECT_EQ(
reference_interfaces[ri_index].get_prefix_name(), controller_->get_node()->get_name());
EXPECT_EQ(reference_interfaces[ri_index].get_interface_name(), dof_name + "/" + interface);
EXPECT_EQ(ref_if_conf[ri_index].get_name(), ref_itf_name);
EXPECT_EQ(ref_if_conf[ri_index].get_prefix_name(), controller_->get_node()->get_name());
EXPECT_EQ(ref_if_conf[ri_index].get_interface_name(), dof_name + "/" + interface);
++ri_index;
}
}
Expand Down

0 comments on commit 8cac8cc

Please sign in to comment.