From 33ef77ef96dfca754f4cc7cd4cf24da21bd05204 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 14 Aug 2024 12:26:41 +0000 Subject: [PATCH 1/5] Add debug output --- .github/workflows/humble-coverage-build.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/humble-coverage-build.yml b/.github/workflows/humble-coverage-build.yml index 209c931d4e..c28d2ff956 100644 --- a/.github/workflows/humble-coverage-build.yml +++ b/.github/workflows/humble-coverage-build.yml @@ -30,7 +30,8 @@ on: jobs: coverage_humble: - uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@debug secrets: inherit with: ros_distro: humble + debug: true From bb2fab2c7ba322b4ffa12e6bae90f085799a85d2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 27 Jul 2024 12:32:46 +0200 Subject: [PATCH 2/5] Add a pytest launch file to test ros2_control_node (#1636) --- controller_manager/CMakeLists.txt | 5 + controller_manager/package.xml | 1 + .../test/test_ros2_control_node.yaml | 11 +++ .../test/test_ros2_control_node_launch.py | 95 +++++++++++++++++++ 4 files changed, 112 insertions(+) create mode 100644 controller_manager/test/test_ros2_control_node.yaml create mode 100644 controller_manager/test/test_ros2_control_node_launch.py diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 29d489ad81..3a806ff67e 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -185,6 +185,11 @@ if(BUILD_TESTING) controller_manager_msgs ros2_control_test_assets ) + + find_package(ament_cmake_pytest REQUIRED) + install(FILES test/test_ros2_control_node.yaml + DESTINATION test) + ament_add_pytest_test(test_ros2_control_node test/test_ros2_control_node_launch.py) endif() # Install Python modules diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 28f30141f6..da555b2e44 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -28,6 +28,7 @@ std_msgs ament_cmake_gmock + ament_cmake_pytest hardware_interface_testing ros2_control_test_assets diff --git a/controller_manager/test/test_ros2_control_node.yaml b/controller_manager/test/test_ros2_control_node.yaml new file mode 100644 index 0000000000..ce0602d6b3 --- /dev/null +++ b/controller_manager/test/test_ros2_control_node.yaml @@ -0,0 +1,11 @@ +controller_manager: + ros__parameters: + update_rate: 100 # Hz + +ctrl_with_parameters_and_type: + ros__parameters: + type: "controller_manager/test_controller" + joint_names: ["joint0"] + +joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster diff --git a/controller_manager/test/test_ros2_control_node_launch.py b/controller_manager/test/test_ros2_control_node_launch.py new file mode 100644 index 0000000000..c8c1136849 --- /dev/null +++ b/controller_manager/test/test_ros2_control_node_launch.py @@ -0,0 +1,95 @@ +# Copyright (c) 2024 AIT - Austrian Institute of Technology GmbH +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the {copyright_holder} nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Christoph Froehlich + +import pytest +import unittest +import time + +from launch import LaunchDescription +from launch.substitutions import PathJoinSubstitution +from launch_ros.substitutions import FindPackageShare +from launch_testing.actions import ReadyToTest + +import launch_testing.markers +import rclpy +import launch_ros.actions +from rclpy.node import Node + + +# Executes the given launch file and checks if all nodes can be started +@pytest.mark.launch_test +def generate_test_description(): + + robot_controllers = PathJoinSubstitution( + [ + FindPackageShare("controller_manager"), + "test", + "test_ros2_control_node.yaml", + ] + ) + + control_node = launch_ros.actions.Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + ) + + return LaunchDescription([control_node, ReadyToTest()]) + + +# This is our test fixture. Each method is a test case. +# These run alongside the processes specified in generate_test_description() +class TestFixture(unittest.TestCase): + + def setUp(self): + rclpy.init() + self.node = Node("test_node") + + def tearDown(self): + self.node.destroy_node() + rclpy.shutdown() + + def test_node_start(self): + start = time.time() + found = False + while time.time() - start < 2.0 and not found: + found = "controller_manager" in self.node.get_node_names() + time.sleep(0.1) + assert found, "controller_manager not found!" + + +@launch_testing.post_shutdown_test() +# These tests are run after the processes in generate_test_description() have shutdown. +class TestDescriptionCraneShutdown(unittest.TestCase): + + def test_exit_codes(self, proc_info): + """Check if the processes exited normally.""" + launch_testing.asserts.assertExitCodes(proc_info) From 106396441e16096a24af306b90b6b8b733923194 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 14 Aug 2024 20:10:36 +0000 Subject: [PATCH 3/5] [CI] Add coveragepy and remove ignore: test (#1668) --- codecov.yml | 2 -- controller_manager/package.xml | 1 + controller_manager/test/test_spawner_unspawner.cpp | 14 ++++++++++---- 3 files changed, 11 insertions(+), 6 deletions(-) diff --git a/codecov.yml b/codecov.yml index 97106f32ff..764afc34e6 100644 --- a/codecov.yml +++ b/codecov.yml @@ -14,8 +14,6 @@ fixes: comment: layout: "diff, flags, files" behavior: default -ignore: - - "**/test" flags: unittests: paths: diff --git a/controller_manager/package.xml b/controller_manager/package.xml index da555b2e44..2bacfd6289 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -29,6 +29,7 @@ ament_cmake_gmock ament_cmake_pytest + python3-coverage hardware_interface_testing ros2_control_test_assets diff --git a/controller_manager/test/test_spawner_unspawner.cpp b/controller_manager/test/test_spawner_unspawner.cpp index 7c03a8862d..65e3dc5b75 100644 --- a/controller_manager/test/test_spawner_unspawner.cpp +++ b/controller_manager/test/test_spawner_unspawner.cpp @@ -27,6 +27,7 @@ using ::testing::_; using ::testing::Return; +const char coveragepy_script[] = "python3 -m coverage run --append --branch"; using namespace std::chrono_literals; class TestLoadController : public ControllerManagerFixture @@ -67,14 +68,18 @@ class TestLoadController : public ControllerManagerFixture Date: Wed, 14 Aug 2024 22:27:33 +0200 Subject: [PATCH 4/5] Update .github/workflows/humble-coverage-build.yml --- .github/workflows/humble-coverage-build.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/workflows/humble-coverage-build.yml b/.github/workflows/humble-coverage-build.yml index c28d2ff956..2f2d1fa37a 100644 --- a/.github/workflows/humble-coverage-build.yml +++ b/.github/workflows/humble-coverage-build.yml @@ -30,8 +30,7 @@ on: jobs: coverage_humble: - uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@debug + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@mster secrets: inherit with: ros_distro: humble - debug: true From 6d6eea361c1c4989da380806b6e7e6173e2e3df0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 14 Aug 2024 23:09:59 +0200 Subject: [PATCH 5/5] Fix typo --- .github/workflows/humble-coverage-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/humble-coverage-build.yml b/.github/workflows/humble-coverage-build.yml index 2f2d1fa37a..209c931d4e 100644 --- a/.github/workflows/humble-coverage-build.yml +++ b/.github/workflows/humble-coverage-build.yml @@ -30,7 +30,7 @@ on: jobs: coverage_humble: - uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@mster + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master secrets: inherit with: ros_distro: humble