Skip to content

Commit

Permalink
Add some additional tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl committed Feb 1, 2024
1 parent 62e4384 commit 2e13c3c
Show file tree
Hide file tree
Showing 2 changed files with 131 additions and 15 deletions.
12 changes: 12 additions & 0 deletions hardware_interface_testing/test/test_resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,12 @@ TEST_F(
ros2_control_test_assets::minimal_robot_not_existing_system_plugin);
}

TEST_F(ResourceManagerTest, expect_load_and_initialize_to_fail_when_there_are_dupplicate_of_hw_comp)
{
test_load_and_initialized_components_failure(
ros2_control_test_assets::minimal_robot_duplicated_component);
}

TEST_F(
ResourceManagerTest, expect_load_and_initialize_to_fail_when_a_hw_component_initialization_fails)
{
Expand All @@ -250,6 +256,12 @@ TEST_F(ResourceManagerTest, load_and_initialize_components_called_if_urdf_is_val
ASSERT_TRUE(rm.are_components_initialized());
}

TEST_F(ResourceManagerTest, load_and_initialize_components_called_if_async_urdf_is_valid)
{
TestableResourceManager rm(ros2_control_test_assets::minimal_async_robot_urdf);
ASSERT_TRUE(rm.are_components_initialized());
}

TEST_F(ResourceManagerTest, can_load_and_initialize_components_later)
{
TestableResourceManager rm;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,55 @@ const auto hardware_resources =
</ros2_control>
)";

const auto async_hardware_resources =
R"(
<ros2_control name="TestActuatorHardware" type="actuator" is_async="true">
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
<ros2_control name="TestSensorHardware" type="sensor" is_async="true">
<hardware>
<plugin>test_sensor</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<sensor name="sensor1">
<state_interface name="velocity"/>
</sensor>
</ros2_control>
<ros2_control name="TestSystemHardware" type="system" is_async="true">
<hardware>
<plugin>test_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint2">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="max_acceleration" />
</joint>
<joint name="joint3">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
)";

const auto unitilizable_hardware_resources =
R"(
<ros2_control name="TestUnitilizableActuatorHardware" type="actuator">
Expand Down Expand Up @@ -253,25 +302,25 @@ const auto hardware_resources_not_existing_actuator_plugin =
<plugin>test_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint2">
</hardware>
<joint name="joint2">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="max_acceleration" />
</joint>
<joint name="joint3">
</joint>
<joint name="joint3">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
</joint>
</ros2_control>
)";

const auto hardware_resources_not_existing_sensor_plugin =
Expand Down Expand Up @@ -302,25 +351,25 @@ const auto hardware_resources_not_existing_sensor_plugin =
<plugin>test_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint2">
</hardware>
<joint name="joint2">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="max_acceleration" />
</joint>
<joint name="joint3">
</joint>
<joint name="joint3">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="configuration">
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
</joint>
</ros2_control>
)";
const auto hardware_resources_not_existing_system_plugin =
R"(
Expand Down Expand Up @@ -371,6 +420,55 @@ const auto hardware_resources_not_existing_system_plugin =
</ros2_control>
)";

const auto hardware_resources_duplicated_component =
R"(
<ros2_control name="TestActuatorHardware" type="actuator">
<hardware>
<plugin>test_actuator</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<command_interface name="max_velocity" />
</joint>
</ros2_control>
<ros2_control name="TestActuatorHardware" type="sensor">
<hardware>
<plugin>test_sensor</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<sensor name="sensor1">
<state_interface name="velocity"/>
</sensor>
</ros2_control>
<ros2_control name="TestSystemHardware" type="system">
<hardware>
<plugin>test_system</plugin>
<param name="example_param_write_for_sec">2</param>
<param name="example_param_read_for_sec">2</param>
</hardware>
<joint name="joint2">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="max_acceleration" />
</joint>
<joint name="joint3">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
</joint>
<joint name="configuration">
<command_interface name="max_tcp_jerk"/>
<state_interface name="max_tcp_jerk"/>
</joint>
</ros2_control>
)";

const auto hardware_resources_actuator_initializaion_error =
R"(
<ros2_control name="TestActuatorHardware" type="actuator">
Expand Down Expand Up @@ -731,6 +829,8 @@ const auto diffbot_urdf =

const auto minimal_robot_urdf =
std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
const auto minimal_async_robot_urdf =
std::string(urdf_head) + std::string(async_hardware_resources) + std::string(urdf_tail);
const auto minimal_unitilizable_robot_urdf =
std::string(urdf_head) + std::string(unitilizable_hardware_resources) + std::string(urdf_tail);

Expand All @@ -744,6 +844,10 @@ const auto minimal_robot_not_existing_system_plugin =
std::string(urdf_head) + std::string(hardware_resources_not_existing_system_plugin) +
std::string(urdf_tail);

const auto minimal_robot_duplicated_component =
std::string(urdf_head) + std::string(hardware_resources_duplicated_component) +
std::string(urdf_tail);

const auto minimal_robot_actuator_initialization_error =
std::string(urdf_head) + std::string(hardware_resources_not_existing_actuator_plugin) +
std::string(urdf_tail);
Expand Down

0 comments on commit 2e13c3c

Please sign in to comment.