Skip to content

Commit

Permalink
Add tests for interface_configuration_type consistently (#899) (#1011)
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] authored Feb 5, 2024
1 parent 100c754 commit 2ac7bb2
Show file tree
Hide file tree
Showing 22 changed files with 804 additions and 111 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 @@ -159,12 +159,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 @@ -247,12 +247,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
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,10 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Configure_Success)
// check interface configuration
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}

TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
Expand Down Expand Up @@ -196,17 +198,21 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success)
// check interface configuration
auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
auto state_if_conf = fts_broadcaster_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);

// deactivate passed
ASSERT_EQ(fts_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);

// check interface configuration
cmd_if_conf = fts_broadcaster_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, IsEmpty());
ASSERT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::NONE);
state_if_conf = fts_broadcaster_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(6lu)); // did not change
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}

TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Update_Success)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,7 @@ TEST_F(ForwardCommandControllerTest, ConfigureParamsSuccess)
ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
}

TEST_F(ForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
Expand Down Expand Up @@ -189,6 +190,7 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

ASSERT_EQ(
controller_->on_activate(rclcpp_lifecycle::State()),
Expand All @@ -197,8 +199,10 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
ASSERT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);
}

TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
Expand Down Expand Up @@ -352,15 +356,18 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

node_state = controller_->get_node()->activate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);

// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

auto command_msg = std::make_shared<std_msgs::msg::Float64MultiArray>();
command_msg->data = {10.0, 20.0, 30.0};
Expand All @@ -383,8 +390,10 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
// check interface configuration
cmd_if_conf = controller_->command_interface_configuration();
ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size())); // did not change
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,6 +297,7 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

// send command
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
Expand All @@ -322,6 +323,7 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, IsEmpty());
EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::NONE);

// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
Expand Down
Loading

0 comments on commit 2ac7bb2

Please sign in to comment.