Skip to content

Commit

Permalink
Move test_components to own package (backport #1325) (#1340)
Browse files Browse the repository at this point in the history
* Move `test_components` to own package (#1325)

(cherry picked from commit 0bdcd41)

---------

Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
Co-authored-by: Dr. Denis <denis@stoglrobotics.de>
  • Loading branch information
3 people authored Jan 26, 2024
1 parent dc7b7be commit 9bab433
Show file tree
Hide file tree
Showing 14 changed files with 112 additions and 54 deletions.
1 change: 1 addition & 0 deletions .github/workflows/ci-coverage-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ jobs:
ros2controlcli
ros2_control
ros2_control_test_assets
hardware_interface_testing
transmission_interface

vcs-repo-file-url: |
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/ci-ros-lint.yml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ jobs:
controller_manager
controller_manager_msgs
hardware_interface
hardware_interface_testing
ros2controlcli
ros2_control
ros2_control_test_assets
Expand All @@ -49,6 +50,7 @@ jobs:
controller_manager
controller_manager_msgs
hardware_interface
hardware_interface_testing
ros2controlcli
ros2_control
ros2_control_test_assets
Expand Down
2 changes: 2 additions & 0 deletions controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@
<depend>std_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>hardware_interface_testing</test_depend>
<test_depend>ros2_control_test_assets</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
22 changes: 0 additions & 22 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -138,19 +138,6 @@ if(BUILD_TESTING)
target_link_libraries(test_component_parser ${PROJECT_NAME})
ament_target_dependencies(test_component_parser ros2_control_test_assets)

add_library(test_components SHARED
test/test_components/test_actuator.cpp
test/test_components/test_sensor.cpp
test/test_components/test_system.cpp)
target_link_libraries(test_components ${PROJECT_NAME})
ament_target_dependencies(test_components
pluginlib)
install(TARGETS test_components
DESTINATION lib
)
pluginlib_export_plugin_description_file(
${PROJECT_NAME} test/test_components/test_components.xml)

add_library(test_hardware_components SHARED
test/test_hardware_components/test_single_joint_actuator.cpp
test/test_hardware_components/test_force_torque_sensor.cpp
Expand All @@ -166,15 +153,6 @@ if(BUILD_TESTING)
pluginlib_export_plugin_description_file(
${PROJECT_NAME} test/test_hardware_components/test_hardware_components.xml
)

ament_add_gmock(test_resource_manager test/test_resource_manager.cpp)
target_link_libraries(test_resource_manager ${PROJECT_NAME})
ament_target_dependencies(test_resource_manager ros2_control_test_assets)

ament_add_gmock(test_resource_manager_prepare_perform_switch test/test_resource_manager_prepare_perform_switch.cpp)
target_link_libraries(test_resource_manager_prepare_perform_switch hardware_interface)
ament_target_dependencies(test_resource_manager_prepare_perform_switch ros2_control_test_assets)

ament_add_gmock(test_generic_system test/mock_components/test_generic_system.cpp)
target_include_directories(test_generic_system PRIVATE include)
target_link_libraries(test_generic_system ${PROJECT_NAME})
Expand Down
46 changes: 46 additions & 0 deletions hardware_interface_testing/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
cmake_minimum_required(VERSION 3.16)
project(hardware_interface_testing LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
control_msgs
hardware_interface
lifecycle_msgs
pluginlib
rclcpp_lifecycle
ros2_control_test_assets
)

find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

add_library(test_components SHARED
test/test_components/test_actuator.cpp
test/test_components/test_sensor.cpp
test/test_components/test_system.cpp
)
ament_target_dependencies(test_components hardware_interface pluginlib ros2_control_test_assets)
install(TARGETS test_components
DESTINATION lib
)
pluginlib_export_plugin_description_file(
hardware_interface test/test_components/test_components.xml)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)

ament_add_gmock(test_resource_manager test/test_resource_manager.cpp)
ament_target_dependencies(test_resource_manager hardware_interface ros2_control_test_assets)

ament_add_gmock(test_resource_manager_prepare_perform_switch test/test_resource_manager_prepare_perform_switch.cpp)
ament_target_dependencies(test_resource_manager_prepare_perform_switch hardware_interface ros2_control_test_assets)

endif()

ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
4 changes: 4 additions & 0 deletions hardware_interface_testing/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
# hardware_interface_testing

This package contains a set of hardware interfaces and controllers that can be used for other
packages to test their functionality.
25 changes: 25 additions & 0 deletions hardware_interface_testing/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface_testing</name>
<version>0.0.0</version>
<description>ros2_control hardware interface testing</description>
<maintainer email="bence.magyar.robotics@gmail.com">Bence Magyar</maintainer>
<maintainer email="denis@stoglrobotics.de">Denis Štogl</maintainer>
<maintainer email="christoph.froehlich@ait.ac.at">Christoph Froehlich</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>control_msgs</depend>
<depend>hardware_interface</depend>
<depend>lifecycle_msgs</depend>
<depend>pluginlib</depend>
<depend>rclcpp_lifecycle</depend>
<depend>ros2_control_test_assets</depend>

<test_depend>ament_cmake_gmock</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -232,73 +232,73 @@ TEST_F(ResourceManagerTest, resource_claiming)
// Activate components to get all interfaces available
activate_components(rm);

const auto key = "joint1/position";
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_FALSE(rm.command_interface_is_claimed(key));
const auto command_interface = "joint1/position";
EXPECT_TRUE(rm.command_interface_is_available(command_interface));
EXPECT_FALSE(rm.command_interface_is_claimed(command_interface));

{
auto position_command_interface = rm.claim_command_interface(key);
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_TRUE(rm.command_interface_is_claimed(key));
auto position_command_interface = rm.claim_command_interface(command_interface);
EXPECT_TRUE(rm.command_interface_is_available(command_interface));
EXPECT_TRUE(rm.command_interface_is_claimed(command_interface));
{
EXPECT_ANY_THROW(rm.claim_command_interface(key));
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_ANY_THROW(rm.claim_command_interface(command_interface));
EXPECT_TRUE(rm.command_interface_is_available(command_interface));
}
}
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_FALSE(rm.command_interface_is_claimed(key));
EXPECT_TRUE(rm.command_interface_is_available(command_interface));
EXPECT_FALSE(rm.command_interface_is_claimed(command_interface));

// command interfaces can only be claimed once
for (const auto & key :
for (const auto & interface_key :
{"joint1/position", "joint1/position", "joint1/position", "joint2/velocity",
"joint3/velocity"})
{
{
auto interface = rm.claim_command_interface(key);
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_TRUE(rm.command_interface_is_claimed(key));
auto interface = rm.claim_command_interface(interface_key);
EXPECT_TRUE(rm.command_interface_is_available(interface_key));
EXPECT_TRUE(rm.command_interface_is_claimed(interface_key));
{
EXPECT_ANY_THROW(rm.claim_command_interface(key));
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_ANY_THROW(rm.claim_command_interface(interface_key));
EXPECT_TRUE(rm.command_interface_is_available(interface_key));
}
}
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_FALSE(rm.command_interface_is_claimed(key));
EXPECT_TRUE(rm.command_interface_is_available(interface_key));
EXPECT_FALSE(rm.command_interface_is_claimed(interface_key));
}

// TODO(destogl): This claim test is not true.... can not be...
// state interfaces can be claimed multiple times
for (const auto & key :
for (const auto & interface_key :
{"joint1/position", "joint1/velocity", "sensor1/velocity", "joint2/position",
"joint3/position"})
{
{
EXPECT_TRUE(rm.state_interface_is_available(key));
auto interface = rm.claim_state_interface(key);
EXPECT_TRUE(rm.state_interface_is_available(interface_key));
auto interface = rm.claim_state_interface(interface_key);
{
EXPECT_TRUE(rm.state_interface_is_available(key));
EXPECT_NO_THROW(rm.claim_state_interface(key));
EXPECT_TRUE(rm.state_interface_is_available(interface_key));
EXPECT_NO_THROW(rm.claim_state_interface(interface_key));
}
}
}

std::vector<hardware_interface::LoanedCommandInterface> interfaces;
const auto interface_names = {"joint1/position", "joint2/velocity", "joint3/velocity"};
for (const auto & key : interface_names)
for (const auto & interface : interface_names)
{
EXPECT_TRUE(rm.command_interface_is_available(key));
interfaces.emplace_back(rm.claim_command_interface(key));
EXPECT_TRUE(rm.command_interface_is_available(interface));
interfaces.emplace_back(rm.claim_command_interface(interface));
}
for (const auto & key : interface_names)
for (const auto & interface : interface_names)
{
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_TRUE(rm.command_interface_is_claimed(key));
EXPECT_TRUE(rm.command_interface_is_available(interface));
EXPECT_TRUE(rm.command_interface_is_claimed(interface));
}
interfaces.clear();
for (const auto & key : interface_names)
for (const auto & interface : interface_names)
{
EXPECT_TRUE(rm.command_interface_is_available(key));
EXPECT_FALSE(rm.command_interface_is_claimed(key));
EXPECT_TRUE(rm.command_interface_is_available(interface));
EXPECT_FALSE(rm.command_interface_is_claimed(interface));
}
}

Expand Down

0 comments on commit 9bab433

Please sign in to comment.