Skip to content

Commit

Permalink
Use a function to reuse for tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Oct 30, 2023
1 parent 608bab3 commit be3e67c
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 91 deletions.
96 changes: 5 additions & 91 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,77 +106,20 @@ TEST_P(TrajectoryControllerTestParameterized, check_interface_names)
const auto state = traj_controller_->get_node()->configure();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);

std::vector<std::string> state_interface_names;
state_interface_names.reserve(joint_names_.size() * state_interface_types_.size());
for (const auto & joint : joint_names_)
{
for (const auto & interface : state_interface_types_)
{
state_interface_names.push_back(joint + "/" + interface);
}
}
auto state_interfaces = traj_controller_->state_interface_configuration();
EXPECT_EQ(state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(state_interfaces.names.size(), joint_names_.size() * state_interface_types_.size());
ASSERT_THAT(state_interfaces.names, testing::UnorderedElementsAreArray(state_interface_names));

std::vector<std::string> command_interface_names;
command_interface_names.reserve(joint_names_.size() * command_interface_types_.size());
for (const auto & joint : joint_names_)
{
for (const auto & interface : command_interface_types_)
{
command_interface_names.push_back(joint + "/" + interface);
}
}
auto command_interfaces = traj_controller_->command_interface_configuration();
EXPECT_EQ(
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(command_interfaces.names.size(), joint_names_.size() * command_interface_types_.size());
ASSERT_THAT(
command_interfaces.names, testing::UnorderedElementsAreArray(command_interface_names));
compare_joints(joint_names_, joint_names_);
}

TEST_P(TrajectoryControllerTestParameterized, check_interface_names_with_command_joints)
{
rclcpp::executors::MultiThreadedExecutor executor;
// set command_joints parameter
// set command_joints parameter different than joint_names_
const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names_);
SetUpTrajectoryController(executor, {command_joint_names_param});

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

std::vector<std::string> state_interface_names;
state_interface_names.reserve(joint_names_.size() * state_interface_types_.size());
for (const auto & joint : joint_names_)
{
for (const auto & interface : state_interface_types_)
{
state_interface_names.push_back(joint + "/" + interface);
}
}
auto state_interfaces = traj_controller_->state_interface_configuration();
EXPECT_EQ(state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(state_interfaces.names.size(), joint_names_.size() * state_interface_types_.size());
ASSERT_THAT(state_interfaces.names, testing::UnorderedElementsAreArray(state_interface_names));

std::vector<std::string> command_interface_names;
command_interface_names.reserve(command_joint_names_.size() * command_interface_types_.size());
for (const auto & joint : command_joint_names_)
{
for (const auto & interface : command_interface_types_)
{
command_interface_names.push_back(joint + "/" + interface);
}
}
auto command_interfaces = traj_controller_->command_interface_configuration();
EXPECT_EQ(
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(
command_interfaces.names.size(), command_joint_names_.size() * command_interface_types_.size());
ASSERT_THAT(
command_interfaces.names, testing::UnorderedElementsAreArray(command_interface_names));
compare_joints(joint_names_, command_joint_names_);
}

/**
Expand All @@ -186,44 +129,15 @@ TEST_P(
TrajectoryControllerTestParameterized, check_interface_names_with_command_joints_less_than_dof)
{
rclcpp::executors::MultiThreadedExecutor executor;
// set command_joints parameter
// set command_joints parameter to a subset of joint_names_
std::vector<std::string> command_joint_names{joint_names_[0], joint_names_[1]};
const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names);
SetUpTrajectoryController(executor, {command_joint_names_param});

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

std::vector<std::string> state_interface_names;
state_interface_names.reserve(joint_names_.size() * state_interface_types_.size());
for (const auto & joint : joint_names_)
{
for (const auto & interface : state_interface_types_)
{
state_interface_names.push_back(joint + "/" + interface);
}
}
auto state_interfaces = traj_controller_->state_interface_configuration();
EXPECT_EQ(state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(state_interfaces.names.size(), joint_names_.size() * state_interface_types_.size());
ASSERT_THAT(state_interfaces.names, testing::UnorderedElementsAreArray(state_interface_names));

std::vector<std::string> command_interface_names;
command_interface_names.reserve(command_joint_names.size() * command_interface_types_.size());
for (const auto & joint : command_joint_names)
{
for (const auto & interface : command_interface_types_)
{
command_interface_names.push_back(joint + "/" + interface);
}
}
auto command_interfaces = traj_controller_->command_interface_configuration();
EXPECT_EQ(
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(
command_interfaces.names.size(), command_joint_names.size() * command_interface_types_.size());
ASSERT_THAT(
command_interfaces.names, testing::UnorderedElementsAreArray(command_interface_names));
compare_joints(joint_names_, command_joint_names);
}

TEST_P(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -540,6 +540,47 @@ class TrajectoryControllerTest : public ::testing::Test
}
}

/**
* @brief compares the joint names and interface types of the controller with the given ones
*/
void compare_joints(
std::vector<std::string> state_joint_names, std::vector<std::string> command_joint_names)
{
std::vector<std::string> state_interface_names;
state_interface_names.reserve(state_joint_names.size() * state_interface_types_.size());
for (const auto & joint : state_joint_names)
{
for (const auto & interface : state_interface_types_)
{
state_interface_names.push_back(joint + "/" + interface);
}
}
auto state_interfaces = traj_controller_->state_interface_configuration();
EXPECT_EQ(
state_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(
state_interfaces.names.size(), state_joint_names.size() * state_interface_types_.size());
ASSERT_THAT(state_interfaces.names, testing::UnorderedElementsAreArray(state_interface_names));

std::vector<std::string> command_interface_names;
command_interface_names.reserve(command_joint_names.size() * command_interface_types_.size());
for (const auto & joint : command_joint_names)
{
for (const auto & interface : command_interface_types_)
{
command_interface_names.push_back(joint + "/" + interface);
}
}
auto command_interfaces = traj_controller_->command_interface_configuration();
EXPECT_EQ(
command_interfaces.type, controller_interface::interface_configuration_type::INDIVIDUAL);
EXPECT_EQ(
command_interfaces.names.size(),
command_joint_names.size() * command_interface_types_.size());
ASSERT_THAT(
command_interfaces.names, testing::UnorderedElementsAreArray(command_interface_names));
}

std::string controller_name_;

std::vector<std::string> joint_names_;
Expand Down

0 comments on commit be3e67c

Please sign in to comment.