Skip to content

Commit

Permalink
Make RHEL CI happy! (#730)
Browse files Browse the repository at this point in the history
* Make RHEL CI happy!

* Use UnorderedElementAre in the assertion

Co-authored-by: VX792 <[email protected]>
Co-authored-by: Bence Magyar <[email protected]>
  • Loading branch information
3 people authored Jun 17, 2022
1 parent 6434833 commit d632e89
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 33 deletions.
25 changes: 13 additions & 12 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

using ::testing::_;
using ::testing::Return;
using ::testing::UnorderedElementsAre;

TEST_F(TestControllerManagerSrvs, list_controller_types)
{
Expand Down Expand Up @@ -93,10 +94,10 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
ASSERT_TRUE(result->controller[0].claimed_interfaces.empty());
ASSERT_THAT(
result->controller[0].required_command_interfaces,
testing::ElementsAre("joint1/position", "joint2/velocity"));
UnorderedElementsAre("joint1/position", "joint2/velocity"));
ASSERT_THAT(
result->controller[0].required_state_interfaces,
testing::ElementsAre("joint1/position", "joint1/velocity", "joint2/position"));
UnorderedElementsAre("joint1/position", "joint1/velocity", "joint2/position"));

cm_->switch_controller(
{test_controller::TEST_CONTROLLER_NAME}, {},
Expand All @@ -107,13 +108,13 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
ASSERT_EQ("active", result->controller[0].state);
ASSERT_THAT(
result->controller[0].claimed_interfaces,
testing::ElementsAre("joint1/position", "joint2/velocity"));
UnorderedElementsAre("joint1/position", "joint2/velocity"));
ASSERT_THAT(
result->controller[0].required_command_interfaces,
testing::ElementsAre("joint1/position", "joint2/velocity"));
UnorderedElementsAre("joint1/position", "joint2/velocity"));
ASSERT_THAT(
result->controller[0].required_state_interfaces,
testing::ElementsAre("joint1/position", "joint1/velocity", "joint2/position"));
UnorderedElementsAre("joint1/position", "joint1/velocity", "joint2/position"));

cm_->switch_controller(
{}, {test_controller::TEST_CONTROLLER_NAME},
Expand All @@ -125,10 +126,10 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
ASSERT_TRUE(result->controller[0].claimed_interfaces.empty());
ASSERT_THAT(
result->controller[0].required_command_interfaces,
testing::ElementsAre("joint1/position", "joint2/velocity"));
UnorderedElementsAre("joint1/position", "joint2/velocity"));
ASSERT_THAT(
result->controller[0].required_state_interfaces,
testing::ElementsAre("joint1/position", "joint1/velocity", "joint2/position"));
UnorderedElementsAre("joint1/position", "joint1/velocity", "joint2/position"));

