From 786d5b5eceb7733eceb2a6720d00b200cec46357 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Fri, 2 Feb 2024 11:26:55 +0100 Subject: [PATCH 01/20] [RHEL-CI] Source underlay with generate_parameter_library --- .github/workflows/humble-rhel-binary-build.yml | 1 + .github/workflows/iron-rhel-binary-build.yml | 1 + .github/workflows/rolling-rhel-binary-build.yml | 1 + 3 files changed, 3 insertions(+) diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index ed37092520..9d39ae10b6 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -26,6 +26,7 @@ jobs: - name: Build and test run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/setup.bash colcon build --packages-skip rqt_controller_manager colcon test --packages-skip rqt_controller_manager ros2controlcli colcon test-result --verbose diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index fc48bd80ea..81a70e4329 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -27,6 +27,7 @@ jobs: - name: Build and test run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/setup.bash colcon build --packages-skip rqt_controller_manager colcon test --packages-skip rqt_controller_manager ros2controlcli colcon test-result --verbose diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index 06a5411c24..9c755769a1 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -27,6 +27,7 @@ jobs: - name: Build and test run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/setup.bash colcon build --packages-skip rqt_controller_manager colcon test --packages-skip rqt_controller_manager ros2controlcli colcon test-result --verbose From a1b03771eb89425af2dcb06ed57e16de7e3809c4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 5 Feb 2024 11:01:38 +0100 Subject: [PATCH 02/20] [CI] Fix ref for scheduled pipelines (#1361) --- .github/workflows/humble-debian-build.yml | 1 + .github/workflows/humble-rhel-binary-build.yml | 1 + .github/workflows/iron-debian-build.yml | 1 + .github/workflows/iron-rhel-binary-build.yml | 2 +- .github/workflows/rolling-debian-build.yml | 2 ++ .github/workflows/rolling-rhel-binary-build.yml | 3 ++- 6 files changed, 8 insertions(+), 2 deletions(-) diff --git a/.github/workflows/humble-debian-build.yml b/.github/workflows/humble-debian-build.yml index 0db1f58210..a3b070355c 100644 --- a/.github/workflows/humble-debian-build.yml +++ b/.github/workflows/humble-debian-build.yml @@ -20,6 +20,7 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - name: Build and test shell: bash run: | diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index 9d39ae10b6..774a04753f 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -19,6 +19,7 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - name: Install dependencies run: | rosdep update diff --git a/.github/workflows/iron-debian-build.yml b/.github/workflows/iron-debian-build.yml index 405e4f9135..75714c5c2a 100644 --- a/.github/workflows/iron-debian-build.yml +++ b/.github/workflows/iron-debian-build.yml @@ -20,6 +20,7 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - name: Build and test shell: bash run: | diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index 81a70e4329..8e8851e448 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -8,7 +8,6 @@ on: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' - jobs: iron_rhel_binary: name: Iron RHEL binary build @@ -20,6 +19,7 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - name: Install dependencies run: | rosdep update diff --git a/.github/workflows/rolling-debian-build.yml b/.github/workflows/rolling-debian-build.yml index 098af45029..b94fd800f9 100644 --- a/.github/workflows/rolling-debian-build.yml +++ b/.github/workflows/rolling-debian-build.yml @@ -20,6 +20,8 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + # default behavior is correct on master branch + # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - name: Build and test shell: bash run: | diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index 9c755769a1..e8ebf6eb2c 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -8,7 +8,6 @@ on: # Run every day to detect flakiness and broken dependencies - cron: '03 1 * * *' - jobs: rolling_rhel_binary: name: Rolling RHEL binary build @@ -20,6 +19,8 @@ jobs: - uses: actions/checkout@v4 with: path: src/ros2_control + # default behavior is correct on master branch + # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - name: Install dependencies run: | rosdep update From 967460aad9ce750fb72e5b74f112bcb0178d5dfa Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 7 Feb 2024 02:17:57 +0000 Subject: [PATCH 03/20] Bump codecov/codecov-action from 3.1.5 to 4.0.1 (#1372) --- .github/workflows/ci-coverage-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci-coverage-build.yml b/.github/workflows/ci-coverage-build.yml index 171a313fc0..efca7ca45e 100644 --- a/.github/workflows/ci-coverage-build.yml +++ b/.github/workflows/ci-coverage-build.yml @@ -42,7 +42,7 @@ jobs: } } colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: codecov/codecov-action@v3.1.5 + - uses: codecov/codecov-action@v4.0.1 with: file: ros_ws/lcov/total_coverage.info flags: unittests From b8c5418aff40ae1762c3811a6958ce4e5c1621ba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 7 Feb 2024 03:19:02 +0100 Subject: [PATCH 04/20] remove workflow dispatch branch (#1362) --- .github/workflows/humble-binary-build-main.yml | 2 -- .github/workflows/humble-binary-build-testing.yml | 2 -- .github/workflows/humble-semi-binary-build-main.yml | 2 -- .github/workflows/humble-semi-binary-build-testing.yml | 2 -- .github/workflows/humble-source-build.yml | 2 -- .github/workflows/iron-binary-build-main.yml | 2 -- .github/workflows/iron-binary-build-testing.yml | 2 -- .github/workflows/iron-semi-binary-build-main.yml | 2 -- .github/workflows/iron-semi-binary-build-testing.yml | 2 -- .github/workflows/iron-source-build.yml | 2 -- .github/workflows/rolling-binary-build-main.yml | 2 -- .github/workflows/rolling-semi-binary-build-testing.yml | 2 -- .github/workflows/rolling-source-build.yml | 2 -- 13 files changed, 26 deletions(-) diff --git a/.github/workflows/humble-binary-build-main.yml b/.github/workflows/humble-binary-build-main.yml index a438d7a9e5..1fafd01c9e 100644 --- a/.github/workflows/humble-binary-build-main.yml +++ b/.github/workflows/humble-binary-build-main.yml @@ -4,8 +4,6 @@ name: Humble Binary Build - main on: workflow_dispatch: - branches: - - humble pull_request: branches: - humble diff --git a/.github/workflows/humble-binary-build-testing.yml b/.github/workflows/humble-binary-build-testing.yml index 5a61534d4e..99ff6ccd4a 100644 --- a/.github/workflows/humble-binary-build-testing.yml +++ b/.github/workflows/humble-binary-build-testing.yml @@ -4,8 +4,6 @@ name: Humble Binary Build - testing on: workflow_dispatch: - branches: - - humble pull_request: branches: - humble diff --git a/.github/workflows/humble-semi-binary-build-main.yml b/.github/workflows/humble-semi-binary-build-main.yml index 539477a302..88591b69f7 100644 --- a/.github/workflows/humble-semi-binary-build-main.yml +++ b/.github/workflows/humble-semi-binary-build-main.yml @@ -3,8 +3,6 @@ name: Humble Semi-Binary Build - main on: workflow_dispatch: - branches: - - humble pull_request: branches: - humble diff --git a/.github/workflows/humble-semi-binary-build-testing.yml b/.github/workflows/humble-semi-binary-build-testing.yml index 889822e7f2..3d6b2717e3 100644 --- a/.github/workflows/humble-semi-binary-build-testing.yml +++ b/.github/workflows/humble-semi-binary-build-testing.yml @@ -3,8 +3,6 @@ name: Humble Semi-Binary Build - testing on: workflow_dispatch: - branches: - - humble pull_request: branches: - humble diff --git a/.github/workflows/humble-source-build.yml b/.github/workflows/humble-source-build.yml index ff0fd62e05..a40d53f8e3 100644 --- a/.github/workflows/humble-source-build.yml +++ b/.github/workflows/humble-source-build.yml @@ -1,8 +1,6 @@ name: Humble Source Build on: workflow_dispatch: - branches: - - humble push: branches: - humble diff --git a/.github/workflows/iron-binary-build-main.yml b/.github/workflows/iron-binary-build-main.yml index bc2dbd96cc..440b573cb9 100644 --- a/.github/workflows/iron-binary-build-main.yml +++ b/.github/workflows/iron-binary-build-main.yml @@ -4,8 +4,6 @@ name: Iron Binary Build - main on: workflow_dispatch: - branches: - - iron pull_request: branches: - iron diff --git a/.github/workflows/iron-binary-build-testing.yml b/.github/workflows/iron-binary-build-testing.yml index 512c4b55e4..78e13f2528 100644 --- a/.github/workflows/iron-binary-build-testing.yml +++ b/.github/workflows/iron-binary-build-testing.yml @@ -4,8 +4,6 @@ name: Iron Binary Build - testing on: workflow_dispatch: - branches: - - iron pull_request: branches: - iron diff --git a/.github/workflows/iron-semi-binary-build-main.yml b/.github/workflows/iron-semi-binary-build-main.yml index 1399e8b32b..c5697d6e74 100644 --- a/.github/workflows/iron-semi-binary-build-main.yml +++ b/.github/workflows/iron-semi-binary-build-main.yml @@ -3,8 +3,6 @@ name: Iron Semi-Binary Build - main on: workflow_dispatch: - branches: - - iron pull_request: branches: - iron diff --git a/.github/workflows/iron-semi-binary-build-testing.yml b/.github/workflows/iron-semi-binary-build-testing.yml index b29f798931..0055e38cba 100644 --- a/.github/workflows/iron-semi-binary-build-testing.yml +++ b/.github/workflows/iron-semi-binary-build-testing.yml @@ -3,8 +3,6 @@ name: Iron Semi-Binary Build - testing on: workflow_dispatch: - branches: - - iron pull_request: branches: - iron diff --git a/.github/workflows/iron-source-build.yml b/.github/workflows/iron-source-build.yml index 1e9d865c49..34372a4178 100644 --- a/.github/workflows/iron-source-build.yml +++ b/.github/workflows/iron-source-build.yml @@ -1,8 +1,6 @@ name: Iron Source Build on: workflow_dispatch: - branches: - - iron push: branches: - iron diff --git a/.github/workflows/rolling-binary-build-main.yml b/.github/workflows/rolling-binary-build-main.yml index 05a9b9c0b2..1777810661 100644 --- a/.github/workflows/rolling-binary-build-main.yml +++ b/.github/workflows/rolling-binary-build-main.yml @@ -4,8 +4,6 @@ name: Rolling Binary Build - main on: workflow_dispatch: - branches: - - master pull_request: branches: - master diff --git a/.github/workflows/rolling-semi-binary-build-testing.yml b/.github/workflows/rolling-semi-binary-build-testing.yml index 4ddfcf5057..17d290c45b 100644 --- a/.github/workflows/rolling-semi-binary-build-testing.yml +++ b/.github/workflows/rolling-semi-binary-build-testing.yml @@ -3,8 +3,6 @@ name: Rolling Semi-Binary Build - testing on: workflow_dispatch: - branches: - - master pull_request: branches: - master diff --git a/.github/workflows/rolling-source-build.yml b/.github/workflows/rolling-source-build.yml index b96ad0298e..475e509e0f 100644 --- a/.github/workflows/rolling-source-build.yml +++ b/.github/workflows/rolling-source-build.yml @@ -1,8 +1,6 @@ name: Rolling Source Build on: workflow_dispatch: - branches: - - master push: branches: - master From 3252a27c4f73678b6b4e215f83d04c4aac442945 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Thu, 8 Feb 2024 02:51:04 +0100 Subject: [PATCH 05/20] [CI] Improvements and Cleanups (#1376) --- .github/workflows/ci-ros-lint.yml | 35 ++++++++----------- .github/workflows/humble-debian-build.yml | 13 +++++-- .../workflows/humble-rhel-binary-build.yml | 17 ++++++--- .github/workflows/iron-debian-build.yml | 13 +++++-- .github/workflows/iron-rhel-binary-build.yml | 18 +++++++--- .github/workflows/rolling-debian-build.yml | 12 +++++-- .../workflows/rolling-rhel-binary-build.yml | 18 +++++++--- 7 files changed, 84 insertions(+), 42 deletions(-) diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml index 52da5edfe4..785afa5ede 100644 --- a/.github/workflows/ci-ros-lint.yml +++ b/.github/workflows/ci-ros-lint.yml @@ -2,6 +2,18 @@ name: ROS Lint on: pull_request: +env: + package-name: + controller_interface + controller_manager + controller_manager_msgs + hardware_interface + hardware_interface_testing + ros2controlcli + ros2_control + ros2_control_test_assets + transmission_interface + jobs: ament_lint: name: ament_${{ matrix.linter }} @@ -19,17 +31,7 @@ jobs: with: distribution: rolling linter: ${{ matrix.linter }} - package-name: - controller_interface - controller_manager - controller_manager_msgs - hardware_interface - hardware_interface_testing - ros2controlcli - ros2_control - ros2_control_test_assets - transmission_interface - + package-name: ${{ env.package-name }} ament_lint_100: name: ament_${{ matrix.linter }} runs-on: ubuntu-latest @@ -45,13 +47,4 @@ jobs: distribution: rolling linter: cpplint arguments: "--linelength=100 --filter=-whitespace/newline" - package-name: - controller_interface - controller_manager - controller_manager_msgs - hardware_interface - hardware_interface_testing - ros2controlcli - ros2_control - ros2_control_test_assets - transmission_interface + package-name: ${{ env.package-name }} diff --git a/.github/workflows/humble-debian-build.yml b/.github/workflows/humble-debian-build.yml index a3b070355c..482504c59a 100644 --- a/.github/workflows/humble-debian-build.yml +++ b/.github/workflows/humble-debian-build.yml @@ -15,17 +15,24 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: humble + skip-packages-build: rqt_controller_manager + skip-packages-test: rqt_controller_manager controller_manager_msgs container: ghcr.io/ros-controls/ros:humble-debian steps: - uses: actions/checkout@v4 with: path: src/ros2_control ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - - name: Build and test + - name: Build workspace shell: bash run: | source /opt/ros2_ws/install/setup.bash vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager control_msgs controller_manager_msgs + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-build }} + - name: Test workspace + shell: bash + continue-on-error: true + run: | + source /opt/ros2_ws/install/setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-test }} colcon test-result --verbose diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index 774a04753f..9d3b095e39 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -14,6 +14,7 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: humble + skip-packages: rqt_controller_manager container: ghcr.io/ros-controls/ros:humble-rhel steps: - uses: actions/checkout@v4 @@ -22,12 +23,20 @@ jobs: ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - name: Install dependencies run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash rosdep update rosdep install -iyr --from-path src/ros2_control || true - - name: Build and test + - name: Build workspace + run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} + - name: Test workspace + shell: bash + continue-on-error: true run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/setup.bash - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager ros2controlcli + source /opt/ros2_ws/install/local_setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} colcon test-result --verbose diff --git a/.github/workflows/iron-debian-build.yml b/.github/workflows/iron-debian-build.yml index 75714c5c2a..35db1eb8d9 100644 --- a/.github/workflows/iron-debian-build.yml +++ b/.github/workflows/iron-debian-build.yml @@ -15,17 +15,24 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: iron + skip-packages-build: rqt_controller_manager + skip-packages-test: rqt_controller_manager controller_manager_msgs container: ghcr.io/ros-controls/ros:iron-debian steps: - uses: actions/checkout@v4 with: path: src/ros2_control ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - - name: Build and test + - name: Build workspace shell: bash run: | source /opt/ros2_ws/install/setup.bash vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager control_msgs controller_manager_msgs + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-build }} + - name: Test workspace + shell: bash + continue-on-error: true + run: | + source /opt/ros2_ws/install/setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-test }} colcon test-result --verbose diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index 8e8851e448..435c3e9316 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -14,6 +14,7 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: iron + skip-packages: rqt_controller_manager container: ghcr.io/ros-controls/ros:iron-rhel steps: - uses: actions/checkout@v4 @@ -22,12 +23,21 @@ jobs: ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - name: Install dependencies run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash rosdep update rosdep install -iyr --from-path src/ros2_control || true - - name: Build and test + - name: Build workspace + # source also underlay workspace with generate_parameter_library on rhel9 + run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} + - name: Test workspace + shell: bash + continue-on-error: true run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/setup.bash - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager ros2controlcli + source /opt/ros2_ws/install/local_setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} colcon test-result --verbose diff --git a/.github/workflows/rolling-debian-build.yml b/.github/workflows/rolling-debian-build.yml index b94fd800f9..efe1422404 100644 --- a/.github/workflows/rolling-debian-build.yml +++ b/.github/workflows/rolling-debian-build.yml @@ -15,6 +15,7 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: rolling + skip-packages: rqt_controller_manager container: ghcr.io/ros-controls/ros:rolling-debian steps: - uses: actions/checkout@v4 @@ -22,11 +23,16 @@ jobs: path: src/ros2_control # default behavior is correct on master branch # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - - name: Build and test + - name: Build workspace shell: bash run: | source /opt/ros2_ws/install/setup.bash vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} + - name: Test workspace + shell: bash + continue-on-error: true + run: | + source /opt/ros2_ws/install/setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} colcon test-result --verbose diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index e8ebf6eb2c..8f2638405b 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -14,6 +14,7 @@ jobs: runs-on: ubuntu-latest env: ROS_DISTRO: rolling + skip-packages: rqt_controller_manager container: ghcr.io/ros-controls/ros:rolling-rhel steps: - uses: actions/checkout@v4 @@ -23,12 +24,21 @@ jobs: # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - name: Install dependencies run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash rosdep update rosdep install -iyr --from-path src/ros2_control || true - - name: Build and test + - name: Build workspace + # source also underlay workspace with generate_parameter_library on rhel9 + run: | + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + source /opt/ros2_ws/install/local_setup.bash + colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} + - name: Test workspace + shell: bash + continue-on-error: true run: | source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/setup.bash - colcon build --packages-skip rqt_controller_manager - colcon test --packages-skip rqt_controller_manager ros2controlcli + source /opt/ros2_ws/install/local_setup.bash + colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} colcon test-result --verbose From 6f57faf712c02956263b7c67282a5bdee01fc6d4 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Fri, 9 Feb 2024 11:25:06 +0100 Subject: [PATCH 06/20] check for state of the controller node before cleanup (#1363) --- controller_manager/src/controller_manager.cpp | 15 ++++++++++++++- .../test/test_controller_manager_srvs.cpp | 16 ++++++++++++++++ 2 files changed, 30 insertions(+), 1 deletion(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 4becabb0a4..1911bd6ff8 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -664,7 +664,20 @@ controller_interface::return_type ControllerManager::unload_controller( RCLCPP_DEBUG(get_logger(), "Cleanup controller"); // TODO(destogl): remove reference interface if chainable; i.e., add a separate method for // cleaning-up controllers? - controller.c->get_node()->cleanup(); + if (is_controller_inactive(*controller.c)) + { + RCLCPP_DEBUG( + get_logger(), "Controller '%s' is cleaned-up before unloading!", controller_name.c_str()); + // TODO(destogl): remove reference interface if chainable; i.e., add a separate method for + // cleaning-up controllers? + const auto new_state = controller.c->get_node()->cleanup(); + if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED) + { + RCLCPP_WARN( + get_logger(), "Failed to clean-up the controller '%s' before unloading!", + controller_name.c_str()); + } + } executor_->remove_node(controller.c->get_node()->get_node_base_interface()); to.erase(found_it); diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index 2cd5645bd8..cdec4806c1 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -456,6 +456,8 @@ TEST_F(TestControllerManagerSrvs, unload_controller_srv) result = call_service_and_wait(*client, request, srv_executor, true); ASSERT_TRUE(result->ok); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); EXPECT_EQ(0u, cm_->get_loaded_controllers().size()); } @@ -488,6 +490,8 @@ TEST_F(TestControllerManagerSrvs, robot_description_on_load_and_unload_controlle auto unload_request = std::make_shared(); unload_request->name = test_controller::TEST_CONTROLLER_NAME; auto result = call_service_and_wait(*unload_client, unload_request, srv_executor, true); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); EXPECT_EQ(0u, cm_->get_loaded_controllers().size()); // now load it and check if it got the new robot description @@ -508,6 +512,9 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv) rclcpp::Client::SharedPtr client = srv_node->create_client( "test_controller_manager/configure_controller"); + rclcpp::Client::SharedPtr unload_client = + srv_node->create_client( + "test_controller_manager/unload_controller"); auto request = std::make_shared(); request->name = test_controller::TEST_CONTROLLER_NAME; @@ -526,6 +533,15 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv) EXPECT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, cm_->get_loaded_controllers()[0].c->get_state().id()); + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id()); + + // now unload the controller and check the state + auto unload_request = std::make_shared(); + unload_request->name = test_controller::TEST_CONTROLLER_NAME; + ASSERT_TRUE(call_service_and_wait(*unload_client, unload_request, srv_executor, true)->ok); + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); + EXPECT_EQ(0u, cm_->get_loaded_controllers().size()); } TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers) From 55eeb09ef64e831c9a6d15049cf7f6fa64109b53 Mon Sep 17 00:00:00 2001 From: Mateus Menezes Date: Fri, 9 Feb 2024 07:37:21 -0300 Subject: [PATCH 07/20] Move hardware interface README content to sphinx documentation (#1342) --- hardware_interface/README.md | 132 +------------- .../doc/different_update_rates_userdoc.rst | 169 ++++++++++++++++++ .../doc/hardware_components_userdoc.rst | 1 + 3 files changed, 173 insertions(+), 129 deletions(-) create mode 100644 hardware_interface/doc/different_update_rates_userdoc.rst diff --git a/hardware_interface/README.md b/hardware_interface/README.md index 343158b698..76480201cb 100644 --- a/hardware_interface/README.md +++ b/hardware_interface/README.md @@ -1,131 +1,5 @@ -robot agnostic hardware_interface package. -This package will eventually be moved into its own repo. +# Overview -## Best practice for `hardware_interface` implementation -In the following section you can find some advices which will help you implement interface -for your specific hardware. +For detailed information about this package, please see the [ros2_control Documentation]! -### Best practice for having different update rate for each `hardware_interface` by counting loops -Current implementation of [ros2_control main node](https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/ros2_control_node.cpp) -has one update rate that controls the rate of the [`read()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L169) and [`write()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L178) -calls in [`hardware_interface(s)`](https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/system_interface.hpp). -In this section suggestion on how to run each interface implementation on its own update rate is introduced. - -1. Add parameters of main control loop update rate and desired update rate for your hardware interface. -``` - - - - - - - - my_system_interface/MySystemHardware - ${main_loop_update_rate} - ${desired_hw_update_rate} - - ... - - - - - -``` - -2. In you [`on_init()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L94) specific implementation fetch desired parameters: -``` -namespace my_system_interface -{ -hardware_interface::CallbackReturn MySystemHardware::on_init( - const hardware_interface::HardwareInfo & info) -{ - if ( - hardware_interface::SystemInterface::on_init(info) != - hardware_interface::CallbackReturn::SUCCESS) - { - return hardware_interface::CallbackReturn::ERROR; - } - - // declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ; - main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]); - desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]); - - ... -} -... -} // my_system_interface -``` - -3. In your `on_activate()` specific implementation reset internal loop counter -``` -hardware_interface::CallbackReturn MySystemHardware::on_activate( - const rclcpp_lifecycle::State & /*previous_state*/) -{ - // declaration in *.hpp file --> unsigned int update_loop_counter_ ; - update_loop_counter_ = 0; - ... -} -``` - -4. In your `read(const rclcpp::Time & time, const rclcpp::Duration & period)` and/or - `write(const rclcpp::Time & time, const rclcpp::Duration & period)` - specific implementations decide if you should interfere with your hardware -``` -hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) -{ - - bool hardware_go = main_loop_update_rate_ == 0 || - desired_hw_update_rate_ == 0 || - ((update_loop_counter_ % desired_hw_update_rate_) == 0); - - if (hardware_go){ - // hardware comms and operations - - } - ... - - // update counter - ++update_loop_counter_; - update_loop_counter_ %= main_loop_update_rate_; -} -``` - -### Best practice for having different update rate for each `hardware_interface` by measuring elapsed time -Another way to decide if hardware communication should be executed in the`read(const rclcpp::Time & time, const rclcpp::Duration & period)` and/or -`write(const rclcpp::Time & time, const rclcpp::Duration & period)` implementations is to measure elapsed time since last pass: - -``` -hardware_interface::CallbackReturn MySystemHardware::on_activate( - const rclcpp_lifecycle::State & /*previous_state*/) -{ - // declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ; - first_read_pass_ = first_write_pass_ = true; - ... -} - -hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) -{ - if (first_read_pass_ || (time - last_read_time_ ) > period) - { - first_read_pass_ = false; - // declaration in *.hpp file --> rclcpp::Time last_read_time_ ; - last_read_time_ = time; - // hardware comms and operations - ... - } - ... -} - -hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period) -{ - if (first_write_pass_ || (time - last_write_time_ ) > period) - { - first_write_pass_ = false; - // declaration in *.hpp file --> rclcpp::Time last_write_time_ ; - last_write_time_ = time; - // hardware comms and operations - ... - } - ... -} -``` +[ros2_control Documentation]: https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/hardware_components_userdoc.html diff --git a/hardware_interface/doc/different_update_rates_userdoc.rst b/hardware_interface/doc/different_update_rates_userdoc.rst new file mode 100644 index 0000000000..23f5e3564a --- /dev/null +++ b/hardware_interface/doc/different_update_rates_userdoc.rst @@ -0,0 +1,169 @@ +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst + +.. _different_update_rates_userdoc: + +Different update rates for Hardware Components +=============================================================================== + +In the following sections you can find some advice which will help you to implement Hardware +Components with update rates different from the main control loop. + +By counting loops +------------------------------------------------------------------------------- + +Current implementation of +`ros2_control main node `_ +has one update rate that controls the rate of the +`read(...) `_ +and `write(...) `_ +calls in `hardware_interface(s) `_. +To achieve different update rates for your hardware component you can use the following steps: + +.. _step-1: + +1. Add parameters of main control loop update rate and desired update rate for your hardware component + + .. code:: xml + + + + + + + + + my_system_interface/MySystemHardware + ${main_loop_update_rate} + ${desired_hw_update_rate} + + ... + + + + + + +.. _step-2: + +2. In you ``on_init()`` specific implementation fetch the desired parameters + + .. code:: cpp + + namespace my_system_interface + { + hardware_interface::CallbackReturn MySystemHardware::on_init( + const hardware_interface::HardwareInfo & info) + { + if ( + hardware_interface::SystemInterface::on_init(info) != + hardware_interface::CallbackReturn::SUCCESS) + { + return hardware_interface::CallbackReturn::ERROR; + } + + // declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ; + main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]); + desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]); + + ... + } + ... + } // my_system_interface + +3. In your ``on_activate`` specific implementation reset internal loop counter + + .. code:: cpp + + hardware_interface::CallbackReturn MySystemHardware::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) + { + // declaration in *.hpp file --> unsigned int update_loop_counter_ ; + update_loop_counter_ = 0; + ... + } + +4. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` + and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` + specific implementations decide if you should interfere with your hardware + + .. code:: cpp + + hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) + { + + bool hardware_go = main_loop_update_rate_ == 0 || + desired_hw_update_rate_ == 0 || + ((update_loop_counter_ % desired_hw_update_rate_) == 0); + + if (hardware_go){ + // hardware comms and operations + ... + } + ... + + // update counter + ++update_loop_counter_; + update_loop_counter_ %= main_loop_update_rate_; + } + +By measuring elapsed time +------------------------------------------------------------------------------- + +Another way to decide if hardware communication should be executed in the +``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` and/or +``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` +implementations is to measure elapsed time since last pass: + +1. In your ``on_activate`` specific implementation reset the flags that indicate + that this is the first pass of the ``read`` and ``write`` methods + + .. code:: cpp + + hardware_interface::CallbackReturn MySystemHardware::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) + { + // declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ; + first_read_pass_ = first_write_pass_ = true; + ... + } + +2. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` + and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)`` + specific implementations decide if you should interfere with your hardware + + .. code:: cpp + + hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) + { + if (first_read_pass_ || (time - last_read_time_ ) > desired_hw_update_period_) + { + first_read_pass_ = false; + // declaration in *.hpp file --> rclcpp::Time last_read_time_ ; + last_read_time_ = time; + // hardware comms and operations + ... + } + ... + } + + hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period) + { + if (first_write_pass_ || (time - last_write_time_ ) > desired_hw_update_period_) + { + first_write_pass_ = false; + // declaration in *.hpp file --> rclcpp::Time last_write_time_ ; + last_write_time_ = time; + // hardware comms and operations + ... + } + ... + } + +.. note:: + + The approach to get the desired update period value from the URDF and assign it to the variable + ``desired_hw_update_period_`` is the same as in the previous section (|step-1|_ and |step-2|_) but + with a different parameter name. + +.. |step-1| replace:: step 1 +.. |step-2| replace:: step 2 diff --git a/hardware_interface/doc/hardware_components_userdoc.rst b/hardware_interface/doc/hardware_components_userdoc.rst index 1a8c5e611b..404e90ee03 100644 --- a/hardware_interface/doc/hardware_components_userdoc.rst +++ b/hardware_interface/doc/hardware_components_userdoc.rst @@ -16,6 +16,7 @@ Guidelines and Best Practices Hardware Interface Types Writing a Hardware Component + Different Update Rates Handling of errors that happen during read() and write() calls From b3912f95663f187566278c4a360ac80af4af3ddf Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 9 Feb 2024 20:46:03 +0100 Subject: [PATCH 08/20] Add missing export macros in lexical_casts.hpp (#1382) --- .../include/hardware_interface/lexical_casts.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/hardware_interface/include/hardware_interface/lexical_casts.hpp b/hardware_interface/include/hardware_interface/lexical_casts.hpp index 846d9f757c..042361e392 100644 --- a/hardware_interface/include/hardware_interface/lexical_casts.hpp +++ b/hardware_interface/include/hardware_interface/lexical_casts.hpp @@ -21,6 +21,8 @@ #include #include +#include "hardware_interface/visibility_control.h" + namespace hardware_interface { @@ -29,8 +31,10 @@ namespace hardware_interface * from https://github.com/ros-planning/srdfdom/blob/ad17b8d25812f752c397a6011cec64aeff090c46/src/model.cpp#L53 */ +HARDWARE_INTERFACE_PUBLIC double stod(const std::string & s); +HARDWARE_INTERFACE_PUBLIC bool parse_bool(const std::string & bool_string); } // namespace hardware_interface From 06ecb5ff952fedbe602d4568a400eb08cf2594e1 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Mon, 12 Feb 2024 18:23:40 +0000 Subject: [PATCH 09/20] Update changelogs --- controller_interface/CHANGELOG.rst | 5 +++++ controller_manager/CHANGELOG.rst | 8 ++++++++ controller_manager_msgs/CHANGELOG.rst | 3 +++ hardware_interface/CHANGELOG.rst | 7 +++++++ hardware_interface_testing/CHANGELOG.rst | 3 +++ joint_limits/CHANGELOG.rst | 3 +++ ros2_control/CHANGELOG.rst | 3 +++ ros2_control_test_assets/CHANGELOG.rst | 3 +++ ros2controlcli/CHANGELOG.rst | 3 +++ rqt_controller_manager/CHANGELOG.rst | 3 +++ transmission_interface/CHANGELOG.rst | 3 +++ 11 files changed, 44 insertions(+) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index c6471c90f6..a6ba59c193 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* A method to get node options to setup the controller node #api-breaking (`#1169 `_) +* Contributors: Sai Kishor Kothakota + 4.4.0 (2024-01-31) ------------------ diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index f5bc17f0f3..7fae16a38d 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* check for state of the controller node before cleanup (`#1363 `_) +* [CM] Use explicit constants in controller tests. (`#1356 `_) +* [CM] Optimized debug output about interfaces when switching controllers. (`#1355 `_) +* A method to get node options to setup the controller node #api-breaking (`#1169 `_) +* Contributors: Dr. Denis, Sai Kishor Kothakota + 4.4.0 (2024-01-31) ------------------ * Move `test_components` to own package (`#1325 `_) diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 36245deaad..2ddca92db0 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index b5fb894e0c..7efdb5c067 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- +* Add missing export macros in lexical_casts.hpp (`#1382 `_) +* Move hardware interface README content to sphinx documentation (`#1342 `_) +* [Doc] Add documentation about initial_value regarding mock_hw (`#1352 `_) +* Contributors: Felix Exner (fexner), Mateus Menezes, Silvio Traversaro + 4.4.0 (2024-01-31) ------------------ * Move `test_components` to own package (`#1325 `_) diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 1ad077aa5c..242851f3fd 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ * Fix version diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index aa9d8db111..f2da17ef04 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ * [Format] Correct formatting of JointLimits URDF file. (`#1339 `_) diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index 3a54f3249c..f9c2ea473c 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index 9e2f966d0d..ff926d4e06 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index b659a5bf97..53abf7eb70 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 07724c98a3..10c1d3e81c 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index c63c29c3ab..854bbf2b51 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,9 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Forthcoming +----------- + 4.4.0 (2024-01-31) ------------------ From 3e0a02351e3a1f5134821e6bb68c64b66575b291 Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Mon, 12 Feb 2024 18:24:48 +0000 Subject: [PATCH 10/20] 4.5.0 --- controller_interface/CHANGELOG.rst | 4 ++-- controller_interface/package.xml | 2 +- controller_manager/CHANGELOG.rst | 4 ++-- controller_manager/package.xml | 2 +- controller_manager_msgs/CHANGELOG.rst | 4 ++-- controller_manager_msgs/package.xml | 2 +- hardware_interface/CHANGELOG.rst | 4 ++-- hardware_interface/package.xml | 2 +- hardware_interface_testing/CHANGELOG.rst | 4 ++-- hardware_interface_testing/package.xml | 2 +- joint_limits/CHANGELOG.rst | 4 ++-- joint_limits/package.xml | 2 +- ros2_control/CHANGELOG.rst | 4 ++-- ros2_control/package.xml | 2 +- ros2_control_test_assets/CHANGELOG.rst | 4 ++-- ros2_control_test_assets/package.xml | 2 +- ros2controlcli/CHANGELOG.rst | 4 ++-- ros2controlcli/package.xml | 2 +- ros2controlcli/setup.py | 2 +- rqt_controller_manager/CHANGELOG.rst | 4 ++-- rqt_controller_manager/package.xml | 2 +- rqt_controller_manager/setup.py | 2 +- transmission_interface/CHANGELOG.rst | 4 ++-- transmission_interface/package.xml | 2 +- 24 files changed, 35 insertions(+), 35 deletions(-) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index a6ba59c193..a795f57677 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ * A method to get node options to setup the controller node #api-breaking (`#1169 `_) * Contributors: Sai Kishor Kothakota diff --git a/controller_interface/package.xml b/controller_interface/package.xml index 919fdf8d20..c33007a3ef 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 4.4.0 + 4.5.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index 7fae16a38d..bda5e0dcbe 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ * check for state of the controller node before cleanup (`#1363 `_) * [CM] Use explicit constants in controller tests. (`#1356 `_) * [CM] Optimized debug output about interfaces when switching controllers. (`#1355 `_) diff --git a/controller_manager/package.xml b/controller_manager/package.xml index e58ff84c3d..1b18c86378 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 4.4.0 + 4.5.0 Description of controller_manager Bence Magyar Denis Štogl diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 2ddca92db0..cbb687b0a9 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 1beaf47741..9f7a523f29 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 4.4.0 + 4.5.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 7efdb5c067..09ca4d3d4a 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ * Add missing export macros in lexical_casts.hpp (`#1382 `_) * Move hardware interface README content to sphinx documentation (`#1342 `_) * [Doc] Add documentation about initial_value regarding mock_hw (`#1352 `_) diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index e3a343c8ae..486e1f97ca 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 4.4.0 + 4.5.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface_testing/CHANGELOG.rst b/hardware_interface_testing/CHANGELOG.rst index 242851f3fd..227c2ac1ad 100644 --- a/hardware_interface_testing/CHANGELOG.rst +++ b/hardware_interface_testing/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package hardware_interface_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/hardware_interface_testing/package.xml b/hardware_interface_testing/package.xml index de7d75b2f5..e33abe073a 100644 --- a/hardware_interface_testing/package.xml +++ b/hardware_interface_testing/package.xml @@ -1,7 +1,7 @@ hardware_interface_testing - 4.4.0 + 4.5.0 ros2_control hardware interface testing Bence Magyar Denis Štogl diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index f2da17ef04..3d69214cb9 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 9deb33af7d..07a7354864 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 4.4.0 + 4.5.0 Interfaces for handling of joint limits for controllers or hardware. Bence Magyar diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index f9c2ea473c..5e266f7745 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/ros2_control/package.xml b/ros2_control/package.xml index 9e7c446b66..80c6332ecc 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 4.4.0 + 4.5.0 Metapackage for ROS2 control related packages Bence Magyar Denis Štogl diff --git a/ros2_control_test_assets/CHANGELOG.rst b/ros2_control_test_assets/CHANGELOG.rst index ff926d4e06..bcca8ae67d 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index c403246015..5a78c5b02e 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 4.4.0 + 4.5.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 53abf7eb70..e59bcae167 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index 33f265a607..48dca4273c 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 4.4.0 + 4.5.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index 02c9f108d3..1da5efa665 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="4.4.0", + version="4.5.0", packages=find_packages(exclude=["test"]), data_files=[ ("share/" + package_name, ["package.xml"]), diff --git a/rqt_controller_manager/CHANGELOG.rst b/rqt_controller_manager/CHANGELOG.rst index 10c1d3e81c..12933ab440 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index c280751db7..2c708dad8f 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 4.4.0 + 4.5.0 Graphical frontend for interacting with the controller manager. Bence Magyar Denis Štogl diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index f93c231cd9..bcde9ff7da 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -6,7 +6,7 @@ setup( name=package_name, - version="4.4.0", + version="4.5.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", ["resource/" + package_name]), diff --git a/transmission_interface/CHANGELOG.rst b/transmission_interface/CHANGELOG.rst index 854bbf2b51..6493d89eb2 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,8 +2,8 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Forthcoming ------------ +4.5.0 (2024-02-12) +------------------ 4.4.0 (2024-01-31) ------------------ diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index 894bbd9b45..a758b9b3f8 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 4.4.0 + 4.5.0 transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this. Bence Magyar Denis Štogl From 3a21841e50560e9fe1d7fc434251ae857f5eb90d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 14 Feb 2024 20:14:44 +0100 Subject: [PATCH 11/20] [CI] Reusable workflows from `ros2_control_ci` (#1383) --- ...ld-testing.yml => humble-binary-build.yml} | 14 ++- .github/workflows/humble-debian-build.yml | 39 +++----- .../workflows/humble-rhel-binary-build.yml | 43 +++------ .../humble-semi-binary-build-main.yml | 23 ----- .../humble-semi-binary-build-testing.yml | 23 ----- ...-main.yml => humble-semi-binary-build.yml} | 14 ++- .github/workflows/humble-source-build.yml | 2 +- ...y-build-main.yml => iron-binary-build.yml} | 12 ++- .github/workflows/iron-debian-build.yml | 39 +++----- .github/workflows/iron-rhel-binary-build.yml | 44 +++------ .../workflows/iron-semi-binary-build-main.yml | 23 ----- .../iron-semi-binary-build-testing.yml | 23 ----- ...testing.yml => iron-semi-binary-build.yml} | 14 ++- .github/workflows/iron-source-build.yml | 2 +- .../reusable-industrial-ci-with-cache.yml | 96 ------------------- .../reusable-ros-tooling-source-build.yml | 56 ----------- ...d-testing.yml => rolling-binary-build.yml} | 16 ++-- .github/workflows/rolling-debian-build.yml | 38 +++----- .../workflows/rolling-rhel-binary-build.yml | 45 +++------ .../rolling-semi-binary-build-main.yml | 25 ----- .../rolling-semi-binary-build-testing.yml | 23 ----- ...main.yml => rolling-semi-binary-build.yml} | 14 ++- .github/workflows/rolling-source-build.yml | 2 +- 23 files changed, 124 insertions(+), 506 deletions(-) rename .github/workflows/{humble-binary-build-testing.yml => humble-binary-build.yml} (51%) delete mode 100644 .github/workflows/humble-semi-binary-build-main.yml delete mode 100644 .github/workflows/humble-semi-binary-build-testing.yml rename .github/workflows/{humble-binary-build-main.yml => humble-semi-binary-build.yml} (51%) rename .github/workflows/{iron-binary-build-main.yml => iron-binary-build.yml} (60%) delete mode 100644 .github/workflows/iron-semi-binary-build-main.yml delete mode 100644 .github/workflows/iron-semi-binary-build-testing.yml rename .github/workflows/{iron-binary-build-testing.yml => iron-semi-binary-build.yml} (53%) delete mode 100644 .github/workflows/reusable-industrial-ci-with-cache.yml delete mode 100644 .github/workflows/reusable-ros-tooling-source-build.yml rename .github/workflows/{rolling-binary-build-testing.yml => rolling-binary-build.yml} (51%) delete mode 100644 .github/workflows/rolling-semi-binary-build-main.yml delete mode 100644 .github/workflows/rolling-semi-binary-build-testing.yml rename .github/workflows/{rolling-binary-build-main.yml => rolling-semi-binary-build.yml} (51%) diff --git a/.github/workflows/humble-binary-build-testing.yml b/.github/workflows/humble-binary-build.yml similarity index 51% rename from .github/workflows/humble-binary-build-testing.yml rename to .github/workflows/humble-binary-build.yml index 99ff6ccd4a..dd7119d878 100644 --- a/.github/workflows/humble-binary-build-testing.yml +++ b/.github/workflows/humble-binary-build.yml @@ -1,4 +1,4 @@ -name: Humble Binary Build - testing +name: Humble Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' @@ -16,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [humble] + ROS_REPO: [main, testing] with: - ros_distro: humble - ros_repo: testing - upstream_workspace: ros2_control-not-released.humble.repos + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control-not-released.${{ matrix.ROS_DISTRO }}.repos ref_for_scheduled_build: humble diff --git a/.github/workflows/humble-debian-build.yml b/.github/workflows/humble-debian-build.yml index 482504c59a..f5af601316 100644 --- a/.github/workflows/humble-debian-build.yml +++ b/.github/workflows/humble-debian-build.yml @@ -1,4 +1,4 @@ -name: Debian Humble Build +name: Debian Humble Source Build on: workflow_dispatch: pull_request: @@ -10,29 +10,14 @@ on: jobs: - humble_debian: - name: Humble debian build - runs-on: ubuntu-latest - env: - ROS_DISTRO: humble - skip-packages-build: rqt_controller_manager - skip-packages-test: rqt_controller_manager controller_manager_msgs - container: ghcr.io/ros-controls/ros:humble-debian - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - - name: Build workspace - shell: bash - run: | - source /opt/ros2_ws/install/setup.bash - vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-build }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros2_ws/install/setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-test }} - colcon test-result --verbose + debian_source_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master + strategy: + matrix: + ROS_DISTRO: [humble] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager + skip_packages_test: controller_manager_msgs diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index 9d3b095e39..c541b00636 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -1,4 +1,4 @@ -name: RHEL Humble Binary Build +name: RHEL Humble Semi-Binary Build on: workflow_dispatch: pull_request: @@ -9,34 +9,13 @@ on: - cron: '03 1 * * *' jobs: - humble_rhel_binary: - name: Humble RHEL binary build - runs-on: ubuntu-latest - env: - ROS_DISTRO: humble - skip-packages: rqt_controller_manager - container: ghcr.io/ros-controls/ros:humble-rhel - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - ref: ${{ github.event_name == 'schedule' && 'humble' || '' }} - - name: Install dependencies - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - rosdep update - rosdep install -iyr --from-path src/ros2_control || true - - name: Build workspace - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - colcon test-result --verbose + rhel_semi_binary_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master + strategy: + matrix: + ROS_DISTRO: [humble] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: humble + skip_packages: rqt_controller_manager diff --git a/.github/workflows/humble-semi-binary-build-main.yml b/.github/workflows/humble-semi-binary-build-main.yml deleted file mode 100644 index 88591b69f7..0000000000 --- a/.github/workflows/humble-semi-binary-build-main.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: Humble Semi-Binary Build - main -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - pull_request: - branches: - - humble - push: - branches: - - humble - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: humble - ros_repo: main - upstream_workspace: ros2_control.humble.repos - ref_for_scheduled_build: humble diff --git a/.github/workflows/humble-semi-binary-build-testing.yml b/.github/workflows/humble-semi-binary-build-testing.yml deleted file mode 100644 index 3d6b2717e3..0000000000 --- a/.github/workflows/humble-semi-binary-build-testing.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: Humble Semi-Binary Build - testing -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - pull_request: - branches: - - humble - push: - branches: - - humble - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: humble - ros_repo: testing - upstream_workspace: ros2_control.humble.repos - ref_for_scheduled_build: humble diff --git a/.github/workflows/humble-binary-build-main.yml b/.github/workflows/humble-semi-binary-build.yml similarity index 51% rename from .github/workflows/humble-binary-build-main.yml rename to .github/workflows/humble-semi-binary-build.yml index 1fafd01c9e..edfcfa1734 100644 --- a/.github/workflows/humble-binary-build-main.yml +++ b/.github/workflows/humble-semi-binary-build.yml @@ -1,4 +1,4 @@ -name: Humble Binary Build - main +name: Humble Semi-Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' @@ -16,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [humble] + ROS_REPO: [main, testing] with: - ros_distro: humble - ros_repo: main - upstream_workspace: ros2_control-not-released.humble.repos + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos ref_for_scheduled_build: humble diff --git a/.github/workflows/humble-source-build.yml b/.github/workflows/humble-source-build.yml index a40d53f8e3..7b4427d6d6 100644 --- a/.github/workflows/humble-source-build.yml +++ b/.github/workflows/humble-source-build.yml @@ -10,7 +10,7 @@ on: jobs: source: - uses: ./.github/workflows/reusable-ros-tooling-source-build.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-source-build.yml@master with: ros_distro: humble ref: humble diff --git a/.github/workflows/iron-binary-build-main.yml b/.github/workflows/iron-binary-build.yml similarity index 60% rename from .github/workflows/iron-binary-build-main.yml rename to .github/workflows/iron-binary-build.yml index 440b573cb9..245b075ae7 100644 --- a/.github/workflows/iron-binary-build-main.yml +++ b/.github/workflows/iron-binary-build.yml @@ -1,4 +1,4 @@ -name: Iron Binary Build - main +name: Iron Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' @@ -16,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [iron] + ROS_REPO: [main, testing] with: - ros_distro: iron - ros_repo: main + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} upstream_workspace: ros2_control-not-released.iron.repos ref_for_scheduled_build: iron diff --git a/.github/workflows/iron-debian-build.yml b/.github/workflows/iron-debian-build.yml index 35db1eb8d9..738fff8acb 100644 --- a/.github/workflows/iron-debian-build.yml +++ b/.github/workflows/iron-debian-build.yml @@ -1,4 +1,4 @@ -name: Debian Iron Build +name: Debian Iron Source Build on: workflow_dispatch: pull_request: @@ -10,29 +10,14 @@ on: jobs: - iron_debian: - name: Iron debian build - runs-on: ubuntu-latest - env: - ROS_DISTRO: iron - skip-packages-build: rqt_controller_manager - skip-packages-test: rqt_controller_manager controller_manager_msgs - container: ghcr.io/ros-controls/ros:iron-debian - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - - name: Build workspace - shell: bash - run: | - source /opt/ros2_ws/install/setup.bash - vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-build }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros2_ws/install/setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages-test }} - colcon test-result --verbose + debian_source_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master + strategy: + matrix: + ROS_DISTRO: [iron] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager + skip_packages_test: controller_manager_msgs diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index 435c3e9316..e1c80435eb 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -1,4 +1,4 @@ -name: RHEL Iron Binary Build +name: RHEL Iron Semi-Binary Build on: workflow_dispatch: pull_request: @@ -9,35 +9,13 @@ on: - cron: '03 1 * * *' jobs: - iron_rhel_binary: - name: Iron RHEL binary build - runs-on: ubuntu-latest - env: - ROS_DISTRO: iron - skip-packages: rqt_controller_manager - container: ghcr.io/ros-controls/ros:iron-rhel - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - ref: ${{ github.event_name == 'schedule' && 'iron' || '' }} - - name: Install dependencies - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - rosdep update - rosdep install -iyr --from-path src/ros2_control || true - - name: Build workspace - # source also underlay workspace with generate_parameter_library on rhel9 - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - colcon test-result --verbose + rhel_semi_binary_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master + strategy: + matrix: + ROS_DISTRO: [iron] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: iron + skip_packages: rqt_controller_manager diff --git a/.github/workflows/iron-semi-binary-build-main.yml b/.github/workflows/iron-semi-binary-build-main.yml deleted file mode 100644 index c5697d6e74..0000000000 --- a/.github/workflows/iron-semi-binary-build-main.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: Iron Semi-Binary Build - main -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - pull_request: - branches: - - iron - push: - branches: - - iron - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: iron - ros_repo: main - upstream_workspace: ros2_control.iron.repos - ref_for_scheduled_build: iron diff --git a/.github/workflows/iron-semi-binary-build-testing.yml b/.github/workflows/iron-semi-binary-build-testing.yml deleted file mode 100644 index 0055e38cba..0000000000 --- a/.github/workflows/iron-semi-binary-build-testing.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: Iron Semi-Binary Build - testing -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - pull_request: - branches: - - iron - push: - branches: - - iron - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: iron - ros_repo: testing - upstream_workspace: ros2_control.iron.repos - ref_for_scheduled_build: iron diff --git a/.github/workflows/iron-binary-build-testing.yml b/.github/workflows/iron-semi-binary-build.yml similarity index 53% rename from .github/workflows/iron-binary-build-testing.yml rename to .github/workflows/iron-semi-binary-build.yml index 78e13f2528..fde8d065e7 100644 --- a/.github/workflows/iron-binary-build-testing.yml +++ b/.github/workflows/iron-semi-binary-build.yml @@ -1,4 +1,4 @@ -name: Iron Binary Build - testing +name: Iron Semi-Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' @@ -16,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [iron] + ROS_REPO: [main, testing] with: - ros_distro: iron - ros_repo: testing - upstream_workspace: ros2_control-not-released.iron.repos + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control.iron.repos ref_for_scheduled_build: iron diff --git a/.github/workflows/iron-source-build.yml b/.github/workflows/iron-source-build.yml index 34372a4178..3609dcfc41 100644 --- a/.github/workflows/iron-source-build.yml +++ b/.github/workflows/iron-source-build.yml @@ -10,7 +10,7 @@ on: jobs: source: - uses: ./.github/workflows/reusable-ros-tooling-source-build.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-source-build.yml@master with: ros_distro: iron ref: iron diff --git a/.github/workflows/reusable-industrial-ci-with-cache.yml b/.github/workflows/reusable-industrial-ci-with-cache.yml deleted file mode 100644 index acefeebfac..0000000000 --- a/.github/workflows/reusable-industrial-ci-with-cache.yml +++ /dev/null @@ -1,96 +0,0 @@ -name: Reusable industrial_ci Workflow with Cache -# Reusable action to simplify dealing with ROS/ROS2 industrial_ci builds with cache -# author: Denis Štogl - -on: - workflow_call: - inputs: - ref_for_scheduled_build: - description: 'Reference on which the repo should be checkout for scheduled build. Usually is this name of a branch or a tag.' - default: '' - required: false - type: string - - upstream_workspace: - description: 'UPSTREAM_WORKSPACE variable for industrial_ci. Usually path to local .repos file.' - required: true - type: string - ros_distro: - description: 'ROS_DISTRO variable for industrial_ci' - required: true - type: string - ros_repo: - description: 'ROS_REPO to run for industrial_ci. Possible values: "main", "testing"' - default: 'main' - required: false - type: string - os_code_name: - description: 'OS_CODE_NAME variable for industrial_ci' - default: '' - required: false - type: string - before_install_upstream_dependencies: - description: 'BEFORE_INSTALL_UPSTREAM_DEPENDENCIES variable for industrial_ci' - default: '' - required: false - type: string - - ccache_dir: - description: 'Local path to store cache (from "github.workspace"). For standard industrial_ci configuration do not have to be changed' - default: '.ccache' - required: false - type: string - basedir: - description: 'Local path to workspace base directory to cache (from "github.workspace"). For standard industrial_ci configuration do not have to be changed' - default: '.work' - required: false - type: string - - -jobs: - reusable_industrial_ci_with_cache: - name: ${{ inputs.ros_distro }} ${{ inputs.ros_repo }} ${{ inputs.os_code_name }} - runs-on: ubuntu-latest - env: - CCACHE_DIR: ${{ github.workspace }}/${{ inputs.ccache_dir }} - BASEDIR: ${{ github.workspace }}/${{ inputs.basedir }} - CACHE_PREFIX: ${{ inputs.ros_distro }}-${{ inputs.upstream_workspace }}-${{ inputs.ros_repo }}-${{ github.job }} - steps: - - name: Checkout ${{ inputs.ref }} when build is not scheduled - if: ${{ github.event_name != 'schedule' }} - uses: actions/checkout@v4 - - name: Checkout ${{ inputs.ref }} on scheduled build - if: ${{ github.event_name == 'schedule' }} - uses: actions/checkout@v4 - with: - ref: ${{ inputs.ref_for_scheduled_build }} - - name: cache target_ws - if: ${{ ! matrix.env.CCOV }} - uses: pat-s/always-upload-cache@v3.0.11 - with: - path: ${{ env.BASEDIR }}/target_ws - key: target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }}-${{ github.run_id }} - restore-keys: | - target_ws-${{ env.CACHE_PREFIX }}-${{ hashFiles('**/CMakeLists.txt', '**/package.xml') }} - - name: cache ccache - uses: pat-s/always-upload-cache@v3.0.11 - with: - path: ${{ env.CCACHE_DIR }} - key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }} - restore-keys: | - ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }} - ccache-${{ env.CACHE_PREFIX }} - - uses: 'ros-industrial/industrial_ci@master' - env: - UPSTREAM_WORKSPACE: ${{ inputs.upstream_workspace }} - ROS_DISTRO: ${{ inputs.ros_distro }} - ROS_REPO: ${{ inputs.ros_repo }} - OS_CODE_NAME: ${{ inputs.os_code_name }} - BEFORE_INSTALL_UPSTREAM_DEPENDENCIES: ${{ inputs.before_install_upstream_dependencies }} - - name: prepare target_ws for cache - if: ${{ always() && ! matrix.env.CCOV }} - run: | - du -sh ${{ env.BASEDIR }}/target_ws - sudo find ${{ env.BASEDIR }}/target_ws -wholename '*/test_results/*' -delete - sudo rm -rf ${{ env.BASEDIR }}/target_ws/src - du -sh ${{ env.BASEDIR }}/target_ws diff --git a/.github/workflows/reusable-ros-tooling-source-build.yml b/.github/workflows/reusable-ros-tooling-source-build.yml deleted file mode 100644 index fa96b7288c..0000000000 --- a/.github/workflows/reusable-ros-tooling-source-build.yml +++ /dev/null @@ -1,56 +0,0 @@ -name: Reusable industrial_ci Workflow with Cache -# Reusable action to simplify dealing with ROS/ROS2 industrial_ci builds with cache -# author: Denis Štogl - -on: - workflow_call: - inputs: - ros_distro: - description: 'ROS2 distribution name' - required: true - type: string - ref: - description: 'Reference on which the repo should be checkout. Usually is this name of a branch or a tag.' - required: true - type: string - ros2_repo_branch: - description: 'Branch in the ros2/ros2 repository from which ".repos" should be used. Possible values: master (Rolling), humble.' - default: 'master' - required: false - type: string - -jobs: - reusable_ros_tooling_source_build: - name: ${{ inputs.ros_distro }} ubuntu-22.04 - runs-on: ubuntu-22.04 - strategy: - fail-fast: false - steps: - - uses: ros-tooling/setup-ros@0.7.1 - with: - required-ros-distributions: ${{ inputs.ros_distro }} - - uses: actions/checkout@v4 - with: - ref: ${{ inputs.ref }} - - uses: ros-tooling/action-ros-ci@0.3.6 - with: - target-ros2-distro: ${{ inputs.ros_distro }} - # build all packages listed in the meta package - ref: ${{ inputs.ref }} # otherwise the default branch is used for scheduled workflows - package-name: - controller_interface - controller_manager - controller_manager_msgs - hardware_interface - ros2controlcli - ros2_control - ros2_control_test_assets - transmission_interface - vcs-repo-file-url: | - https://raw.githubusercontent.com/ros2/ros2/${{ inputs.ros2_repo_branch }}/ros2.repos - https://raw.githubusercontent.com/${{ github.repository }}/${{ github.sha }}/ros2_control.${{ inputs.ros_distro }}.repos?token=${{ secrets.GITHUB_TOKEN }} - colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: actions/upload-artifact@v4.3.0 - with: - name: colcon-logs-ubuntu-22.04 - path: ros_ws/log diff --git a/.github/workflows/rolling-binary-build-testing.yml b/.github/workflows/rolling-binary-build.yml similarity index 51% rename from .github/workflows/rolling-binary-build-testing.yml rename to .github/workflows/rolling-binary-build.yml index 811c96fce4..c17799922a 100644 --- a/.github/workflows/rolling-binary-build-testing.yml +++ b/.github/workflows/rolling-binary-build.yml @@ -1,11 +1,9 @@ -name: Rolling Binary Build - testing +name: Rolling Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' on: workflow_dispatch: - branches: - - master pull_request: branches: - master @@ -18,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [rolling] + ROS_REPO: [main, testing] with: - ros_distro: rolling - ros_repo: testing - upstream_workspace: ros2_control-not-released.rolling.repos + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control-not-released.${{ matrix.ROS_DISTRO }}.repos ref_for_scheduled_build: master diff --git a/.github/workflows/rolling-debian-build.yml b/.github/workflows/rolling-debian-build.yml index efe1422404..c175f41e5b 100644 --- a/.github/workflows/rolling-debian-build.yml +++ b/.github/workflows/rolling-debian-build.yml @@ -1,4 +1,4 @@ -name: Debian Rolling Build +name: Debian Rolling Source Build on: workflow_dispatch: pull_request: @@ -10,29 +10,13 @@ on: jobs: - rolling_debian: - name: Rolling debian build - runs-on: ubuntu-latest - env: - ROS_DISTRO: rolling - skip-packages: rqt_controller_manager - container: ghcr.io/ros-controls/ros:rolling-debian - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - # default behavior is correct on master branch - # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - - name: Build workspace - shell: bash - run: | - source /opt/ros2_ws/install/setup.bash - vcs import src < src/ros2_control/ros2_control.${{ env.ROS_DISTRO }}.repos - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros2_ws/install/setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - colcon test-result --verbose + debian_source_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master + strategy: + matrix: + ROS_DISTRO: [rolling] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index 8f2638405b..d3544d53a2 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -1,4 +1,4 @@ -name: RHEL Rolling Binary Build +name: RHEL Rolling Semi-Binary Build on: workflow_dispatch: pull_request: @@ -9,36 +9,13 @@ on: - cron: '03 1 * * *' jobs: - rolling_rhel_binary: - name: Rolling RHEL binary build - runs-on: ubuntu-latest - env: - ROS_DISTRO: rolling - skip-packages: rqt_controller_manager - container: ghcr.io/ros-controls/ros:rolling-rhel - steps: - - uses: actions/checkout@v4 - with: - path: src/ros2_control - # default behavior is correct on master branch - # ref: ${{ github.event_name == 'schedule' && 'master' || '' }} - - name: Install dependencies - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - rosdep update - rosdep install -iyr --from-path src/ros2_control || true - - name: Build workspace - # source also underlay workspace with generate_parameter_library on rhel9 - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon build --packages-up-to $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - - name: Test workspace - shell: bash - continue-on-error: true - run: | - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - source /opt/ros2_ws/install/local_setup.bash - colcon test --packages-select $(colcon list --paths src/ros2_control/* --names-only) --packages-skip ${{ env.skip-packages }} - colcon test-result --verbose + rhel_semi_binary_build: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master + strategy: + matrix: + ROS_DISTRO: [rolling] + with: + ros_distro: ${{ matrix.ROS_DISTRO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos + ref_for_scheduled_build: master + skip_packages: rqt_controller_manager diff --git a/.github/workflows/rolling-semi-binary-build-main.yml b/.github/workflows/rolling-semi-binary-build-main.yml deleted file mode 100644 index 1033dd1e6c..0000000000 --- a/.github/workflows/rolling-semi-binary-build-main.yml +++ /dev/null @@ -1,25 +0,0 @@ -name: Rolling Semi-Binary Build - main -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - branches: - - master - pull_request: - branches: - - master - push: - branches: - - master - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: rolling - ros_repo: main - upstream_workspace: ros2_control.rolling.repos - ref_for_scheduled_build: master diff --git a/.github/workflows/rolling-semi-binary-build-testing.yml b/.github/workflows/rolling-semi-binary-build-testing.yml deleted file mode 100644 index 17d290c45b..0000000000 --- a/.github/workflows/rolling-semi-binary-build-testing.yml +++ /dev/null @@ -1,23 +0,0 @@ -name: Rolling Semi-Binary Build - testing -# description: 'Build & test that compiles the main dependencies from source.' - -on: - workflow_dispatch: - pull_request: - branches: - - master - push: - branches: - - master - schedule: - # Run every morning to detect flakiness and broken dependencies - - cron: '33 1 * * *' - -jobs: - semi_binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml - with: - ros_distro: rolling - ros_repo: testing - upstream_workspace: ros2_control.rolling.repos - ref_for_scheduled_build: master diff --git a/.github/workflows/rolling-binary-build-main.yml b/.github/workflows/rolling-semi-binary-build.yml similarity index 51% rename from .github/workflows/rolling-binary-build-main.yml rename to .github/workflows/rolling-semi-binary-build.yml index 1777810661..743b472c32 100644 --- a/.github/workflows/rolling-binary-build-main.yml +++ b/.github/workflows/rolling-semi-binary-build.yml @@ -1,4 +1,4 @@ -name: Rolling Binary Build - main +name: Rolling Semi-Binary Build # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' @@ -16,9 +16,13 @@ on: jobs: binary: - uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master + strategy: + matrix: + ROS_DISTRO: [rolling] + ROS_REPO: [main, testing] with: - ros_distro: rolling - ros_repo: main - upstream_workspace: ros2_control-not-released.rolling.repos + ros_distro: ${{ matrix.ROS_DISTRO }} + ros_repo: ${{ matrix.ROS_REPO }} + upstream_workspace: ros2_control.${{ matrix.ROS_DISTRO }}.repos ref_for_scheduled_build: master diff --git a/.github/workflows/rolling-source-build.yml b/.github/workflows/rolling-source-build.yml index 475e509e0f..f34a8e6bb5 100644 --- a/.github/workflows/rolling-source-build.yml +++ b/.github/workflows/rolling-source-build.yml @@ -10,7 +10,7 @@ on: jobs: source: - uses: ./.github/workflows/reusable-ros-tooling-source-build.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-source-build.yml@master with: ros_distro: rolling ref: master From 976433f7739afe09f6061c972e2923d4ba7e5dfe Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 14 Feb 2024 19:15:34 +0000 Subject: [PATCH 12/20] Bump actions/upload-artifact from 4.3.0 to 4.3.1 (#1386) --- .github/workflows/ci-coverage-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci-coverage-build.yml b/.github/workflows/ci-coverage-build.yml index efca7ca45e..2e353211ba 100644 --- a/.github/workflows/ci-coverage-build.yml +++ b/.github/workflows/ci-coverage-build.yml @@ -47,7 +47,7 @@ jobs: file: ros_ws/lcov/total_coverage.info flags: unittests name: codecov-umbrella - - uses: actions/upload-artifact@v4.3.0 + - uses: actions/upload-artifact@v4.3.1 with: name: colcon-logs-ubuntu-22.04-coverage-rolling path: ros_ws/log From ac76ec917f0ffafee54bcb5d8aeb09f3f807541d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Thu, 15 Feb 2024 17:50:10 +0100 Subject: [PATCH 13/20] fail-fast: false (#1397) --- .github/workflows/humble-binary-build.yml | 1 + .github/workflows/humble-debian-build.yml | 1 + .github/workflows/humble-rhel-binary-build.yml | 1 + .github/workflows/humble-semi-binary-build.yml | 1 + .github/workflows/iron-binary-build.yml | 1 + .github/workflows/iron-debian-build.yml | 1 + .github/workflows/iron-rhel-binary-build.yml | 1 + .github/workflows/iron-semi-binary-build.yml | 1 + .github/workflows/rolling-binary-build.yml | 1 + .github/workflows/rolling-debian-build.yml | 1 + .github/workflows/rolling-rhel-binary-build.yml | 1 + .github/workflows/rolling-semi-binary-build.yml | 1 + 12 files changed, 12 insertions(+) diff --git a/.github/workflows/humble-binary-build.yml b/.github/workflows/humble-binary-build.yml index dd7119d878..2cf14105f5 100644 --- a/.github/workflows/humble-binary-build.yml +++ b/.github/workflows/humble-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [humble] ROS_REPO: [main, testing] diff --git a/.github/workflows/humble-debian-build.yml b/.github/workflows/humble-debian-build.yml index f5af601316..3b8a1c6287 100644 --- a/.github/workflows/humble-debian-build.yml +++ b/.github/workflows/humble-debian-build.yml @@ -13,6 +13,7 @@ jobs: debian_source_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [humble] with: diff --git a/.github/workflows/humble-rhel-binary-build.yml b/.github/workflows/humble-rhel-binary-build.yml index c541b00636..4c00d2f2ad 100644 --- a/.github/workflows/humble-rhel-binary-build.yml +++ b/.github/workflows/humble-rhel-binary-build.yml @@ -12,6 +12,7 @@ jobs: rhel_semi_binary_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [humble] with: diff --git a/.github/workflows/humble-semi-binary-build.yml b/.github/workflows/humble-semi-binary-build.yml index edfcfa1734..19637c4897 100644 --- a/.github/workflows/humble-semi-binary-build.yml +++ b/.github/workflows/humble-semi-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [humble] ROS_REPO: [main, testing] diff --git a/.github/workflows/iron-binary-build.yml b/.github/workflows/iron-binary-build.yml index 245b075ae7..911ccafae5 100644 --- a/.github/workflows/iron-binary-build.yml +++ b/.github/workflows/iron-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [iron] ROS_REPO: [main, testing] diff --git a/.github/workflows/iron-debian-build.yml b/.github/workflows/iron-debian-build.yml index 738fff8acb..ff503d64a9 100644 --- a/.github/workflows/iron-debian-build.yml +++ b/.github/workflows/iron-debian-build.yml @@ -13,6 +13,7 @@ jobs: debian_source_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [iron] with: diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml index e1c80435eb..981893524d 100644 --- a/.github/workflows/iron-rhel-binary-build.yml +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -12,6 +12,7 @@ jobs: rhel_semi_binary_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [iron] with: diff --git a/.github/workflows/iron-semi-binary-build.yml b/.github/workflows/iron-semi-binary-build.yml index fde8d065e7..59f8f347dd 100644 --- a/.github/workflows/iron-semi-binary-build.yml +++ b/.github/workflows/iron-semi-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [iron] ROS_REPO: [main, testing] diff --git a/.github/workflows/rolling-binary-build.yml b/.github/workflows/rolling-binary-build.yml index c17799922a..b083cc46fc 100644 --- a/.github/workflows/rolling-binary-build.yml +++ b/.github/workflows/rolling-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [rolling] ROS_REPO: [main, testing] diff --git a/.github/workflows/rolling-debian-build.yml b/.github/workflows/rolling-debian-build.yml index c175f41e5b..e792963cc6 100644 --- a/.github/workflows/rolling-debian-build.yml +++ b/.github/workflows/rolling-debian-build.yml @@ -13,6 +13,7 @@ jobs: debian_source_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-debian-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [rolling] with: diff --git a/.github/workflows/rolling-rhel-binary-build.yml b/.github/workflows/rolling-rhel-binary-build.yml index d3544d53a2..38f375d6b6 100644 --- a/.github/workflows/rolling-rhel-binary-build.yml +++ b/.github/workflows/rolling-rhel-binary-build.yml @@ -12,6 +12,7 @@ jobs: rhel_semi_binary_build: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-rhel-binary-build.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [rolling] with: diff --git a/.github/workflows/rolling-semi-binary-build.yml b/.github/workflows/rolling-semi-binary-build.yml index 743b472c32..f5c7885139 100644 --- a/.github/workflows/rolling-semi-binary-build.yml +++ b/.github/workflows/rolling-semi-binary-build.yml @@ -18,6 +18,7 @@ jobs: binary: uses: ros-controls/ros2_control_ci/.github/workflows/reusable-industrial-ci-with-cache.yml@master strategy: + fail-fast: false matrix: ROS_DISTRO: [rolling] ROS_REPO: [main, testing] From 5f9be40267e8feaf8bbf1634169a09e54e54ddb1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Thu, 15 Feb 2024 17:50:46 +0100 Subject: [PATCH 14/20] Move reviewer-lottery list to ros2_control_ci (#1395) --- .github/reviewer-lottery.yml | 32 -------------------------- .github/workflows/reviewer_lottery.yml | 3 ++- 2 files changed, 2 insertions(+), 33 deletions(-) delete mode 100644 .github/reviewer-lottery.yml diff --git a/.github/reviewer-lottery.yml b/.github/reviewer-lottery.yml deleted file mode 100644 index 2da79efd9a..0000000000 --- a/.github/reviewer-lottery.yml +++ /dev/null @@ -1,32 +0,0 @@ -groups: - # Default reviewers for all pull requests. - # Usually, at least on of the maintainers should approve PR before merging. - # The best is if two maintainers do that. - - name: maintainers # name of the group - reviewers: 2 # how many reviewers do you want to assign? - internal_reviewers: 1 # how many reviewers do you want to assign when the PR author belongs to this group? - usernames: # github usernames of the reviewers - - bmagyar - - destogl - - # Reviewers group to get broader feedback. - - name: reviewers - reviewers: 5 - usernames: - - aprotyas - - arne48 - - bijoua29 - - christophfroehlich - - DasRoteSkelett - - erickisos - - fmauch - - jaron-l - - livanov93 - - mcbed - - moriarty - - olivier-stasse - - peterdavidfagan - - progtologist - - saikishor - - VanshGehlot - - VX792 diff --git a/.github/workflows/reviewer_lottery.yml b/.github/workflows/reviewer_lottery.yml index ed28964e01..79695914a2 100644 --- a/.github/workflows/reviewer_lottery.yml +++ b/.github/workflows/reviewer_lottery.yml @@ -4,7 +4,7 @@ on: types: [opened, ready_for_review, reopened] jobs: - test: + assign_reviewers: runs-on: ubuntu-latest if: github.actor != 'dependabot[bot]' && github.actor != 'mergify[bot]' steps: @@ -12,3 +12,4 @@ jobs: - uses: uesteibar/reviewer-lottery@v3 with: repo-token: ${{ secrets.GITHUB_TOKEN }} + config: ros-controls/ros2_control_ci/.github/reviewer-lottery.yml From b050c952713d57c84ec34338db2314bef089cb00 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 16 Feb 2024 13:34:36 +0000 Subject: [PATCH 15/20] Bump pre-commit/action from 3.0.0 to 3.0.1 (#1385) --- .github/workflows/ci-format.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci-format.yml b/.github/workflows/ci-format.yml index c7199b88c5..569bb95e24 100644 --- a/.github/workflows/ci-format.yml +++ b/.github/workflows/ci-format.yml @@ -18,6 +18,6 @@ jobs: python-version: '3.10' - name: Install system hooks run: sudo apt install -qq cppcheck - - uses: pre-commit/action@v3.0.0 + - uses: pre-commit/action@v3.0.1 with: extra_args: --all-files --hook-stage manual From 01ed7721a02986bf7ffab44d1a6b158eadbc065e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sun, 18 Feb 2024 18:48:58 +0100 Subject: [PATCH 16/20] :wrench: Update badges in README (#1403) --- .github/workflows/README.md | 6 +++--- README.md | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/README.md b/.github/workflows/README.md index 5e8c8ef0fd..ed64bcd94c 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -1,6 +1,6 @@ ROS2 Distro | Branch | Build status | Documentation | Released packages :---------: | :----: | :----------: | :-----------: | :---------------: -**Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-main.yml?branch=master)
[![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-testing.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-main.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-testing.yml?branch=master)
[![Rolling Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml?branch=master) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) -**Iron** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-main.yml?branch=master)
[![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-testing.yml?branch=master)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-main.yml?branch=master)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-testing.yml?branch=master)
[![Iron Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml?branch=master) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) -**Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-main.yml?branch=master)
[![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-testing.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-main.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-testing.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-testing.yml?branch=master)
[![Humble Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml?branch=master) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) +**Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml?branch=master)
[![Rolling Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-source-build.yml?branch=master)
[![Debian Rolling Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-debian-build.yml)
[![RHEL Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-rhel-binary-build.yml) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) +**Iron** | [`iron`](https://github.com/ros-controls/ros2_control/tree/master) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml?branch=master)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml?branch=master)
[![Iron Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-source-build.yml?branch=master)
[![Debian Iron Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-debian-build.yml)
[![RHEL Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-rhel-binary-build.yml) | [Documentation](https://control.ros.org/iron/index.html)
[API Reference](https://control.ros.org/iron/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) +**Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml?branch=master)
[![Humble Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-source-build.yml?branch=master)
[![Debian Humble Source Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-debian-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-debian-build.yml)
[![RHEL Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-rhel-binary-build.yml/badge.svg)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-rhel-binary-build.yml) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) diff --git a/README.md b/README.md index 0c26afd184..e88ca5b7bd 100644 --- a/README.md +++ b/README.md @@ -11,9 +11,9 @@ For more, please check the [documentation](https://control.ros.org/). ROS2 Distro | Branch | Build status | Documentation | Released packages :---------: | :----: | :----------: | :-----------: | :---------------: -**Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build-main.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build-main.yml?branch=master) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) -**Iron** | [`iron`](https://github.com/ros-controls/ros2_control/tree/iron) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-main.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build-main.yml?branch=iron)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-main.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build-main.yml?branch=iron) | [Documentation](https://control.ros.org/iron/index.html)
[API Reference](https://control.ros.org/iron/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) -**Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build-main.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-main.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build-main.yml?branch=master) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) +**Rolling** | [`master`](https://github.com/ros-controls/ros2_control/tree/master) | [![Rolling Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-binary-build.yml?branch=master)
[![Rolling Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/rolling-semi-binary-build.yml?branch=master) | [Documentation](https://control.ros.org/master/index.html)
[API Reference](https://control.ros.org/master/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#rolling) +**Iron** | [`iron`](https://github.com/ros-controls/ros2_control/tree/iron) | [![Iron Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-binary-build.yml?branch=iron)
[![Iron Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml/badge.svg?branch=iron)](https://github.com/ros-controls/ros2_control/actions/workflows/iron-semi-binary-build.yml?branch=iron) | [Documentation](https://control.ros.org/iron/index.html)
[API Reference](https://control.ros.org/iron/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#iron) +**Humble** | [`humble`](https://github.com/ros-controls/ros2_control/tree/humble) | [![Humble Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-binary-build.yml?branch=master)
[![Humble Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml/badge.svg?branch=master)](https://github.com/ros-controls/ros2_control/actions/workflows/humble-semi-binary-build.yml?branch=master) | [Documentation](https://control.ros.org/humble/index.html)
[API Reference](https://control.ros.org/humble/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#humble) [Detailed build status](.github/workflows/README.md) From c4affe4bbfbb12b947acfc7b268f529724e0aae8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 19 Feb 2024 19:49:00 +0100 Subject: [PATCH 17/20] Use reusable-reviewer-lottery from ros2_control_ci (#1402) --- .github/workflows/reviewer_lottery.yml | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/.github/workflows/reviewer_lottery.yml b/.github/workflows/reviewer_lottery.yml index 79695914a2..0584f4a7f3 100644 --- a/.github/workflows/reviewer_lottery.yml +++ b/.github/workflows/reviewer_lottery.yml @@ -1,15 +1,10 @@ name: Reviewer lottery +# pull_request_target takes the same events as pull_request, +# but it runs on the base branch instead of the head branch. on: pull_request_target: types: [opened, ready_for_review, reopened] jobs: assign_reviewers: - runs-on: ubuntu-latest - if: github.actor != 'dependabot[bot]' && github.actor != 'mergify[bot]' - steps: - - uses: actions/checkout@v4 - - uses: uesteibar/reviewer-lottery@v3 - with: - repo-token: ${{ secrets.GITHUB_TOKEN }} - config: ros-controls/ros2_control_ci/.github/reviewer-lottery.yml + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-reviewer-lottery.yml@master From 1cc73c25e39567bc46a472d71ec9643e4fc40dab Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Thu, 22 Feb 2024 15:13:40 +0100 Subject: [PATCH 18/20] Fix multiple chainable controller activation bug (#1401) --- controller_manager/src/controller_manager.cpp | 13 +- .../test/test_controller_manager_srvs.cpp | 197 ++++++++++++++++++ 2 files changed, 207 insertions(+), 3 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 1911bd6ff8..ee2ee87218 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -840,6 +840,12 @@ void ControllerManager::clear_requests() { deactivate_request_.clear(); activate_request_.clear(); + // Set these interfaces as unavailable when clearing requests to avoid leaving them in available + // state without the controller being in active state + for (const auto & controller_name : to_chained_mode_request_) + { + resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); + } to_chained_mode_request_.clear(); from_chained_mode_request_.clear(); activate_command_interface_request_.clear(); @@ -1429,9 +1435,6 @@ void ControllerManager::switch_chained_mode( auto controller = found_it->c; if (!is_controller_active(*controller)) { - // if it is a chainable controller, make the reference interfaces available on preactivation - // (This is needed when you activate a couple of chainable controller altogether) - resource_manager_->make_controller_reference_interfaces_available(controller_name); if (!controller->set_chained_mode(to_chained_mode)) { RCLCPP_ERROR( @@ -2368,6 +2371,10 @@ controller_interface::return_type ControllerManager::check_following_controllers if (found_it == to_chained_mode_request_.end()) { to_chained_mode_request_.push_back(following_ctrl_it->info.name); + // if it is a chainable controller, make the reference interfaces available on preactivation + // (This is needed when you activate a couple of chainable controller altogether) + resource_manager_->make_controller_reference_interfaces_available( + following_ctrl_it->info.name); RCLCPP_DEBUG( get_logger(), "Adding controller '%s' in 'to chained mode' request.", following_ctrl_it->info.name.c_str()); diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index cdec4806c1..36d8aa7c4e 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -1729,3 +1729,200 @@ TEST_F(TestControllerManagerSrvs, list_hardware_interfaces_srv) } } } + +TEST_F(TestControllerManagerSrvs, activate_chained_controllers_one_by_one) +{ + /// The simulated controller chaining is: + /// test_controller_name -> chain_ctrl_2 -> chain_ctrl_1 + /// + /// NOTE: A -> B signifies that the controller A is utilizing the reference interfaces exported + /// from the controller B (or) the controller B is utilizing the expected interfaces exported from + /// the controller A + + // create server client and request + rclcpp::executors::SingleThreadedExecutor srv_executor; + rclcpp::Node::SharedPtr srv_node = std::make_shared("srv_client"); + srv_executor.add_node(srv_node); + rclcpp::Client::SharedPtr client = + srv_node->create_client("test_controller_manager/list_controllers"); + auto request = std::make_shared(); + + // create set of chained controllers + static constexpr char TEST_CHAINED_CONTROLLER_1[] = "test_chainable_controller_name_1"; + static constexpr char TEST_CHAINED_CONTROLLER_2[] = "test_chainable_controller_name_2"; + auto test_chained_controller_1 = std::make_shared(); + controller_interface::InterfaceConfiguration chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint1/position"}}; + controller_interface::InterfaceConfiguration chained_state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_chained_controller_1->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_1->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_1->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + auto test_chained_controller_2 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_1) + "/joint1/position"}}; + test_chained_controller_2->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_2->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_2->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + // create non-chained controller + auto test_controller = std::make_shared(); + controller_interface::InterfaceConfiguration cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/velocity", "joint2/velocity"}}; + controller_interface::InterfaceConfiguration state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_controller->set_command_interface_configuration(cmd_cfg); + test_controller->set_state_interface_configuration(state_cfg); + // add controllers + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + // get controller list before configure + auto result = call_service_and_wait(*client, request, srv_executor); + // check chainable controller + ASSERT_EQ(3u, result->controller.size()); + ASSERT_EQ(result->controller[0].name, TEST_CHAINED_CONTROLLER_1); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_2); + // check test controller + ASSERT_EQ(result->controller[1].name, "test_controller_name"); + + // configure controllers + for (const auto & controller : + {TEST_CHAINED_CONTROLLER_1, test_controller::TEST_CONTROLLER_NAME, + TEST_CHAINED_CONTROLLER_2}) + { + cm_->configure_controller(controller); + } + + // get controller list after configure + result = call_service_and_wait(*client, request, srv_executor); + ASSERT_EQ(3u, result->controller.size()); + + // reordered controllers + ASSERT_EQ(result->controller[0].name, "test_controller_name"); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_2); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_1); + + // activate controllers one by one + auto res1 = cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_1}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(res1, controller_interface::return_type::OK); + auto res2 = cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_2}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(res2, controller_interface::return_type::OK); + auto res3 = cm_->switch_controller( + {test_controller::TEST_CONTROLLER_NAME}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + ASSERT_EQ(res3, controller_interface::return_type::OK); + + RCLCPP_ERROR(srv_node->get_logger(), "Check successful!"); +} + +TEST_F(TestControllerManagerSrvs, activate_chained_controllers_all_at_once) +{ + /// The simulated controller chaining is: + /// test_controller_name -> chain_ctrl_2 -> chain_ctrl_1 + /// + /// NOTE: A -> B signifies that the controller A is utilizing the reference interfaces exported + /// from the controller B (or) the controller B is utilizing the expected interfaces exported from + /// the controller A + + // create server client and request + rclcpp::executors::SingleThreadedExecutor srv_executor; + rclcpp::Node::SharedPtr srv_node = std::make_shared("srv_client"); + srv_executor.add_node(srv_node); + rclcpp::Client::SharedPtr client = + srv_node->create_client("test_controller_manager/list_controllers"); + auto request = std::make_shared(); + + // create set of chained controllers + static constexpr char TEST_CHAINED_CONTROLLER_1[] = "test_chainable_controller_name_1"; + static constexpr char TEST_CHAINED_CONTROLLER_2[] = "test_chainable_controller_name_2"; + auto test_chained_controller_1 = std::make_shared(); + controller_interface::InterfaceConfiguration chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint1/position"}}; + controller_interface::InterfaceConfiguration chained_state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_chained_controller_1->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_1->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_1->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + auto test_chained_controller_2 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_1) + "/joint1/position"}}; + test_chained_controller_2->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_2->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_2->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + // create non-chained controller + auto test_controller = std::make_shared(); + controller_interface::InterfaceConfiguration cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/velocity", "joint2/velocity"}}; + controller_interface::InterfaceConfiguration state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_controller->set_command_interface_configuration(cmd_cfg); + test_controller->set_state_interface_configuration(state_cfg); + // add controllers + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + // get controller list before configure + auto result = call_service_and_wait(*client, request, srv_executor); + // check chainable controller + ASSERT_EQ(3u, result->controller.size()); + ASSERT_EQ(result->controller[0].name, TEST_CHAINED_CONTROLLER_1); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_2); + // check test controller + ASSERT_EQ(result->controller[1].name, "test_controller_name"); + + // configure controllers + for (const auto & controller : + {TEST_CHAINED_CONTROLLER_1, test_controller::TEST_CONTROLLER_NAME, + TEST_CHAINED_CONTROLLER_2}) + { + cm_->configure_controller(controller); + } + + // get controller list after configure + result = call_service_and_wait(*client, request, srv_executor); + ASSERT_EQ(3u, result->controller.size()); + + // reordered controllers + ASSERT_EQ(result->controller[0].name, "test_controller_name"); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_2); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_1); + + // activate controllers all at once + auto res = cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_1, TEST_CHAINED_CONTROLLER_2, test_controller::TEST_CONTROLLER_NAME}, + {}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true, + rclcpp::Duration(0, 0)); + ASSERT_EQ(res, controller_interface::return_type::OK); + + RCLCPP_ERROR(srv_node->get_logger(), "Check successful!"); +} From 1538c91ccf5899d4f2d6759e64a8ec0e29b681a5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sun, 25 Feb 2024 09:59:48 +0100 Subject: [PATCH 19/20] [CI] Code coverage + pre-commit (#1413) --- .github/workflows/ci-coverage-build.yml | 53 ------------------- .github/workflows/ci-format.yml | 23 -------- .github/workflows/ci-ros-lint.yml | 50 ----------------- .github/workflows/humble-coverage-build.yml | 17 ++++++ .github/workflows/humble-pre-commit.yml | 14 +++++ .github/workflows/iron-coverage-build.yml | 17 ++++++ .github/workflows/iron-pre-commit.yml | 14 +++++ .github/workflows/rolling-coverage-build.yml | 17 ++++++ .github/workflows/rolling-pre-commit.yml | 14 +++++ .github/workflows/update-pre-commit.yml | 12 +++++ .pre-commit-config.yaml | 34 +++++++----- CONTRIBUTING.md | 5 +- controller_manager/src/controller_manager.cpp | 2 +- .../test/controller_manager_test_common.hpp | 2 +- hardware_interface/test/test_handle.cpp | 8 +-- rqt_controller_manager/setup.py | 14 +++++ 16 files changed, 146 insertions(+), 150 deletions(-) delete mode 100644 .github/workflows/ci-coverage-build.yml delete mode 100644 .github/workflows/ci-format.yml delete mode 100644 .github/workflows/ci-ros-lint.yml create mode 100644 .github/workflows/humble-coverage-build.yml create mode 100644 .github/workflows/humble-pre-commit.yml create mode 100644 .github/workflows/iron-coverage-build.yml create mode 100644 .github/workflows/iron-pre-commit.yml create mode 100644 .github/workflows/rolling-coverage-build.yml create mode 100644 .github/workflows/rolling-pre-commit.yml create mode 100644 .github/workflows/update-pre-commit.yml diff --git a/.github/workflows/ci-coverage-build.yml b/.github/workflows/ci-coverage-build.yml deleted file mode 100644 index 2e353211ba..0000000000 --- a/.github/workflows/ci-coverage-build.yml +++ /dev/null @@ -1,53 +0,0 @@ -name: Coverage Build -on: - workflow_dispatch: - push: - branches: - - master - pull_request: - branches: - - master - -jobs: - coverage: - name: coverage build - runs-on: ubuntu-22.04 - strategy: - fail-fast: false - env: - ROS_DISTRO: rolling - steps: - - uses: ros-tooling/setup-ros@0.7.1 - with: - required-ros-distributions: ${{ env.ROS_DISTRO }} - - uses: actions/checkout@v4 - - uses: ros-tooling/action-ros-ci@0.3.6 - with: - target-ros2-distro: ${{ env.ROS_DISTRO }} - import-token: ${{ secrets.GITHUB_TOKEN }} - # build all packages listed in the meta package - package-name: - controller_interface - controller_manager - hardware_interface - hardware_interface_testing - transmission_interface - - vcs-repo-file-url: | - https://raw.githubusercontent.com/${{ github.repository }}/${{ github.sha }}/ros2_control-not-released.${{ env.ROS_DISTRO }}.repos?token=${{ secrets.GITHUB_TOKEN }} - colcon-defaults: | - { - "build": { - "mixin": ["coverage-gcc"] - } - } - colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml - - uses: codecov/codecov-action@v4.0.1 - with: - file: ros_ws/lcov/total_coverage.info - flags: unittests - name: codecov-umbrella - - uses: actions/upload-artifact@v4.3.1 - with: - name: colcon-logs-ubuntu-22.04-coverage-rolling - path: ros_ws/log diff --git a/.github/workflows/ci-format.yml b/.github/workflows/ci-format.yml deleted file mode 100644 index 569bb95e24..0000000000 --- a/.github/workflows/ci-format.yml +++ /dev/null @@ -1,23 +0,0 @@ -# This is a format job. Pre-commit has a first-party GitHub action, so we use -# that: https://github.com/pre-commit/action - -name: Format - -on: - workflow_dispatch: - pull_request: - -jobs: - pre-commit: - name: Format - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - - uses: actions/setup-python@v5.0.0 - with: - python-version: '3.10' - - name: Install system hooks - run: sudo apt install -qq cppcheck - - uses: pre-commit/action@v3.0.1 - with: - extra_args: --all-files --hook-stage manual diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml deleted file mode 100644 index 785afa5ede..0000000000 --- a/.github/workflows/ci-ros-lint.yml +++ /dev/null @@ -1,50 +0,0 @@ -name: ROS Lint -on: - pull_request: - -env: - package-name: - controller_interface - controller_manager - controller_manager_msgs - hardware_interface - hardware_interface_testing - ros2controlcli - ros2_control - ros2_control_test_assets - transmission_interface - -jobs: - ament_lint: - name: ament_${{ matrix.linter }} - runs-on: ubuntu-latest - strategy: - fail-fast: false - matrix: - linter: [cppcheck, copyright, lint_cmake] - env: - AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS: true - steps: - - uses: actions/checkout@v4 - - uses: ros-tooling/setup-ros@0.7.1 - - uses: ros-tooling/action-ros-lint@v0.1 - with: - distribution: rolling - linter: ${{ matrix.linter }} - package-name: ${{ env.package-name }} - ament_lint_100: - name: ament_${{ matrix.linter }} - runs-on: ubuntu-latest - strategy: - fail-fast: false - matrix: - linter: [cpplint] - steps: - - uses: actions/checkout@v4 - - uses: ros-tooling/setup-ros@0.7.1 - - uses: ros-tooling/action-ros-lint@v0.1 - with: - distribution: rolling - linter: cpplint - arguments: "--linelength=100 --filter=-whitespace/newline" - package-name: ${{ env.package-name }} diff --git a/.github/workflows/humble-coverage-build.yml b/.github/workflows/humble-coverage-build.yml new file mode 100644 index 0000000000..0910572227 --- /dev/null +++ b/.github/workflows/humble-coverage-build.yml @@ -0,0 +1,17 @@ +name: Coverage Build - Humble +on: + workflow_dispatch: + push: + branches: + - humble + pull_request: + branches: + - humble + +jobs: + coverage_humble: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master + secrets: inherit + with: + ros_distro: humble + os_name: ubuntu-22.04 diff --git a/.github/workflows/humble-pre-commit.yml b/.github/workflows/humble-pre-commit.yml new file mode 100644 index 0000000000..be8c84b05b --- /dev/null +++ b/.github/workflows/humble-pre-commit.yml @@ -0,0 +1,14 @@ +name: Pre-Commit - Humble + +on: + workflow_dispatch: + pull_request: + branches: + - humble + +jobs: + pre-commit: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master + with: + ros_distro: humble + os_name: ubuntu-22.04 diff --git a/.github/workflows/iron-coverage-build.yml b/.github/workflows/iron-coverage-build.yml new file mode 100644 index 0000000000..d82c52bf51 --- /dev/null +++ b/.github/workflows/iron-coverage-build.yml @@ -0,0 +1,17 @@ +name: Coverage Build - Iron +on: + workflow_dispatch: + push: + branches: + - iron + pull_request: + branches: + - iron + +jobs: + coverage_iron: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master + secrets: inherit + with: + ros_distro: iron + os_name: ubuntu-22.04 diff --git a/.github/workflows/iron-pre-commit.yml b/.github/workflows/iron-pre-commit.yml new file mode 100644 index 0000000000..60ad26d073 --- /dev/null +++ b/.github/workflows/iron-pre-commit.yml @@ -0,0 +1,14 @@ +name: Pre-Commit - Iron + +on: + workflow_dispatch: + pull_request: + branches: + - iron + +jobs: + pre-commit: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master + with: + ros_distro: iron + os_name: ubuntu-22.04 diff --git a/.github/workflows/rolling-coverage-build.yml b/.github/workflows/rolling-coverage-build.yml new file mode 100644 index 0000000000..4d4750c54c --- /dev/null +++ b/.github/workflows/rolling-coverage-build.yml @@ -0,0 +1,17 @@ +name: Coverage Build - Rolling +on: + workflow_dispatch: + push: + branches: + - master + pull_request: + branches: + - master + +jobs: + coverage_rolling: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-build-coverage.yml@master + secrets: inherit + with: + ros_distro: rolling + os_name: ubuntu-22.04 diff --git a/.github/workflows/rolling-pre-commit.yml b/.github/workflows/rolling-pre-commit.yml new file mode 100644 index 0000000000..9c87311bd7 --- /dev/null +++ b/.github/workflows/rolling-pre-commit.yml @@ -0,0 +1,14 @@ +name: Pre-Commit - Rolling + +on: + workflow_dispatch: + pull_request: + branches: + - master + +jobs: + pre-commit: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-pre-commit.yml@master + with: + ros_distro: rolling + os_name: ubuntu-22.04 diff --git a/.github/workflows/update-pre-commit.yml b/.github/workflows/update-pre-commit.yml new file mode 100644 index 0000000000..8b9545dff1 --- /dev/null +++ b/.github/workflows/update-pre-commit.yml @@ -0,0 +1,12 @@ +name: Auto Update pre-commit +# Update pre-commit config and create PR if changes are detected +# author: Christoph Fröhlich + +on: + workflow_dispatch: + schedule: + - cron: '0 0 * * 0' # Run every Sunday at midnight + +jobs: + auto_update_and_create_pr: + uses: ros-controls/ros2_control_ci/.github/workflows/reusable-update-pre-commit.yml@master diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 6e6d41cc9c..6da427c6ee 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -16,7 +16,7 @@ repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.4.0 + rev: v4.5.0 hooks: - id: check-added-large-files - id: check-ast @@ -36,7 +36,7 @@ repos: # Python hooks - repo: https://github.com/asottile/pyupgrade - rev: v3.4.0 + rev: v3.15.1 hooks: - id: pyupgrade args: [--py36-plus] @@ -49,40 +49,38 @@ repos: args: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"] - repo: https://github.com/psf/black - rev: 23.3.0 + rev: 24.2.0 hooks: - id: black args: ["--line-length=99"] - repo: https://github.com/pycqa/flake8 - rev: 6.0.0 + rev: 7.0.0 hooks: - id: flake8 args: ["--extend-ignore=E501"] # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v15.0.6 + rev: v17.0.6 hooks: - id: clang-format + args: ['-fallback-style=none', '-i'] - repo: local hooks: - id: ament_cppcheck name: ament_cppcheck description: Static code analysis of C/C++ files. - stages: [commit] - entry: ament_cppcheck + entry: env AMENT_CPPCHECK_ALLOW_SLOW_VERSIONS=1 ament_cppcheck language: system files: \.(h\+\+|h|hh|hxx|hpp|cuh|c|cc|cpp|cu|c\+\+|cxx|tpp|txx)$ - # Maybe use https://github.com/cpplint/cpplint instead - repo: local hooks: - id: ament_cpplint name: ament_cpplint description: Static code analysis of C/C++ files. - stages: [commit] entry: ament_cpplint language: system files: \.(h\+\+|h|hh|hxx|hpp|cuh|c|cc|cpp|cu|c\+\+|cxx|tpp|txx)$ @@ -94,7 +92,6 @@ repos: - id: ament_lint_cmake name: ament_lint_cmake description: Check format of CMakeLists.txt files. - stages: [commit] entry: ament_lint_cmake language: system files: CMakeLists\.txt$ @@ -105,7 +102,6 @@ repos: - id: ament_copyright name: ament_copyright description: Check if copyright notice is available in all files. - stages: [commit] entry: ament_copyright language: system @@ -128,8 +124,18 @@ repos: # Spellcheck in comments and docs # skipping of *.svg files is not working... - repo: https://github.com/codespell-project/codespell - rev: v2.2.4 + rev: v2.2.6 hooks: - id: codespell - args: ['--write-changes'] - exclude: CHANGELOG\.rst|\.(svg|pyc)$ + args: ['--write-changes', '--uri-ignore-words-list=ist', '-L manuel'] + exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$ + + - repo: https://github.com/python-jsonschema/check-jsonschema + rev: 0.28.0 + hooks: + - id: check-github-workflows + args: ["--verbose"] + - id: check-github-actions + args: ["--verbose"] + - id: check-dependabot + args: ["--verbose"] diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index d9cdc27041..df91cfbf20 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -54,7 +54,9 @@ As this project, by default, uses the default GitHub issue labels ## Licensing -Any contribution that you make to this repository will be under the Apache 2 License, as dictated by that [license]: +Any contribution that you make to this repository will +be under the Apache 2 License, as dictated by that +[license](http://www.apache.org/licenses/LICENSE-2.0.html): ~~~ 5. Submission of Contributions. Unless You explicitly state otherwise, @@ -69,4 +71,3 @@ Any contribution that you make to this repository will be under the Apache 2 Lic [issues]: https://github.com/ros-controls/ros2_control/issues [closed-issues]: https://github.com/ros-controls/ros2_control/issues?utf8=%E2%9C%93&q=is%3Aissue%20is%3Aclosed%20 [help-wanted]: https://github.com/ros-controls/ros2_control/issues?q=is%3Aopen+is%3Aissue+label%3A%22help+wanted%22 -[license]: http://www.apache.org/licenses/LICENSE-2.0.html diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index ee2ee87218..2112708638 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -341,7 +341,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String & RCLCPP_INFO(get_logger(), "Received robot description from topic."); RCLCPP_DEBUG( get_logger(), "'Content of robot description file: %s", robot_description.data.c_str()); - // TODO(Manuel): errors should probably be caught since we don't want controller_manager node + // TODO(mamueluth): errors should probably be caught since we don't want controller_manager node // to die if a non valid urdf is passed. However, should maybe be fine tuned. try { diff --git a/controller_manager/test/controller_manager_test_common.hpp b/controller_manager/test/controller_manager_test_common.hpp index 7bf5cae628..ac66392a13 100644 --- a/controller_manager/test/controller_manager_test_common.hpp +++ b/controller_manager/test/controller_manager_test_common.hpp @@ -88,7 +88,7 @@ class ControllerManagerFixture : public ::testing::Test } else { - // TODO(Manuel) : passing via topic not working in test setup, tested cm does + // TODO(mamueluth) : passing via topic not working in test setup, tested cm does // not receive msg. Have to check this... // this is just a workaround to skip passing diff --git a/hardware_interface/test/test_handle.cpp b/hardware_interface/test/test_handle.cpp index 16ca710e9d..da8258c643 100644 --- a/hardware_interface/test/test_handle.cpp +++ b/hardware_interface/test/test_handle.cpp @@ -27,9 +27,7 @@ constexpr auto FOO_INTERFACE = "FooInterface"; TEST(TestHandle, command_interface) { double value = 1.337; - CommandInterface interface { - JOINT_NAME, FOO_INTERFACE, &value - }; + CommandInterface interface{JOINT_NAME, FOO_INTERFACE, &value}; EXPECT_DOUBLE_EQ(interface.get_value(), value); EXPECT_NO_THROW(interface.set_value(0.0)); EXPECT_DOUBLE_EQ(interface.get_value(), 0.0); @@ -38,9 +36,7 @@ TEST(TestHandle, command_interface) TEST(TestHandle, state_interface) { double value = 1.337; - StateInterface interface { - JOINT_NAME, FOO_INTERFACE, &value - }; + StateInterface interface{JOINT_NAME, FOO_INTERFACE, &value}; EXPECT_DOUBLE_EQ(interface.get_value(), value); // interface.set_value(5); compiler error, no set_value function } diff --git a/rqt_controller_manager/setup.py b/rqt_controller_manager/setup.py index bcde9ff7da..44ef78ced2 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -1,3 +1,17 @@ +# Copyright 2024 Apache License, Version 2.0 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from glob import glob from setuptools import setup From dbfe9ea257314c87a1276af5e964e3911da8daec Mon Sep 17 00:00:00 2001 From: "Felix Exner (fexner)" Date: Wed, 28 Feb 2024 09:56:40 +0100 Subject: [PATCH 20/20] [BREAKING CHANGE] Use `robot_description` topic instead of `~/robot_description` and update docs regarding this (#1410) * Use `robot_description` instead of `~/robot_description` topic Using robot_description by default instead will work for most people out of the box while also working correctly with different descriptions in different namespaces when using remaps. Nowadays, the parameter is deprecated and will be removed. --------- Co-authored-by: Sai Kishor Kothakota Co-authored-by: Dr. Denis --- controller_manager/doc/userdoc.rst | 53 +++++++++++++++++-- controller_manager/src/controller_manager.cpp | 4 +- 2 files changed, 51 insertions(+), 6 deletions(-) diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index 46c46fa028..46781d461c 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -70,10 +70,6 @@ hardware_components_initial_state.unconfigured (optional; list; default: hardware_components_initial_state.inactive (optional; list; default: empty) Defines which hardware components will be configured immediately when controller manager is started. -robot_description (mandatory; string) - String with the URDF string as robot description. - This is usually result of the parsed description files by ``xacro`` command. - update_rate (mandatory; integer) The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controller and writes commands to hardware. @@ -83,6 +79,55 @@ update_rate (mandatory; integer) Name of a plugin exported using ``pluginlib`` for a controller. This is a class from which controller's instance with name "``controller_name``" is created. +Subscribers +----------- + +robot_description (std_msgs/msg/String) + The URDF string as robot description. + This is usually published by the ``robot_state_publisher`` node. + +Handling Multiple Controller Managers +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +When dealing with multiple controller managers, you have two options for managing different robot descriptions: + +1. **Using Namespaces:** You can place both the ``robot_state_publisher`` and the ``controller_manager`` nodes into the same namespace. + +.. code-block:: python + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + namespace="rrbot", + ) + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + namespace="rrbot", + ) + +2. **Using Remappings:** You can use remappings to handle different robot descriptions. This involves relaying topics using the ``remappings`` tag, allowing you to specify custom topics for each controller manager. + +.. code-block:: python + + control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[robot_controllers], + output="both", + remappings=[('robot_description', '/rrbot/robot_description')] + ) + robot_state_pub_node = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + output="both", + parameters=[robot_description], + namespace="rrbot", + ) Helper scripts -------------- diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 2112708638..b7d2869107 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -284,7 +284,7 @@ ControllerManager::ControllerManager( RCLCPP_WARN( get_logger(), "[Deprecated] Passing the robot description parameter directly to the control_manager node " - "is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead."); + "is deprecated. Use the 'robot_description' topic from 'robot_state_publisher' instead."); init_resource_manager(robot_description_); init_services(); } @@ -329,7 +329,7 @@ void ControllerManager::subscribe_to_robot_description_topic() // set QoS to transient local to get messages that have already been published // (if robot state publisher starts before controller manager) robot_description_subscription_ = create_subscription( - "~/robot_description", rclcpp::QoS(1).transient_local(), + "robot_description", rclcpp::QoS(1).transient_local(), std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1)); RCLCPP_INFO( get_logger(), "Subscribing to '%s' topic for robot description.",