cmd_cfg = {controller_interface::interface_configuration_type::ALL};
test_controller->set_command_interface_configuration(cmd_cfg);
Expand All @@ -143,17 +144,17 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
ASSERT_EQ("active", result->controller[0].state);
ASSERT_THAT(
result->controller[0].claimed_interfaces,
testing::ElementsAre(
UnorderedElementsAre(
"joint2/velocity", "joint3/velocity", "joint2/max_acceleration", "configuration/max_tcp_jerk",
"joint1/position", "joint1/max_velocity"));
ASSERT_THAT(
result->controller[0].required_command_interfaces,
testing::ElementsAre(
UnorderedElementsAre(
"configuration/max_tcp_jerk", "joint1/max_velocity", "joint1/position",
"joint2/max_acceleration", "joint2/velocity", "joint3/velocity"));
ASSERT_THAT(
result->controller[0].required_state_interfaces,
testing::ElementsAre(
UnorderedElementsAre(
"configuration/max_tcp_jerk", "joint1/position", "joint1/some_unlisted_interface",
"joint1/velocity", "joint2/acceleration", "joint2/position", "joint2/velocity",
"joint3/acceleration", "joint3/position", "joint3/velocity", "sensor1/velocity"));
Expand All @@ -168,12 +169,12 @@ TEST_F(TestControllerManagerSrvs, list_controllers_srv)
ASSERT_TRUE(result->controller[0].claimed_interfaces.empty());
ASSERT_THAT(
result->controller[0].required_command_interfaces,
testing::ElementsAre(
UnorderedElementsAre(
"configuration/max_tcp_jerk", "joint1/max_velocity", "joint1/position",
"joint2/max_acceleration", "joint2/velocity", "joint3/velocity"));
ASSERT_THAT(
result->controller[0].required_state_interfaces,
testing::ElementsAre(
UnorderedElementsAre(
"configuration/max_tcp_jerk", "joint1/position", "joint1/some_unlisted_interface",
"joint1/velocity", "joint2/acceleration", "joint2/position", "joint2/velocity",
"joint3/acceleration", "joint3/position", "joint3/velocity", "sensor1/velocity"));
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/test/test_hardware_management_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
auto check_interfaces =
[](
const std::vector<controller_manager_msgs::msg::HardwareInterface> & interfaces,
const std::vector<const char *> & interface_names,
const std::vector<std::string> & interface_names,
const std::vector<bool> is_available_status, const std::vector<bool> is_claimed_status)
{
for (auto i = 0ul; i < interfaces.size(); ++i)
Expand Down
10 changes: 5 additions & 5 deletions hardware_interface/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -452,9 +452,9 @@ TEST_F(TestResourceManager, resource_status)

auto check_interfaces = [](
const std::vector<std::string> & registered_interfaces,
const std::vector<const char *> & interface_names)
const std::vector<std::string> & interface_names)
{
for (const auto & interface : interface_names)
for (const std::string & interface : interface_names)
{
auto it = std::find(registered_interfaces.begin(), registered_interfaces.end(), interface);
EXPECT_NE(it, registered_interfaces.end());
Expand Down Expand Up @@ -846,7 +846,7 @@ TEST_F(TestResourceManager, resource_availability_and_claiming_in_lifecycle)
hardware_interface::ResourceManager rm(ros2_control_test_assets::minimal_robot_urdf);

auto check_interfaces =
[](const std::vector<const char *> & interface_names, auto check_method, bool expected_result)
[](const std::vector<std::string> & interface_names, auto check_method, bool expected_result)
{
for (const auto & interface : interface_names)
{
Expand All @@ -855,8 +855,8 @@ TEST_F(TestResourceManager, resource_availability_and_claiming_in_lifecycle)
};

auto check_interface_claiming = [&](
const std::vector<const char *> & state_interface_names,
const std::vector<const char *> & command_interface_names,
const std::vector<std::string> & state_interface_names,
const std::vector<std::string> & command_interface_names,
bool expected_result)
{
std::vector<hardware_interface::LoanedStateInterface> states;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_

#include <string>
#include <vector>

namespace ros2_control_test_assets
{
Expand Down Expand Up @@ -414,26 +415,27 @@ const auto minimal_robot_missing_command_keys_urdf =
std::string(urdf_head) + std::string(hardware_resources_missing_command_keys) +
std::string(urdf_tail);

[[maybe_unused]] const auto TEST_ACTUATOR_HARDWARE_NAME = "TestActuatorHardware";
[[maybe_unused]] const auto TEST_ACTUATOR_HARDWARE_TYPE = "actuator";
[[maybe_unused]] const auto TEST_ACTUATOR_HARDWARE_CLASS_TYPE = "test_actuator";
[[maybe_unused]] const auto TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES = {
[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_NAME = "TestActuatorHardware";
[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_TYPE = "actuator";
[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_CLASS_TYPE = "test_actuator";
[[maybe_unused]] const std::vector<std::string> TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES = {
"joint1/position", "joint1/max_velocity"};
[[maybe_unused]] const auto TEST_ACTUATOR_HARDWARE_STATE_INTERFACES = {
[[maybe_unused]] const std::vector<std::string> TEST_ACTUATOR_HARDWARE_STATE_INTERFACES = {
"joint1/position", "joint1/velocity", "joint1/some_unlisted_interface"};

[[maybe_unused]] const auto TEST_SENSOR_HARDWARE_NAME = "TestSensorHardware";
[[maybe_unused]] const auto TEST_SENSOR_HARDWARE_TYPE = "sensor";
[[maybe_unused]] const auto TEST_SENSOR_HARDWARE_CLASS_TYPE = "test_sensor";
[[maybe_unused]] const auto TEST_SENSOR_HARDWARE_COMMAND_INTERFACES = {""};
[[maybe_unused]] const auto TEST_SENSOR_HARDWARE_STATE_INTERFACES = {"sensor1/velocity"};
[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_NAME = "TestSensorHardware";
[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_TYPE = "sensor";
[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_CLASS_TYPE = "test_sensor";
[[maybe_unused]] const std::vector<std::string> TEST_SENSOR_HARDWARE_COMMAND_INTERFACES = {""};
[[maybe_unused]] const std::vector<std::string> TEST_SENSOR_HARDWARE_STATE_INTERFACES = {
"sensor1/velocity"};

[[maybe_unused]] const auto TEST_SYSTEM_HARDWARE_NAME = "TestSystemHardware";
[[maybe_unused]] const auto TEST_SYSTEM_HARDWARE_TYPE = "system";
[[maybe_unused]] const auto TEST_SYSTEM_HARDWARE_CLASS_TYPE = "test_system";
[[maybe_unused]] const auto TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES = {
[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_NAME = "TestSystemHardware";
[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_TYPE = "system";
[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_CLASS_TYPE = "test_system";
[[maybe_unused]] const std::vector<std::string> TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES = {
"joint2/velocity", "joint2/max_acceleration", "joint3/velocity", "configuration/max_tcp_jerk"};
[[maybe_unused]] const auto TEST_SYSTEM_HARDWARE_STATE_INTERFACES = {
[[maybe_unused]] const std::vector<std::string> TEST_SYSTEM_HARDWARE_STATE_INTERFACES = {
"joint2/position", "joint2/velocity", "joint2/acceleration", "joint3/position",
"joint3/velocity", "joint3/acceleration", "configuration/max_tcp_jerk"};

Expand Down

0 comments on commit d632e89

Please sign in to comment.