diff --git a/.clang-format b/.clang-format index 9c21e1e17c..698bda7da8 100644 --- a/.clang-format +++ b/.clang-format @@ -10,6 +10,6 @@ ConstructorInitializerIndentWidth: 0 ContinuationIndentWidth: 2 DerivePointerAlignment: false PointerAlignment: Middle -ReflowComments: false +ReflowComments: true IncludeBlocks: Preserve ... diff --git a/.docker/README.md b/.docker/README.md index b79ca69449..238e261b7b 100644 --- a/.docker/README.md +++ b/.docker/README.md @@ -3,7 +3,7 @@ Meant to provide basic docker containers for CI or development purposes. To use them, make sure you have [Docker](https://docs.docker.com/get-docker/) installed. You then can pull the latest source or build image or build any version and run the image by following tag specific commands as described below: ## Source folder and tag -Downloads and builds ros2_controls into a workspace for development use exactly as is found [here](https://ros-controls.github.io/control.ros.org/getting_started.html#compiling). This is primarily used for development and CI of ros2_control and related packages. +Downloads and builds ros2_controls into a workspace for development use exactly as is found [here](https://control.ros.org/master/doc/getting_started/getting_started.html#building-from-source). This is primarily used for development and CI of ros2_control and related packages. You can pull a prebuilt image with this docker tag: `ghcr.io/ros-controls/ros2_control_source`. @@ -30,7 +30,7 @@ docker run -it --mount type=volume,source=name-of-volume,destination=/root/ws_ro Note: this is probably the preferred solution as changes persist across rebuilds of container and doesn't require you to pull all repositories that you want to edit as they'll already be in the container. ## Release folder and tag -Installs ros2_control in the base ros2 docker container as mentioned [here](https://ros-controls.github.io/control.ros.org/getting_started.html#getting-started). This is mainly intended for development of external packages that rely on ros2_control. +Installs ros2_control in the base ros2 docker container as mentioned [here](https://control.ros.org/master/doc/getting_started/getting_started.html#building-from-source). This is mainly intended for development of external packages that rely on ros2_control. You can pull a prebuilt image using the following tag: `ghcr.io/ros2-controls/ros2_control_release`. diff --git a/.github/ISSUE_TEMPLATE/good-first-issue.md b/.github/ISSUE_TEMPLATE/good-first-issue.md index a4f155ffda..57779881d2 100644 --- a/.github/ISSUE_TEMPLATE/good-first-issue.md +++ b/.github/ISSUE_TEMPLATE/good-first-issue.md @@ -28,7 +28,7 @@ Nothing. This issue is meant to welcome you to Open Source :) We are happy to wa - [ ] 🙋 **Claim this issue**: Comment below. If someone else has claimed it, ask if they've opened a pull request already and if they're stuck -- maybe you can help them solve a problem or move it along! -- [ ] 🗄️ **Create a local workspace** for making your changes and testing [following these instructions](https://docs.ros.org/en/galactic/Tutorials/Workspace/Creating-A-Workspace.html), for Step3 use "Download Source Code" section with [these instructions](https://ros-controls.github.io/control.ros.org/getting_started.html#compiling). +- [ ] 🗄️ **Create a local workspace** for making your changes and testing [following these instructions](https://docs.ros.org/en/rolling/Tutorials/Workspace/Creating-A-Workspace.html), for Step 3 use "Download Source Code" section with [these instructions](https://control.ros.org/master/doc/getting_started/getting_started.html#building-from-source). - [ ] 🍴 **Fork the repository** using the handy button at the top of the repository page and **clone** it into `~/ws_ros2_control/src/ros-controls/ros2_control`, [here is a guide that you can follow](https://guides.github.com/activities/forking/) (You will have to remove or empty the existing `ros2_control` folder before cloning your own fork) @@ -53,8 +53,8 @@ Nothing. This issue is meant to welcome you to Open Source :) We are happy to wa Don’t hesitate to ask questions or to get help if you feel like you are getting stuck. For example leave a comment below! Furthermore, you find helpful resources here: -* [ROS2 Control Contribution Guide](https://ros-controls.github.io/control.ros.org/contributing.html) -* [ROS2 Tutorials](https://docs.ros.org/en/galactic/Tutorials.html) +* [ROS2 Control Contribution Guide](https://control.ros.org/master/doc/contributing/contributing.html) +* [ROS2 Tutorials](https://docs.ros.org/en/rolling/Tutorials.html) * [ROS Answers](https://answers.ros.org/questions/) **Good luck with your first issue!** diff --git a/.github/mergify.yml b/.github/mergify.yml index e62f958961..49d2acedfa 100644 --- a/.github/mergify.yml +++ b/.github/mergify.yml @@ -2,30 +2,12 @@ pull_request_rules: - name: Backport to humble at reviewers discretion conditions: - base=master - - "label=humble-galactic" + - "label=backport-humble" actions: backport: branches: - humble - - name: Backport to galactic at reviewers discretion - conditions: - - base=master - - "label=backport-galactic" - actions: - backport: - branches: - - galactic - - - name: Backport to foxy at reviewers discretion - conditions: - - base=master - - "label=backport-foxy" - actions: - backport: - branches: - - foxy - - name: Ask to resolve conflict conditions: - conflict diff --git a/.github/workflows/README.md b/.github/workflows/README.md index e784883593..5e8c8ef0fd 100644 --- a/.github/workflows/README.md +++ b/.github/workflows/README.md @@ -2,6 +2,5 @@ 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) -**Galactic** | [`galactic`](https://github.com/ros-controls/ros2_control/tree/galactic) | [![Galactic Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-main.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-main.yml?branch=galactic)
[![Galactic Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-testing.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-testing.yml?branch=galactic)
[![Galactic Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-main.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-main.yml?branch=galactic)
[![Galactic Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-testing.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-testing.yml?branch=galactic) | [Documentation](https://control.ros.org/galactic/index.html)
[API Reference](https://control.ros.org/galactic/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#galactic) -**Foxy** | [`foxy`](https://github.com/ros-controls/ros2_control/tree/foxy) | [![Foxy Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-main.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-main.yml?branch=foxy)
[![Foxy Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-testing.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-testing.yml?branch=foxy)
[![Foxy Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-main.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-main.yml?branch=foxy)
[![Foxy Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-testing.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-testing.yml?branch=foxy) | [Documentation](https://control.ros.org/foxy/index.html)
[API Reference](https://control.ros.org/foxy/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#foxy) diff --git a/.github/workflows/ci-check-docs.yml b/.github/workflows/ci-check-docs.yml new file mode 100644 index 0000000000..90a822aa72 --- /dev/null +++ b/.github/workflows/ci-check-docs.yml @@ -0,0 +1,12 @@ +name: Check Docs + +on: + workflow_dispatch: + pull_request: + +jobs: + check-docs: + name: Check Docs + uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@master + with: + ROS2_CONTROL_PR: ${{ github.ref }} diff --git a/.github/workflows/ci-coverage-build.yml b/.github/workflows/ci-coverage-build.yml index 9c3a1378ee..b339b45e66 100644 --- a/.github/workflows/ci-coverage-build.yml +++ b/.github/workflows/ci-coverage-build.yml @@ -16,11 +16,11 @@ jobs: env: ROS_DISTRO: rolling steps: - - uses: ros-tooling/setup-ros@0.6.1 + - uses: ros-tooling/setup-ros@0.7.0 with: required-ros-distributions: ${{ env.ROS_DISTRO }} - uses: actions/checkout@v3 - - uses: ros-tooling/action-ros-ci@0.3.0 + - uses: ros-tooling/action-ros-ci@0.3.3 with: target-ros2-distro: ${{ env.ROS_DISTRO }} import-token: ${{ secrets.GITHUB_TOKEN }} diff --git a/.github/workflows/ci-format.yml b/.github/workflows/ci-format.yml index 83fe361f4d..9b91657851 100644 --- a/.github/workflows/ci-format.yml +++ b/.github/workflows/ci-format.yml @@ -13,7 +13,7 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 - - uses: actions/setup-python@v4.6.0 + - uses: actions/setup-python@v4.7.0 with: python-version: '3.10' - name: Install system hooks diff --git a/.github/workflows/ci-ros-lint.yml b/.github/workflows/ci-ros-lint.yml index 67d1b2c5e9..37c371ce83 100644 --- a/.github/workflows/ci-ros-lint.yml +++ b/.github/workflows/ci-ros-lint.yml @@ -5,14 +5,16 @@ on: jobs: ament_lint: name: ament_${{ matrix.linter }} - runs-on: ubuntu-20.04 + 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@v3 - - uses: ros-tooling/setup-ros@0.6.1 + - uses: ros-tooling/setup-ros@0.7.0 - uses: ros-tooling/action-ros-lint@v0.1 with: distribution: rolling @@ -29,14 +31,14 @@ jobs: ament_lint_100: name: ament_${{ matrix.linter }} - runs-on: ubuntu-20.04 + runs-on: ubuntu-latest strategy: fail-fast: false matrix: linter: [cpplint] steps: - uses: actions/checkout@v3 - - uses: ros-tooling/setup-ros@0.6.1 + - uses: ros-tooling/setup-ros@0.7.0 - uses: ros-tooling/action-ros-lint@v0.1 with: distribution: rolling diff --git a/.github/workflows/galactic-abi-compatibility.yml b/.github/workflows/galactic-abi-compatibility.yml deleted file mode 100644 index 06a48ef9c7..0000000000 --- a/.github/workflows/galactic-abi-compatibility.yml +++ /dev/null @@ -1,20 +0,0 @@ -name: Galactic - ABI Compatibility Check -on: - workflow_dispatch: - branches: - - galactic - pull_request: - branches: - - galactic - -jobs: - abi_check: - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v3 - - uses: ros-industrial/industrial_ci@master - env: - ROS_DISTRO: galactic - ROS_REPO: main - ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} - NOT_TEST_BUILD: true diff --git a/.github/workflows/galactic-rhel-binary-build.yml b/.github/workflows/galactic-rhel-binary-build.yml deleted file mode 100644 index ca0b30382a..0000000000 --- a/.github/workflows/galactic-rhel-binary-build.yml +++ /dev/null @@ -1,33 +0,0 @@ -name: Galactic RHEL Binary Build -on: - workflow_dispatch: - branches: - - galactic - pull_request: - branches: - - galactic - push: - branches: - - galactic - schedule: - # Run every day to detect flakiness and broken dependencies - - cron: '03 1 * * *' - - -jobs: - galactic_rhel_binary: - name: Galactic RHEL binary build - runs-on: ubuntu-latest - env: - ROS_DISTRO: galactic - container: ghcr.io/ros-controls/ros:galactic-rhel - steps: - - uses: actions/checkout@v3 - with: - path: src/ros2_control - - run: | - rosdep update - rosdep install -iy --from-path src/ros2_control - source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash - colcon build - colcon test diff --git a/.github/workflows/foxy-abi-compatibility.yml b/.github/workflows/iron-abi-compatibility.yml similarity index 79% rename from .github/workflows/foxy-abi-compatibility.yml rename to .github/workflows/iron-abi-compatibility.yml index 7ce17effd0..f92166b0c1 100644 --- a/.github/workflows/foxy-abi-compatibility.yml +++ b/.github/workflows/iron-abi-compatibility.yml @@ -1,11 +1,11 @@ -name: Foxy - ABI Compatibility Check +name: Iron - ABI Compatibility Check on: workflow_dispatch: branches: - - foxy + - master pull_request: branches: - - foxy + - master jobs: abi_check: @@ -14,7 +14,7 @@ jobs: - uses: actions/checkout@v3 - uses: ros-industrial/industrial_ci@master env: - ROS_DISTRO: foxy + ROS_DISTRO: iron ROS_REPO: main ABICHECK_URL: github:${{ github.repository }}#${{ github.base_ref }} NOT_TEST_BUILD: true diff --git a/.github/workflows/foxy-binary-build-main.yml b/.github/workflows/iron-binary-build-main.yml similarity index 68% rename from .github/workflows/foxy-binary-build-main.yml rename to .github/workflows/iron-binary-build-main.yml index 0d74ce64e4..be225cc0e1 100644 --- a/.github/workflows/foxy-binary-build-main.yml +++ b/.github/workflows/iron-binary-build-main.yml @@ -1,17 +1,17 @@ -name: Foxy Binary Build - main +name: Iron Binary Build - main # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' on: workflow_dispatch: branches: - - foxy + - master pull_request: branches: - - foxy + - master push: branches: - - foxy + - master schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' @@ -20,7 +20,7 @@ jobs: binary: uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml with: - ros_distro: foxy + ros_distro: iron ros_repo: main - upstream_workspace: ros2_control-not-released.foxy.repos - ref_for_scheduled_build: foxy + upstream_workspace: ros2_control-not-released.iron.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/galactic-binary-build-main.yml b/.github/workflows/iron-binary-build-testing.yml similarity index 63% rename from .github/workflows/galactic-binary-build-main.yml rename to .github/workflows/iron-binary-build-testing.yml index f50c773444..c44786c7e2 100644 --- a/.github/workflows/galactic-binary-build-main.yml +++ b/.github/workflows/iron-binary-build-testing.yml @@ -1,17 +1,17 @@ -name: Galactic Binary Build - main +name: Iron Binary Build - testing # author: Denis Štogl # description: 'Build & test all dependencies from released (binary) packages.' on: workflow_dispatch: branches: - - galactic + - master pull_request: branches: - - galactic + - master push: branches: - - galactic + - master schedule: # Run every morning to detect flakiness and broken dependencies - cron: '03 1 * * *' @@ -20,7 +20,7 @@ jobs: binary: uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml with: - ros_distro: galactic - ros_repo: main - upstream_workspace: ros2_control-not-released.galactic.repos - ref_for_scheduled_build: galactic + ros_distro: iron + ros_repo: testing + upstream_workspace: ros2_control-not-released.iron.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/iron-rhel-binary-build.yml b/.github/workflows/iron-rhel-binary-build.yml new file mode 100644 index 0000000000..afcdf332d4 --- /dev/null +++ b/.github/workflows/iron-rhel-binary-build.yml @@ -0,0 +1,32 @@ +name: Iron RHEL Binary Build +on: + workflow_dispatch: + branches: + - iron +# pull_request: +# branches: +# - iron +# push: +# branches: +# - iron +# schedule: +# # Run every day to detect flakiness and broken dependencies +# - cron: '03 1 * * *' + +jobs: + iron_rhel_binary: + name: Iron RHEL binary build + runs-on: ubuntu-latest + env: + ROS_DISTRO: iron + container: ghcr.io/ros-controls/ros:iron-rhel + steps: + - uses: actions/checkout@v3 + with: + path: src/ros2_control + - run: | + rosdep update + rosdep install -iy --from-path src/ros2_control + source /opt/ros/${{ env.ROS_DISTRO }}/setup.bash + colcon build + colcon test diff --git a/.github/workflows/foxy-semi-binary-build-main.yml b/.github/workflows/iron-semi-binary-build-main.yml similarity index 67% rename from .github/workflows/foxy-semi-binary-build-main.yml rename to .github/workflows/iron-semi-binary-build-main.yml index 68e709cc00..1d72d06149 100644 --- a/.github/workflows/foxy-semi-binary-build-main.yml +++ b/.github/workflows/iron-semi-binary-build-main.yml @@ -1,16 +1,16 @@ -name: Foxy Semi-Binary Build - main +name: Iron Semi-Binary Build - main # description: 'Build & test that compiles the main dependencies from source.' on: workflow_dispatch: branches: - - foxy + - master pull_request: branches: - - foxy + - master push: branches: - - foxy + - master schedule: # Run every morning to detect flakiness and broken dependencies - cron: '33 1 * * *' @@ -19,7 +19,7 @@ jobs: semi_binary: uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml with: - ros_distro: foxy + ros_distro: iron ros_repo: main - upstream_workspace: ros2_control.foxy.repos - ref_for_scheduled_build: foxy + upstream_workspace: ros2_control.iron.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/galactic-semi-binary-build-main.yml b/.github/workflows/iron-semi-binary-build-testing.yml similarity index 58% rename from .github/workflows/galactic-semi-binary-build-main.yml rename to .github/workflows/iron-semi-binary-build-testing.yml index 0578366a45..48707cd914 100644 --- a/.github/workflows/galactic-semi-binary-build-main.yml +++ b/.github/workflows/iron-semi-binary-build-testing.yml @@ -1,13 +1,16 @@ -name: Galactic Semi-Binary Build - main +name: Iron Semi-Binary Build - testing # description: 'Build & test that compiles the main dependencies from source.' on: workflow_dispatch: branches: - - galactic + - master + pull_request: + branches: + - master push: branches: - - galactic + - master schedule: # Run every morning to detect flakiness and broken dependencies - cron: '33 1 * * *' @@ -16,7 +19,7 @@ jobs: semi_binary: uses: ./.github/workflows/reusable-industrial-ci-with-cache.yml with: - ros_distro: galactic - ros_repo: main - upstream_workspace: ros2_control.galactic.repos - ref_for_scheduled_build: galactic + ros_distro: iron + ros_repo: testing + upstream_workspace: ros2_control.iron.repos + ref_for_scheduled_build: master diff --git a/.github/workflows/iron-source-build.yml b/.github/workflows/iron-source-build.yml new file mode 100644 index 0000000000..31eccd1bef --- /dev/null +++ b/.github/workflows/iron-source-build.yml @@ -0,0 +1,19 @@ +name: Iron Source Build +on: + workflow_dispatch: + branches: + - master + push: + branches: + - master + schedule: + # Run every day to detect flakiness and broken dependencies + - cron: '03 3 * * *' + +jobs: + source: + uses: ./.github/workflows/reusable-ros-tooling-source-build.yml + with: + ros_distro: iron + ref: master + ros2_repo_branch: iron diff --git a/.github/workflows/prerelease-check.yml b/.github/workflows/prerelease-check.yml index b9460bda47..eefb15ae87 100644 --- a/.github/workflows/prerelease-check.yml +++ b/.github/workflows/prerelease-check.yml @@ -9,9 +9,8 @@ on: default: 'rolling' type: choice options: - - foxy - - galactic - humble + - iron - rolling branch: description: 'Chose branch for distro' @@ -19,9 +18,8 @@ on: default: 'master' type: choice options: - - foxy - - galactic - humble + - iron - master jobs: diff --git a/.github/workflows/reusable-ros-tooling-source-build.yml b/.github/workflows/reusable-ros-tooling-source-build.yml index 5a715fd503..6cd59ce5f9 100644 --- a/.github/workflows/reusable-ros-tooling-source-build.yml +++ b/.github/workflows/reusable-ros-tooling-source-build.yml @@ -14,7 +14,7 @@ on: required: true type: string ros2_repo_branch: - description: 'Branch in the ros2/ros2 repozitory from which ".repos" should be used. Possible values: master (Rolling), humble, galactic, foxy.' + description: 'Branch in the ros2/ros2 repository from which ".repos" should be used. Possible values: master (Rolling), humble.' default: 'master' required: false type: string @@ -26,13 +26,13 @@ jobs: strategy: fail-fast: false steps: - - uses: ros-tooling/setup-ros@0.6.1 + - uses: ros-tooling/setup-ros@0.7.0 with: required-ros-distributions: ${{ inputs.ros_distro }} - uses: actions/checkout@v3 with: ref: ${{ inputs.ref }} - - uses: ros-tooling/action-ros-ci@0.3.0 + - uses: ros-tooling/action-ros-ci@0.3.3 with: target-ros2-distro: ${{ inputs.ros_distro }} # build all packages listed in the meta package diff --git a/.github/workflows/reviewer_lottery.yml b/.github/workflows/reviewer_lottery.yml index 94f3d9bde6..772809825f 100644 --- a/.github/workflows/reviewer_lottery.yml +++ b/.github/workflows/reviewer_lottery.yml @@ -8,6 +8,6 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v3 - - uses: uesteibar/reviewer-lottery@v2 + - uses: uesteibar/reviewer-lottery@v3 with: repo-token: ${{ secrets.GITHUB_TOKEN }} diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 9cb5781b56..d9cdc27041 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -21,7 +21,7 @@ Please try to include as much information as you can. Details like these are inc ## Contributing via Pull Requests -The following guidance should be up-to-date, but the documentation as found [here](https://ros-controls.github.io/control.ros.org/contributing.html#pull-requests) should prove as the final say. +The following guidance should be up-to-date, but the documentation as found [here](https://control.ros.org/master/doc/contributing/contributing.html#pull-requests) should prove as the final say. Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that: diff --git a/README.md b/README.md index 276ffb9e6a..b68c11705c 100644 --- a/README.md +++ b/README.md @@ -3,7 +3,7 @@ [![Licence](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) This package is a part of the ros2_control framework. -For more, please check the [documentation](https://ros-controls.github.io/control.ros.org/). +For more, please check the [documentation](https://control.ros.org/). ## Build status @@ -11,9 +11,8 @@ For more, please check the [documentation](https://ros-controls.github.io/contro 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** | [`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 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) | [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 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) -**Galactic** | [`galactic`](https://github.com/ros-controls/ros2_control/tree/galactic) | [![Galactic Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-main.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-binary-build-main.yml?branch=galactic)
[![Galactic Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-main.yml/badge.svg?branch=galactic)](https://github.com/ros-controls/ros2_control/actions/workflows/galactic-semi-binary-build-main.yml?branch=galactic) | [Documentation](https://control.ros.org/galactic/index.html)
[API Reference](https://control.ros.org/galactic/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#galactic) -**Foxy** | [`foxy`](https://github.com/ros-controls/ros2_control/tree/foxy) | [![Foxy Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-main.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-binary-build-main.yml?branch=foxy)
[![Foxy Semi-Binary Build](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-main.yml/badge.svg?branch=foxy)](https://github.com/ros-controls/ros2_control/actions/workflows/foxy-semi-binary-build-main.yml?branch=foxy) | [Documentation](https://control.ros.org/foxy/index.html)
[API Reference](https://control.ros.org/foxy/doc/api/index.html) | [ros2_control](https://index.ros.org/p/ros2_control/#foxy) [Detailed build status](.github/workflows/README.md) diff --git a/controller_interface/CHANGELOG.rst b/controller_interface/CHANGELOG.rst index 29f69150d2..aaa2667a06 100644 --- a/controller_interface/CHANGELOG.rst +++ b/controller_interface/CHANGELOG.rst @@ -2,6 +2,26 @@ Changelog for package controller_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- +* add a broadcaster for range sensor (`#1091 `_) +* Contributors: flochre + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- +* Add -Wconversion flag to protect future developments (`#1053 `_) +* enable ReflowComments to also use ColumnLimit on comments (`#1037 `_) +* Contributors: Sai Kishor Kothakota, gwalck + 3.13.0 (2023-05-18) ------------------- diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 034556d19f..88a54d5c7a 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16) project(controller_interface LANGUAGES CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp index 37b784011c..2bdccefdc5 100644 --- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp +++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp @@ -41,7 +41,8 @@ class ChainableControllerInterface : public ControllerInterfaceBase virtual ~ChainableControllerInterface() = default; /** - * Control step update. Command interfaces are updated based on on reference inputs and current states. + * Control step update. Command interfaces are updated based on on reference inputs and current + * states. * **The method called in the (real-time) control loop.** * * \param[in] time The time at the start of this control loop iteration @@ -83,7 +84,9 @@ class ChainableControllerInterface : public ControllerInterfaceBase * * \param[in] flag marking a switch to or from chained mode. * - * \returns true if controller successfully switched between "chained" and "external" mode. \default returns true so the method don't have to be overridden if controller can always switch chained mode. + * \returns true if controller successfully switched between "chained" and "external" mode. + * \default returns true so the method don't have to be overridden if controller can always switch + * chained mode. */ virtual bool on_set_chained_mode(bool chained_mode); diff --git a/controller_interface/include/controller_interface/controller_interface_base.hpp b/controller_interface/include/controller_interface/controller_interface_base.hpp index fdaffac06f..05ee0c8830 100644 --- a/controller_interface/include/controller_interface/controller_interface_base.hpp +++ b/controller_interface/include/controller_interface/controller_interface_base.hpp @@ -74,15 +74,13 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy /// Get configuration for controller's required command interfaces. /** - * Method used by the controller_manager to get the set of command interfaces used by the controller. - * Each controller can use individual method to determine interface names that in simples case - * have the following format: `/`. - * The method is called only in `inactive` or `active` state, i.e., `on_configure` has to be - * called first. - * The configuration is used to check if controller can be activated and to claim interfaces from - * hardware. - * The claimed interfaces are populated in the - * \ref ControllerInterfaceBase::command_interfaces_ "command_interfaces_" member. + * Method used by the controller_manager to get the set of command interfaces used by the + * controller. Each controller can use individual method to determine interface names that in + * simples case have the following format: `/`. The method is called only in + * `inactive` or `active` state, i.e., `on_configure` has to be called first. The configuration is + * used to check if controller can be activated and to claim interfaces from hardware. The claimed + * interfaces are populated in the \ref ControllerInterfaceBase::command_interfaces_ + * "command_interfaces_" member. * * \returns configuration of command interfaces. */ @@ -131,7 +129,8 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy virtual CallbackReturn on_init() = 0; /** - * Control step update. Command interfaces are updated based on on reference inputs and current states. + * Control step update. Command interfaces are updated based on on reference inputs and current + * states. * **The method called in the (real-time) control loop.** * * \param[in] time The time at the start of this control loop iteration diff --git a/controller_interface/include/controller_interface/helpers.hpp b/controller_interface/include/controller_interface/helpers.hpp index 45b048fc72..b571751f55 100644 --- a/controller_interface/include/controller_interface/helpers.hpp +++ b/controller_interface/include/controller_interface/helpers.hpp @@ -23,19 +23,19 @@ namespace controller_interface { /// Reorder interfaces with references according to joint names or full interface names. /** - * Method to reorder and check if all expected interfaces are provided for the joint. - * Fill `ordered_interfaces` with references from `unordered_interfaces` in the same order as in - * `ordered_names`. - * - * \param[in] unordered_interfaces vector with loaned unordered state or command interfaces. - * \param[in] ordered_names vector with ordered names to order \p unordered_interfaces. - * The valued inputs are list of joint names or interface full names. - * If joint names are used for ordering, \p interface_type specifies valid interface. - * If full interface names are used for ordering, \p interface_type should be empty string (""). - * \param[in] interface_type used for ordering interfaces with respect to joint names. - * \param[out] ordered_interfaces vector with ordered interfaces. - * \return true if all interfaces or joints in \p ordered_names are found, otherwise false. - */ + * Method to reorder and check if all expected interfaces are provided for the joint. + * Fill `ordered_interfaces` with references from `unordered_interfaces` in the same order as in + * `ordered_names`. + * + * \param[in] unordered_interfaces vector with loaned unordered state or command interfaces. + * \param[in] ordered_names vector with ordered names to order \p unordered_interfaces. + * The valued inputs are list of joint names or interface full names. + * If joint names are used for ordering, \p interface_type specifies valid interface. + * If full interface names are used for ordering, \p interface_type should be empty string (""). + * \param[in] interface_type used for ordering interfaces with respect to joint names. + * \param[out] ordered_interfaces vector with ordered interfaces. + * \return true if all interfaces or joints in \p ordered_names are found, otherwise false. + */ template bool get_ordered_interfaces( std::vector & unordered_interfaces, const std::vector & ordered_names, diff --git a/controller_interface/include/semantic_components/range_sensor.hpp b/controller_interface/include/semantic_components/range_sensor.hpp new file mode 100644 index 0000000000..baa9022c75 --- /dev/null +++ b/controller_interface/include/semantic_components/range_sensor.hpp @@ -0,0 +1,60 @@ +// Copyright 2023 flochre +// +// 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. + +#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ +#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ + +#include +#include +#include + +#include "semantic_components/semantic_component_interface.hpp" +#include "sensor_msgs/msg/range.hpp" + +namespace semantic_components +{ +class RangeSensor : public SemanticComponentInterface +{ +public: + explicit RangeSensor(const std::string & name) : SemanticComponentInterface(name, 1) + { + interface_names_.emplace_back(name_ + "/" + "range"); + } + + virtual ~RangeSensor() = default; + + /** + * Return Range reported by a sensor + * + * \return value of the range in meters + */ + float get_range() { return state_interfaces_[0].get().get_value(); } + + /// Return Range message with range in meters + /** + * Constructs and return a Range message from the current values. + * \return Range message from values; + */ + bool get_values_as_message(sensor_msgs::msg::Range & message) + { + // update the message values + message.range = get_range(); + + return true; + } +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_ diff --git a/controller_interface/package.xml b/controller_interface/package.xml index f20eccd9eb..d960bdf28a 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -2,7 +2,7 @@ controller_interface - 3.13.0 + 3.18.0 Description of controller_interface Bence Magyar Denis Štogl diff --git a/controller_manager/CHANGELOG.rst b/controller_manager/CHANGELOG.rst index d663cd3b32..2a9e348b8e 100644 --- a/controller_manager/CHANGELOG.rst +++ b/controller_manager/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- +* Controller sorting and proper execution in a chain (Fixes `#853 `_) (`#1063 `_) +* Contributors: Sai Kishor Kothakota, Christoph Fröhlich, Dr Denis, Bence Magyar + +3.17.0 (2023-08-07) +------------------- +* [CM] Fixes the issue with individual controller's update rate (`#1082 `_) +* Fix deprecation warning (`#1093 `_) +* Contributors: Christoph Fröhlich, Sai Kishor Kothakota + +3.16.0 (2023-07-09) +------------------- +* added controller manager runner to have update cycles (`#1075 `_) +* [CM] Make error message after trying to active controller more informative. (`#1066 `_) +* Fix equal and higher controller update rate (`#1070 `_) +* Create doc file for chained controllers (`#985 `_) +* Contributors: Dr. Denis, Sai Kishor Kothakota + +3.15.0 (2023-06-23) +------------------- +* Enable setting of initial state in HW compoments (`#1046 `_) +* [CM] Improve output when using robot description topic and give output about correct topic even remapped. (`#1059 `_) +* Contributors: Dr. Denis + +3.14.0 (2023-06-14) +------------------- +* Add -Wconversion flag to protect future developments (`#1053 `_) +* [CM] Use `robot_description` topic instead of parameter and don't crash on empty URDF 🦿 (`#940 `_) +* enable ReflowComments to also use ColumnLimit on comments (`#1037 `_) +* Docs: Use branch name substitution for all links (`#1031 `_) +* Add text to assertions references (`#1023 `_) +* Contributors: Christoph Fröhlich, Felix Exner (fexner), Manuel Muth, Sai Kishor Kothakota, gwalck + 3.13.0 (2023-05-18) ------------------- * Add class for thread management of async hw interfaces (`#981 `_) diff --git a/controller_manager/CMakeLists.txt b/controller_manager/CMakeLists.txt index 1d9b062efa..77ba823e1f 100644 --- a/controller_manager/CMakeLists.txt +++ b/controller_manager/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16) project(controller_manager LANGUAGES CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS @@ -14,6 +14,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS pluginlib rclcpp realtime_tools + std_msgs ) find_package(ament_cmake REQUIRED) @@ -143,6 +144,16 @@ if(BUILD_TESTING) ament_target_dependencies(test_controller_manager_srvs controller_manager_msgs ) + ament_add_gmock(test_controller_manager_urdf_passing + test/test_controller_manager_urdf_passing.cpp + ) + target_link_libraries(test_controller_manager_urdf_passing + controller_manager + ros2_control_test_assets::ros2_control_test_assets + ) + ament_target_dependencies(test_controller_manager_urdf_passing + controller_manager_msgs + ) add_library(test_controller_with_interfaces SHARED test/test_controller_with_interfaces/test_controller_with_interfaces.cpp diff --git a/controller_manager/doc/controller_chaining.rst b/controller_manager/doc/controller_chaining.rst new file mode 100644 index 0000000000..437cb70509 --- /dev/null +++ b/controller_manager/doc/controller_chaining.rst @@ -0,0 +1,119 @@ +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/controller_manager/doc/controller_chaining.rst + +.. _controller_chaining: + +Controller Chaining / Cascade Control +====================================== + +This document proposes a minimal-viable-implementation of serial controller chaining as described in `Chaining Controllers design document `__. +Cascade control is a specific type of controller chaining. + + +Scope of the Document and Background Knowledge +------------------------------------------------------- + +This approach focuses only on serial chaining of controllers and tries to reuse existing mechanisms for it. +It focuses on `inputs and outputs of a controller `__ and their management in the controller manager. +The concept of `controller groups `__ will be introduced only for clarity reasons, and its only meaning is that controllers in that group can be updated in arbitrary order. +This doesn't mean that the controller groups as described `in the controller chaining document `__ will not be introduced and used in the future. +Nevertheless, the author is convinced that this would add only unnecessary complexity at this stage, although in the long term they *could* provide clearer structure and interfaces. + +Motivation, Purpose and Use +--------------------------------- + +To describe the intent of this document, lets focus on the simple yet sufficient example `Example 2 from 'controllers_chaining' design docs `__: + +.. image:: images/chaining_example2.png + :alt: Example2 + + +In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers. +Let's now imagine a use-case where we don't only want to run all those controllers as a group, but also flexibly add preceding steps. +This means the following: + + 1. When a robot is started, we want to check if motor velocity control is working properly and therefore only PID controllers are activated. + At this stage we can control the input of PID controller also externally using topics. + However, these controllers also provide virtual interfaces, so we can chain them. + 2. Then "diff_drive_controller" is activated and attaches itself to the virtual input interfaces of PID controllers. + PID controllers also get informed that they are working in chained mode and therefore disable their external interface through subscriber. + Now we check if kinematics of differential robot is running properly. + 3. After that, "position_tracking" can be activated and attached to "diff_drive_controller" that disables its external interfaces. + 4. If any of the controllers is deactivated, also all preceding controllers are deactivated. + + +Implementation +-------------- + +A Controller Base-Class: ChainableController +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +A ``ChainableController`` extends ``ControllerInterface`` class with ``virtual InterfaceConfiguration input_interface_configuration() const = 0`` method. +This method should implement for each controller that **can be preceded** by another controller exporting all the input interfaces. +For simplicity reasons, it is assumed for now that controller's all input interfaces are used. +Therefore, do not try to implement any exclusive combinations of input interfaces, but rather write multiple controllers if you need exclusivity. + +The ``ChainableController`` base class implements ``void set_chained_mode(bool activate)`` that sets an internal flag that a controller is used by another controller (in chained mode) and calls ``virtual void on_set_chained_mode(bool activate) = 0`` that implements controller's specific actions when chained modes is activated or deactivated, e.g., deactivating subscribers. + +As an example, PID controllers export one virtual interface ``pid_reference`` and stop their subscriber ``/pid_reference`` when used in chained mode. 'diff_drive_controller' controller exports list of virtual interfaces ``/v_x``, ``/v_y``, and ``/w_z``, and stops subscribers from topics ``/cmd_vel`` and ``/cmd_vel_unstamped``. Its publishers can continue running. + +Inner Resource Management +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +After configuring a chainable controller, controller manager calls ``input_interface_configuration`` method and takes ownership over controller's input interfaces. +This is the same process as done by ``ResourceManager`` and hardware interfaces. +Controller manager maintains "claimed" status of interface in a vector (the same as done in ``ResourceManager``). + +Activation and Deactivation Chained Controllers +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Controller Manager has an additional parameter that describes how controllers are chained. +In the first version, the parameter-structure would have some semantic meaning embedded into it, as follows: + + +.. code-block:: yaml + + controller_manager: + ros__parameters: + chained_controllers: + + - parallel_group_1: + - controller1_1 + - controller1_2 + + - parallel_group_2: + - controller2_1 + + - parallel_group_3: + - controller3_1 + - controller3_2 + - controller3_3 + + ... + + - parallel_group_N: + - controllerN_1 + - ... + - controllerN_M + + + +This structure is motivated by ``filter_chain`` structure from `ros/filters repository `__, see `this file for implementation `__. + +This structure is stored internally by controller manager into an ordered map (``std::map>``) with group name as key. +When a controller should be deactivated, the controller manager deactivates all the controllers in the preceding groups first. +All other controllers from the group stay active, as well as all controllers in the following groups. +NOTE: In the future this could be done more intelligently, i.e., deactivate only controllers in the preceding groups that actually precede the controller that should be deactivated. + +On the other hand, the controller should be manually activated in the reverse order, i.e., from the those closer to the hardware toward those preceding them. + + +Debugging outputs +---------------------------- + +Flag ``unavailable`` on reference interface does not provide much information about anything at the moment. So don't get confused by it. The reason we have it are internal implementation reasons irelevant for the usage. + + +Closing remarks +---------------------------- + +- Maybe addition of the new controller's type ``ChainableController`` is not necessary. It would also be feasible to add implementation of ``input_interface_configuration()`` method into ``ControllerInterface`` class with default result ``interface_configuration_type::NONE``. diff --git a/controller_manager/doc/images/chaining_example2.png b/controller_manager/doc/images/chaining_example2.png new file mode 100644 index 0000000000..1ba49a116e Binary files /dev/null and b/controller_manager/doc/images/chaining_example2.png differ diff --git a/controller_manager/doc/userdoc.rst b/controller_manager/doc/userdoc.rst index de42850b6b..a05f6a3afc 100644 --- a/controller_manager/doc/userdoc.rst +++ b/controller_manager/doc/userdoc.rst @@ -39,21 +39,27 @@ The limits will be applied after you log out and in again. Parameters ----------- -activate_components_on_start (optional; list; default: empty) - Define which hardware components should be activated when controller manager is started. +hardware_components_initial_state + Map of parameters for controlled lifecycle management of hardware components. The names of the components are defined as attribute of ````-tag in ``robot_description``. - All other components will stay ``UNCONFIGURED``. - If this and ``configure_components_on_start`` are empty, all available components will be activated. - If this or ``configure_components_on_start`` are not empty, any component not in either list will be in unconfigured state. + Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated. + Detailed explanation of each parameter is given below. + The full structure of the map is given in the following example: +.. code-block:: yaml -configure_components_on_start (optional; list; default: empty) - Define which hardware components should be configured when controller manager is started. - The names of the components are defined as attribute of ````-tag in ``robot_description``. - All other components will stay ``UNCONFIGURED``. - If this and ``activate_components_on_start`` are empty, all available components will be activated. - If this or ``activate_components_on_start`` are not empty, any component not in either list will be in unconfigured state. + hardware_components_initial_state: + unconfigured: + - "arm1" + - "arm2" + inactive: + - "base3" + +hardware_components_initial_state.unconfigured (optional; list; default: empty) + Defines which hardware components will be only loaded immediately when controller manager is started. +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. diff --git a/controller_manager/include/controller_manager/controller_manager.hpp b/controller_manager/include/controller_manager/controller_manager.hpp index e09f3f2f3d..d5b32cf9f1 100644 --- a/controller_manager/include/controller_manager/controller_manager.hpp +++ b/controller_manager/include/controller_manager/controller_manager.hpp @@ -52,6 +52,8 @@ #include "rclcpp/node_interfaces/node_logging_interface.hpp" #include "rclcpp/node_interfaces/node_parameters_interface.hpp" #include "rclcpp/parameter.hpp" +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" namespace controller_manager { @@ -83,6 +85,9 @@ class ControllerManager : public rclcpp::Node CONTROLLER_MANAGER_PUBLIC virtual ~ControllerManager() = default; + CONTROLLER_MANAGER_PUBLIC + void robot_description_callback(const std_msgs::msg::String & msg); + CONTROLLER_MANAGER_PUBLIC void init_resource_manager(const std::string & robot_description); @@ -326,10 +331,11 @@ class ControllerManager : public rclcpp::Node std::vector get_controller_names(); std::pair split_command_interface( const std::string & command_interface); + void subscribe_to_robot_description_topic(); /** - * Clear request lists used when switching controllers. The lists are shared between "callback" and - * "control loop" threads. + * Clear request lists used when switching controllers. The lists are shared between "callback" + * and "control loop" threads. */ void clear_requests(); @@ -393,6 +399,29 @@ class ControllerManager : public rclcpp::Node const std::vector & controllers, int strictness, const ControllersListIterator controller_it); + /// A method to be used in the std::sort method to sort the controllers to be able to + /// execute them in a proper order + /** + * Compares the controllers ctrl_a and ctrl_b and then returns which comes first in the sequence + * + * @note The following conditions needs to be handled while ordering the controller list + * 1. The controllers that do not use any state or command interfaces are updated first + * 2. The controllers that use only the state system interfaces only are updated next + * 3. The controllers that use any of an another controller's reference interface are updated + * before the preceding controller + * 4. The controllers that use the controller's estimated interfaces are updated after the + * preceding controller + * 5. The controllers that only use the hardware command interfaces are updated last + * 6. All inactive controllers go at the end of the list + * + * \param[in] controllers list of controllers to compare their names to interface's prefix. + * + * @return true, if ctrl_a needs to execute first, else false + */ + bool controller_sorting( + const ControllerSpec & ctrl_a, const ControllerSpec & ctrl_b, + const std::vector & controllers); + void controller_activity_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat); diagnostic_updater::Updater diagnostics_updater_; @@ -438,7 +467,8 @@ class ControllerManager : public rclcpp::Node * lists match and returns a reference to it * This referenced list can be modified safely until switch_updated_controller_list() * is called, at this point the RT thread may start using it at any time - * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list + * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by + * rt list */ std::vector & get_unused_list( const std::lock_guard & guard); @@ -446,7 +476,8 @@ class ControllerManager : public rclcpp::Node /// get_updated_list Returns a const reference to the most updated list. /** * \warning May or may not being used by the realtime thread, read-only reference for safety - * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list + * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by + * rt list */ const std::vector & get_updated_list( const std::lock_guard & guard) const; @@ -454,7 +485,8 @@ class ControllerManager : public rclcpp::Node /** * switch_updated_list Switches the "updated" and "outdated" lists, and waits * until the RT thread is using the new "updated" list. - * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by rt list + * \param[in] guard Guard needed to make sure the caller is the only one accessing the unused by + * rt list */ void switch_updated_list(const std::lock_guard & guard); @@ -511,6 +543,8 @@ class ControllerManager : public rclcpp::Node std::vector activate_command_interface_request_, deactivate_command_interface_request_; + rclcpp::Subscription::SharedPtr robot_description_subscription_; + struct SwitchParams { bool do_switch = {false}; diff --git a/controller_manager/package.xml b/controller_manager/package.xml index 246bf5f9d4..adb6769d9c 100644 --- a/controller_manager/package.xml +++ b/controller_manager/package.xml @@ -2,7 +2,7 @@ controller_manager - 3.13.0 + 3.18.0 Description of controller_manager Bence Magyar Denis Štogl @@ -26,6 +26,7 @@ ros2_control_test_assets ros2param ros2run + std_msgs ament_cmake_gmock ros2_control_test_assets diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index 95594077fd..31a53aebb7 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -118,6 +118,123 @@ bool command_interface_is_reference_interface_of_controller( return true; } +/** + * A method to retrieve the names of all it's following controllers given a controller name + * For instance, for the following case + * A -> B -> C -> D + * When called with B, returns C and D + * 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 + * + * @param controller_name - Name of the controller for checking the tree + * \param[in] controllers list of controllers to compare their names to interface's prefix. + * @return list of controllers that are following the given controller in a chain. If none, return + * empty. + */ +std::vector get_following_controller_names( + const std::string controller_name, + const std::vector & controllers) +{ + std::vector following_controllers; + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, controller_name)); + if (controller_it == controllers.end()) + { + RCLCPP_DEBUG( + rclcpp::get_logger("ControllerManager::utils"), + "Required controller : '%s' is not found in the controller list ", controller_name.c_str()); + + return following_controllers; + } + // If the controller is not configured, return empty + if (!(is_controller_active(controller_it->c) || is_controller_inactive(controller_it->c))) + return following_controllers; + const auto cmd_itfs = controller_it->c->command_interface_configuration().names; + for (const auto & itf : cmd_itfs) + { + controller_manager::ControllersListIterator ctrl_it; + if (command_interface_is_reference_interface_of_controller(itf, controllers, ctrl_it)) + { + RCLCPP_DEBUG( + rclcpp::get_logger("ControllerManager::utils"), + "The interface is a reference interface of controller : %s", ctrl_it->info.name.c_str()); + following_controllers.push_back(ctrl_it->info.name); + const std::vector ctrl_names = + get_following_controller_names(ctrl_it->info.name, controllers); + for (const std::string & controller : ctrl_names) + { + if ( + std::find(following_controllers.begin(), following_controllers.end(), controller) == + following_controllers.end()) + { + // Only add to the list if it doesn't exist + following_controllers.push_back(controller); + } + } + } + } + return following_controllers; +} + +/** + * A method to retrieve the names of all it's preceding controllers given a controller name + * For instance, for the following case + * A -> B -> C -> D + * When called with C, returns A and B + * 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 + * + * @param controller_name - Name of the controller for checking the tree + * \param[in] controllers list of controllers to compare their names to interface's prefix. + * @return list of controllers that are preceding the given controller in a chain. If none, return + * empty. + */ +std::vector get_preceding_controller_names( + const std::string controller_name, + const std::vector & controllers) +{ + std::vector preceding_controllers; + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, controller_name)); + if (controller_it == controllers.end()) + { + RCLCPP_DEBUG( + rclcpp::get_logger("ControllerManager::utils"), + "Required controller : '%s' is not found in the controller list ", controller_name.c_str()); + return preceding_controllers; + } + for (const auto & ctrl : controllers) + { + // If the controller is not configured, return empty + if (!(is_controller_active(ctrl.c) || is_controller_inactive(ctrl.c))) + return preceding_controllers; + auto cmd_itfs = ctrl.c->command_interface_configuration().names; + for (const auto & itf : cmd_itfs) + { + if (itf.find(controller_name) != std::string::npos) + { + preceding_controllers.push_back(ctrl.info.name); + auto ctrl_names = get_preceding_controller_names(ctrl.info.name, controllers); + for (const std::string & controller : ctrl_names) + { + if ( + std::find(preceding_controllers.begin(), preceding_controllers.end(), controller) == + preceding_controllers.end()) + { + // Only add to the list if it doesn't exist + preceding_controllers.push_back(controller); + } + } + } + } + } + return preceding_controllers; +} + } // namespace namespace controller_manager @@ -151,13 +268,20 @@ ControllerManager::ControllerManager( } std::string robot_description = ""; + // TODO(destogl): remove support at the end of 2023 get_parameter("robot_description", robot_description); if (robot_description.empty()) { - throw std::runtime_error("Unable to initialize resource manager, no robot description found."); + subscribe_to_robot_description_topic(); + } + else + { + 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."); + init_resource_manager(robot_description); } - - init_resource_manager(robot_description); diagnostics_updater_.setHardwareID("ros2_control"); diagnostics_updater_.add( @@ -183,41 +307,140 @@ ControllerManager::ControllerManager( { RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value."); } + + subscribe_to_robot_description_topic(); + diagnostics_updater_.setHardwareID("ros2_control"); diagnostics_updater_.add( "Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback); init_services(); } +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(), + std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1)); + RCLCPP_INFO( + get_logger(), "Subscribing to '%s' topic for robot description.", + robot_description_subscription_->get_topic_name()); +} + +void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description) +{ + 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 + // to die if a non valid urdf is passed. However, should maybe be fine tuned. + try + { + if (resource_manager_->is_urdf_already_loaded()) + { + RCLCPP_WARN( + get_logger(), + "ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot " + "description file."); + return; + } + init_resource_manager(robot_description.data.c_str()); + } + catch (std::runtime_error & e) + { + RCLCPP_ERROR_STREAM( + get_logger(), + "The published robot description file (urdf) seems not to be genuine. The following error " + "was caught:" + << e.what()); + } +} + void ControllerManager::init_resource_manager(const std::string & robot_description) { // TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong... resource_manager_->load_urdf(robot_description); + // Get all components and if they are not defined in parameters activate them automatically + auto components_to_activate = resource_manager_->get_components_status(); + using lifecycle_msgs::msg::State; - std::vector configure_components_on_start = std::vector({}); - if (get_parameter("configure_components_on_start", configure_components_on_start)) + auto set_components_to_state = + [&](const std::string & parameter_name, rclcpp_lifecycle::State state) { - RCLCPP_WARN_STREAM( - get_logger(), - "[Deprecated]: Usage of parameter \"configure_components_on_start\" is deprecated. Use " - "hardware_spawner instead."); - rclcpp_lifecycle::State inactive_state( - State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE); - for (const auto & component : configure_components_on_start) + std::vector components_to_set = std::vector({}); + if (get_parameter(parameter_name, components_to_set)) { - resource_manager_->set_component_state(component, inactive_state); + for (const auto & component : components_to_set) + { + if (component.empty()) + { + continue; + } + if (components_to_activate.find(component) == components_to_activate.end()) + { + RCLCPP_WARN( + get_logger(), "Hardware component '%s' is unknown, therefore not set in '%s' state.", + component.c_str(), state.label().c_str()); + } + else + { + RCLCPP_INFO( + get_logger(), "Setting component '%s' to '%s' state.", component.c_str(), + state.label().c_str()); + resource_manager_->set_component_state(component, state); + components_to_activate.erase(component); + } + } } + }; + + // unconfigured (loaded only) + set_components_to_state( + "hardware_components_initial_state.unconfigured", + rclcpp_lifecycle::State( + State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED)); + + // inactive (configured) + // BEGIN: Keep old functionality on for backwards compatibility (Remove at the end of 2023) + std::vector configure_components_on_start = std::vector({}); + get_parameter("configure_components_on_start", configure_components_on_start); + if (!configure_components_on_start.empty()) + { + RCLCPP_WARN( + get_logger(), + "Parameter 'configure_components_on_start' is deprecated. " + "Use 'hardware_components_initial_state.inactive' instead, to set component's initial " + "state to 'inactive'. Don't use this parameters in combination with the new " + "'hardware_components_initial_state' parameter structure."); + set_components_to_state( + "configure_components_on_start", + rclcpp_lifecycle::State( + State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE)); + } + // END: Keep old functionality on humble backwards compatibility (Remove at the end of 2023) + else + { + set_components_to_state( + "hardware_components_initial_state.inactive", + rclcpp_lifecycle::State( + State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE)); } + // BEGIN: Keep old functionality on for backwards compatibility (Remove at the end of 2023) std::vector activate_components_on_start = std::vector({}); - if (get_parameter("activate_components_on_start", activate_components_on_start)) + get_parameter("activate_components_on_start", activate_components_on_start); + rclcpp_lifecycle::State active_state( + State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); + if (!activate_components_on_start.empty()) { - RCLCPP_WARN_STREAM( + RCLCPP_WARN( get_logger(), - "[Deprecated]: Usage of parameter \"activate_components_on_start\" is deprecated. Use " - "hardware_spawner instead."); + "Parameter 'activate_components_on_start' is deprecated. " + "Components are activated per default. Don't use this parameters in combination with the new " + "'hardware_components_initial_state' parameter structure."); rclcpp_lifecycle::State active_state( State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); for (const auto & component : activate_components_on_start) @@ -225,15 +448,16 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript resource_manager_->set_component_state(component, active_state); } } - // if both parameter are empty or non-existing preserve behavior where all components are - // activated per default - if (configure_components_on_start.empty() && activate_components_on_start.empty()) + // END: Keep old functionality on humble for backwards compatibility (Remove at the end of 2023) + else { - RCLCPP_WARN_STREAM( - get_logger(), - "[Deprecated]: Automatic activation of all hardware components will not be supported in the " - "future anymore. Use hardware_spawner instead."); - resource_manager_->activate_all_components(); + // activate all other components + for (const auto & [component, state] : components_to_activate) + { + rclcpp_lifecycle::State active_state( + State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); + resource_manager_->set_component_state(component, active_state); + } } } @@ -504,6 +728,31 @@ controller_interface::return_type ControllerManager::configure_controller( std::make_unique(controller, update_rate_)); } + const auto controller_update_rate = controller->get_update_rate(); + const auto cm_update_rate = get_update_rate(); + if (controller_update_rate > cm_update_rate) + { + RCLCPP_WARN( + get_logger(), + "The controller : %s update rate : %d Hz should be less than or equal to controller " + "manager's update rate : %d Hz!. The controller will be updated at controller_manager's " + "update rate.", + controller_name.c_str(), controller_update_rate, cm_update_rate); + } + else if (controller_update_rate != 0 && cm_update_rate % controller_update_rate != 0) + { + // NOTE: The following computation is done to compute the approx controller update that can be + // achieved w.r.t to the CM's update rate. This is done this way to take into account the + // unsigned integer division. + const auto act_ctrl_update_rate = cm_update_rate / (cm_update_rate / controller_update_rate); + RCLCPP_WARN( + get_logger(), + "The controller : %s update rate : %d Hz is not a perfect divisor of the controller " + "manager's update rate : %d Hz!. The controller will be updated with nearest divisor's " + "update rate which is : %d Hz.", + controller_name.c_str(), controller_update_rate, cm_update_rate, act_ctrl_update_rate); + } + // CHAINABLE CONTROLLERS: get reference interfaces from chainable controllers if (controller->is_chainable()) { @@ -985,6 +1234,20 @@ controller_interface::return_type ControllerManager::switch_controller( controller.info.claimed_interfaces.clear(); } } + + // Reordering the controllers + std::sort( + to.begin(), to.end(), + std::bind( + &ControllerManager::controller_sorting, this, std::placeholders::_1, std::placeholders::_2, + to)); + + RCLCPP_DEBUG(get_logger(), "Reordered controllers list is:"); + for (const auto & ctrl : to) + { + RCLCPP_DEBUG(this->get_logger(), "\t%s", ctrl.info.name.c_str()); + } + // switch lists rt_controllers_wrapper_.switch_updated_list(guard); // clear unused list @@ -1281,8 +1544,11 @@ void ControllerManager::activate_controllers( if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { RCLCPP_ERROR( - get_logger(), "After activating, controller '%s' is in state '%s', expected Active", - controller->get_node()->get_name(), new_state.label().c_str()); + get_logger(), + "After activation, controller '%s' is in state '%s' (%d), expected '%s' (%d).", + controller->get_node()->get_name(), new_state.label().c_str(), new_state.id(), + hardware_interface::lifecycle_state_names::ACTIVE, + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE); } if (controller->is_async()) @@ -1766,9 +2032,12 @@ controller_interface::return_type ControllerManager::update( if (!loaded_controller.c->is_async() && is_controller_active(*loaded_controller.c)) { const auto controller_update_rate = loaded_controller.c->get_update_rate(); + const auto controller_update_factor = + (controller_update_rate == 0) || (controller_update_rate >= update_rate_) + ? 1u + : update_rate_ / controller_update_rate; - bool controller_go = - controller_update_rate == 0 || ((update_loop_counter_ % controller_update_rate) == 0); + bool controller_go = ((update_loop_counter_ % controller_update_factor) == 0); RCLCPP_DEBUG( get_logger(), "update_loop_counter: '%d ' controller_go: '%s ' controller_name: '%s '", update_loop_counter_, controller_go ? "True" : "False", @@ -1777,7 +2046,7 @@ controller_interface::return_type ControllerManager::update( if (controller_go) { auto controller_ret = loaded_controller.c->update( - time, (controller_update_rate != update_rate_ && controller_update_rate != 0) + time, (controller_update_factor != 1u) ? rclcpp::Duration::from_seconds(1.0 / controller_update_rate) : period); @@ -2150,6 +2419,99 @@ controller_interface::return_type ControllerManager::check_preceeding_controller } } return controller_interface::return_type::OK; +} + +bool ControllerManager::controller_sorting( + const ControllerSpec & ctrl_a, const ControllerSpec & ctrl_b, + const std::vector & controllers) +{ + // If the controllers are not active, then should be at the end of the list + if (!is_controller_active(ctrl_a.c) || !is_controller_active(ctrl_b.c)) + { + if (is_controller_active(ctrl_a.c)) return true; + return false; + } + + const std::vector cmd_itfs = ctrl_a.c->command_interface_configuration().names; + const std::vector state_itfs = ctrl_a.c->state_interface_configuration().names; + if (cmd_itfs.empty() || !ctrl_a.c->is_chainable()) + { + // The case of the controllers that don't have any command interfaces. For instance, + // joint_state_broadcaster + return true; + } + else + { + auto following_ctrls = get_following_controller_names(ctrl_a.info.name, controllers); + if (following_ctrls.empty()) return false; + // If the ctrl_b is any of the following controllers of ctrl_a, then place ctrl_a before ctrl_b + if ( + std::find(following_ctrls.begin(), following_ctrls.end(), ctrl_b.info.name) != + following_ctrls.end()) + return true; + else + { + auto ctrl_a_preceding_ctrls = get_preceding_controller_names(ctrl_a.info.name, controllers); + // This is to check that the ctrl_b is in the preceding controllers list of ctrl_a - This + // check is useful when there is a chained controller branching, but they belong to same + // branch + if ( + std::find(ctrl_a_preceding_ctrls.begin(), ctrl_a_preceding_ctrls.end(), ctrl_b.info.name) != + ctrl_a_preceding_ctrls.end()) + { + return false; + } + + // This is to handle the cases where, the parsed ctrl_a and ctrl_b are not directly related + // but might have a common parent - happens in branched chained controller + auto ctrl_b_preceding_ctrls = get_preceding_controller_names(ctrl_b.info.name, controllers); + std::sort(ctrl_a_preceding_ctrls.begin(), ctrl_a_preceding_ctrls.end()); + std::sort(ctrl_b_preceding_ctrls.begin(), ctrl_b_preceding_ctrls.end()); + std::list intersection; + std::set_intersection( + ctrl_a_preceding_ctrls.begin(), ctrl_a_preceding_ctrls.end(), + ctrl_b_preceding_ctrls.begin(), ctrl_b_preceding_ctrls.end(), + std::back_inserter(intersection)); + if (!intersection.empty()) + { + // If there is an intersection, then there is a common parent controller for both ctrl_a and + // ctrl_b + return true; + } + + // If there is no common parent, then they belong to 2 different sets + auto following_ctrls_b = get_following_controller_names(ctrl_b.info.name, controllers); + if (following_ctrls_b.empty()) return true; + auto find_first_element = [&](const auto & controllers_list) + { + auto it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, controllers_list.back())); + if (it != controllers.end()) + { + int dist = std::distance(controllers.begin(), it); + return dist; + } + }; + const int ctrl_a_chain_first_controller = find_first_element(following_ctrls); + const int ctrl_b_chain_first_controller = find_first_element(following_ctrls_b); + if (ctrl_a_chain_first_controller < ctrl_b_chain_first_controller) return true; + } + + // If the ctrl_a's state interface is the one exported by the ctrl_b then ctrl_b should be + // infront of ctrl_a + // TODO(saikishor): deal with the state interface chaining in the sorting algorithm + auto state_it = std::find_if( + state_itfs.begin(), state_itfs.end(), + [ctrl_b](auto itf) { return (itf.find(ctrl_b.info.name) != std::string::npos); }); + if (state_it != state_itfs.end()) + { + return false; + } + + // The rest of the cases, basically end up at the end of the list + return false; + } }; void ControllerManager::controller_activity_diagnostic_callback( diff --git a/controller_manager/test/controller_manager_test_common.hpp b/controller_manager/test/controller_manager_test_common.hpp index b6e6acac0e..78c3fcb06b 100644 --- a/controller_manager/test/controller_manager_test_common.hpp +++ b/controller_manager/test/controller_manager_test_common.hpp @@ -22,15 +22,20 @@ #include #include #include +#include #include #include "controller_interface/controller_interface.hpp" #include "controller_manager/controller_manager.hpp" +#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp" #include "controller_manager_msgs/srv/switch_controller.hpp" +#include "rclcpp/rclcpp.hpp" #include "rclcpp/utilities.hpp" +#include "std_msgs/msg/string.hpp" + #include "ros2_control_test_assets/descriptions.hpp" #include "test_controller_failed_init/test_controller_failed_init.hpp" @@ -60,21 +65,51 @@ template class ControllerManagerFixture : public ::testing::Test { public: + explicit ControllerManagerFixture( + const std::string & robot_description = ros2_control_test_assets::minimal_robot_urdf, + const bool & pass_urdf_as_parameter = false) + : robot_description_(robot_description), pass_urdf_as_parameter_(pass_urdf_as_parameter) + { + executor_ = std::make_shared(); + // We want to be able to create a ResourceManager where no urdf file has been passed to + if (robot_description_.empty()) + { + cm_ = std::make_shared( + std::make_unique(), executor_, TEST_CM_NAME); + } + else + { + // can be removed later, needed if we want to have the deprecated way of passing the robot + // description file to the controller manager covered by tests + if (pass_urdf_as_parameter_) + { + cm_ = std::make_shared( + std::make_unique(robot_description_, true, true), + executor_, TEST_CM_NAME); + } + else + { + // TODO(Manuel) : 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 + cm_ = std::make_shared( + std::make_unique(), executor_, TEST_CM_NAME); + // mimic topic call + auto msg = std_msgs::msg::String(); + msg.data = robot_description_; + cm_->robot_description_callback(msg); + } + } + } + static void SetUpTestCase() { rclcpp::init(0, nullptr); } static void TearDownTestCase() { rclcpp::shutdown(); } - void SetUp() - { - executor_ = std::make_shared(); - cm_ = std::make_shared( - std::make_unique( - ros2_control_test_assets::minimal_robot_urdf, true, true), - executor_, TEST_CM_NAME); - run_updater_ = false; - } + void SetUp() override { run_updater_ = false; } - void TearDown() { stopCmUpdater(); } + void TearDown() override { stopCmUpdater(); } void startCmUpdater() { @@ -120,6 +155,8 @@ class ControllerManagerFixture : public ::testing::Test std::thread updater_; bool run_updater_; + const std::string robot_description_; + const bool pass_urdf_as_parameter_; }; class TestControllerManagerSrvs diff --git a/controller_manager/test/test_controller/test_controller.hpp b/controller_manager/test/test_controller/test_controller.hpp index 1b070ab302..f73f592037 100644 --- a/controller_manager/test/test_controller/test_controller.hpp +++ b/controller_manager/test/test_controller/test_controller.hpp @@ -65,7 +65,7 @@ class TestController : public controller_interface::ControllerInterface CONTROLLER_MANAGER_PUBLIC void set_state_interface_configuration(const controller_interface::InterfaceConfiguration & cfg); - size_t internal_counter = 0; + unsigned int internal_counter = 0; bool simulate_cleanup_failure = false; // Variable where we store when cleanup was called, pointer because the controller // is usually destroyed after cleanup diff --git a/controller_manager/test/test_controller_manager.cpp b/controller_manager/test/test_controller_manager.cpp index 22221b6e21..6db4cfd1b2 100644 --- a/controller_manager/test/test_controller_manager.cpp +++ b/controller_manager/test/test_controller_manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include #include #include #include @@ -27,13 +27,13 @@ using ::testing::_; using ::testing::Return; -class TestControllerManager +class TestControllerManagerWithStrictness : public ControllerManagerFixture, public testing::WithParamInterface { }; -TEST_P(TestControllerManager, controller_lifecycle) +TEST_P(TestControllerManagerWithStrictness, controller_lifecycle) { const auto test_param = GetParam(); auto test_controller = std::make_shared(); @@ -159,7 +159,7 @@ TEST_P(TestControllerManager, controller_lifecycle) controller_interface::return_type::OK, cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); EXPECT_GE(test_controller->internal_counter, 1u); - auto last_internal_counter = test_controller->internal_counter; + size_t last_internal_counter = test_controller->internal_counter; // Stop controller, will take effect at the end of the update function start_controllers = {}; @@ -196,7 +196,7 @@ TEST_P(TestControllerManager, controller_lifecycle) EXPECT_EQ(1, test_controller.use_count()); } -TEST_P(TestControllerManager, per_controller_update_rate) +TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate) { auto strictness = GetParam().strictness; auto test_controller = std::make_shared(); @@ -246,12 +246,204 @@ TEST_P(TestControllerManager, per_controller_update_rate) EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id()); + // As the controller frequency is 4Hz, it needs to pass 25 iterations for 1 update cycle + for (size_t i = 0; i < 25; i++) + { + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + } + EXPECT_GE(test_controller->internal_counter, 1u); + EXPECT_EQ(test_controller->get_update_rate(), 4u); +} + +INSTANTIATE_TEST_SUITE_P( + test_strict_best_effort, TestControllerManagerWithStrictness, + testing::Values(strict, best_effort)); + +class TestControllerManagerWithUpdateRates +: public ControllerManagerFixture, + public testing::WithParamInterface +{ +}; + +TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_update_rate) +{ + const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + const unsigned int ctrl_update_rate = GetParam(); + auto test_controller = std::make_shared(); + + auto last_internal_counter = 0u; + RCLCPP_INFO( + rclcpp::get_logger("test_controller_manager"), "Testing update rate : %u Hz", ctrl_update_rate); + { + ControllerManagerRunner cm_runner(this); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_controller::TEST_CONTROLLER_CLASS_NAME); + } + EXPECT_EQ(1u, cm_->get_loaded_controllers().size()); + EXPECT_EQ(2, test_controller.use_count()); EXPECT_EQ( controller_interface::return_type::OK, cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); - EXPECT_GE(test_controller->internal_counter, 1u); - EXPECT_EQ(test_controller->get_update_rate(), 4u); + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) + << "Update should not reach an unconfigured controller"; + + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); + + rclcpp::Parameter update_rate_parameter("update_rate", static_cast(ctrl_update_rate)); + test_controller->get_node()->set_parameter(update_rate_parameter); + // configure controller + cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) + << "Controller is not started"; + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id()); + + // Start controller, will take effect at the end of the update function + std::vector start_controllers = {test_controller::TEST_CONTROLLER_NAME}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0)); + + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(last_internal_counter, test_controller->internal_counter) + << "Controller is started at the end of update"; + { + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + } + + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id()); + + const auto pre_internal_counter = test_controller->internal_counter; + rclcpp::Rate loop_rate(cm_->get_update_rate()); + for (size_t i = 0; i < 2 * cm_->get_update_rate(); i++) + { + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + loop_rate.sleep(); + } + // if we do 2 times of the controller_manager update rate, the internal counter should be + // similarly incremented + EXPECT_EQ(test_controller->internal_counter, pre_internal_counter + (2 * cm_->get_update_rate())); + EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate); + + auto deactivate_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + stop_controllers, start_controllers, strictness, true, rclcpp::Duration(0, 0)); + + ASSERT_EQ(std::future_status::timeout, deactivate_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))) + << "Controller is stopped at the end of update, so it should have done one more update"; + { + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, deactivate_future.get()); + } + auto unload_future = std::async( + std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_, + test_controller::TEST_CONTROLLER_NAME); + ASSERT_EQ(std::future_status::timeout, unload_future.wait_for(std::chrono::milliseconds(100))) + << "unload_controller should be blocking until next update cycle"; + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, unload_future.get()); + last_internal_counter = test_controller->internal_counter; +} + +INSTANTIATE_TEST_SUITE_P( + per_controller_equal_and_higher_update_rate, TestControllerManagerWithUpdateRates, + testing::Values(100, 232, 400)); + +class TestControllerUpdateRates +: public ControllerManagerFixture, + public testing::WithParamInterface +{ +}; + +TEST_P(TestControllerUpdateRates, check_the_controller_update_rate) +{ + const unsigned int ctrl_update_rate = GetParam(); + auto test_controller = std::make_shared(); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_controller::TEST_CONTROLLER_CLASS_NAME); + EXPECT_EQ(1u, cm_->get_loaded_controllers().size()); + EXPECT_EQ(2, test_controller.use_count()); + + EXPECT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state().id()); + + test_controller->get_node()->set_parameter({"update_rate", static_cast(ctrl_update_rate)}); + // configure controller + cm_->configure_controller(test_controller::TEST_CONTROLLER_NAME); + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is not started"; + + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state().id()); + + // Start controller, will take effect at the end of the update function + const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT; + std::vector start_controllers = {test_controller::TEST_CONTROLLER_NAME}; + std::vector stop_controllers = {}; + auto switch_future = std::async( + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, + start_controllers, stop_controllers, strictness, true, rclcpp::Duration(0, 0)); + + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) + << "switch_controller should be blocking until next update cycle"; + + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + EXPECT_EQ(0u, test_controller->internal_counter) << "Controller is started at the end of update"; + { + ControllerManagerRunner cm_runner(this); + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); + } + + EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state().id()); + + EXPECT_EQ(test_controller->get_update_rate(), ctrl_update_rate); + const auto cm_update_rate = cm_->get_update_rate(); + const auto controller_update_rate = test_controller->get_update_rate(); + const auto controller_factor = (cm_update_rate / controller_update_rate); + const auto expected_controller_update_rate = + static_cast(std::round(cm_update_rate / static_cast(controller_factor))); + + const auto initial_counter = test_controller->internal_counter; + for (size_t update_counter = 1; update_counter <= 10 * cm_update_rate; ++update_counter) + { + EXPECT_EQ( + controller_interface::return_type::OK, + cm_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01))); + + if (update_counter % cm_update_rate == 0) + { + const auto no_of_secs_passed = update_counter / cm_update_rate; + EXPECT_EQ( + test_controller->internal_counter - initial_counter, + (expected_controller_update_rate * no_of_secs_passed)); + } + } } INSTANTIATE_TEST_SUITE_P( - test_strict_best_effort, TestControllerManager, testing::Values(strict, best_effort)); + per_controller_update_rate_check, TestControllerUpdateRates, + testing::Values(10, 12, 16, 23, 37, 40, 50, 63, 71, 85, 98)); diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index adb227d6fe..583480d494 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -289,19 +289,19 @@ TEST_F(TestControllerManagerSrvs, list_chained_controllers_srv) controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); // get controller list after activate result = call_service_and_wait(*client, request, srv_executor); - // check chainable controller - ASSERT_EQ(result->controller[0].state, "active"); - ASSERT_EQ(result->controller[0].claimed_interfaces.size(), 1u); - ASSERT_EQ(result->controller[0].is_chained, true); // check test controller + ASSERT_EQ(result->controller[0].state, "active"); + ASSERT_EQ(result->controller[0].claimed_interfaces.size(), 3u); + // check chainable controller ASSERT_EQ(result->controller[1].state, "active"); - ASSERT_EQ(result->controller[1].claimed_interfaces.size(), 3u); + ASSERT_EQ(result->controller[1].claimed_interfaces.size(), 1u); + ASSERT_EQ(result->controller[1].is_chained, true); ASSERT_EQ( test_chainable_controller::TEST_CONTROLLER_NAME, - result->controller[1].chain_connections[0].name); - ASSERT_EQ(2u, result->controller[1].chain_connections[0].reference_interfaces.size()); - ASSERT_EQ("joint1/position", result->controller[1].chain_connections[0].reference_interfaces[0]); - ASSERT_EQ("joint1/velocity", result->controller[1].chain_connections[0].reference_interfaces[1]); + result->controller[0].chain_connections[0].name); + ASSERT_EQ(2u, result->controller[0].chain_connections[0].reference_interfaces.size()); + ASSERT_EQ("joint1/position", result->controller[0].chain_connections[0].reference_interfaces[0]); + ASSERT_EQ("joint1/velocity", result->controller[0].chain_connections[0].reference_interfaces[1]); } TEST_F(TestControllerManagerSrvs, reload_controller_libraries_srv) @@ -480,3 +480,586 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv) lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, cm_->get_loaded_controllers()[0].c->get_state().id()); } + +TEST_F(TestControllerManagerSrvs, list_sorted_chained_controllers) +{ + /// The simulated controller chaining is: + /// test_controller_name -> chain_ctrl_5 -> chain_ctrl_4 -> chain_ctrl_3 -> 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"; + static constexpr char TEST_CHAINED_CONTROLLER_3[] = "test_chainable_controller_name_3"; + static constexpr char TEST_CHAINED_CONTROLLER_4[] = "test_chainable_controller_name_4"; + static constexpr char TEST_CHAINED_CONTROLLER_5[] = "test_chainable_controller_name_5"; + 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"}); + + auto test_chained_controller_3 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/position"}}; + test_chained_controller_3->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_3->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_3->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + auto test_chained_controller_4 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_3) + "/joint1/position"}}; + test_chained_controller_4->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_4->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_4->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + auto test_chained_controller_5 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_4) + "/joint1/position"}}; + test_chained_controller_5->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_5->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_5->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_5) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_5) + "/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_4, TEST_CHAINED_CONTROLLER_4, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller, test_controller::TEST_CONTROLLER_NAME, + test_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(6u, result->controller.size()); + ASSERT_EQ(result->controller[0].name, TEST_CHAINED_CONTROLLER_4); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_1); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_3); + ASSERT_EQ(result->controller[3].name, TEST_CHAINED_CONTROLLER_5); + ASSERT_EQ(result->controller[4].name, TEST_CHAINED_CONTROLLER_2); + // check test controller + ASSERT_EQ(result->controller[5].name, "test_controller_name"); + + // configure controllers + for (const auto & controller : + {TEST_CHAINED_CONTROLLER_4, TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, + TEST_CHAINED_CONTROLLER_2, TEST_CHAINED_CONTROLLER_1, + test_controller::TEST_CONTROLLER_NAME}) + cm_->configure_controller(controller); + + // get controller list after configure + result = call_service_and_wait(*client, request, srv_executor); + ASSERT_EQ(6u, result->controller.size()); + + // activate controllers + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_1}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2, + TEST_CHAINED_CONTROLLER_4}, + {}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true, + rclcpp::Duration(0, 0)); + cm_->switch_controller( + {test_controller::TEST_CONTROLLER_NAME}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + // get controller list after activate + result = call_service_and_wait(*client, request, srv_executor); + + ASSERT_EQ(6u, result->controller.size()); + // reordered controllers + ASSERT_EQ(result->controller[0].name, "test_controller_name"); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_5); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_4); + ASSERT_EQ(result->controller[3].name, TEST_CHAINED_CONTROLLER_3); + ASSERT_EQ(result->controller[4].name, TEST_CHAINED_CONTROLLER_2); + ASSERT_EQ(result->controller[5].name, TEST_CHAINED_CONTROLLER_1); + RCLCPP_ERROR(srv_node->get_logger(), "Check successful!"); +} + +TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers) +{ + /// The simulated controller chain branching is: + /// test_controller_name -> chain_ctrl_7 -> chain_ctrl_6 -> chain_ctrl_2 -> chain_ctrl_1 + /// & + /// chain_ctrl_6 -> chain_ctrl_5 -> chain_ctrl_4 -> chain_ctrl_3 + /// + /// 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"; + static constexpr char TEST_CHAINED_CONTROLLER_3[] = "test_chainable_controller_name_3"; + static constexpr char TEST_CHAINED_CONTROLLER_4[] = "test_chainable_controller_name_4"; + static constexpr char TEST_CHAINED_CONTROLLER_5[] = "test_chainable_controller_name_5"; + static constexpr char TEST_CHAINED_CONTROLLER_6[] = "test_chainable_controller_name_6"; + static constexpr char TEST_CHAINED_CONTROLLER_7[] = "test_chainable_controller_name_7"; + 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", "joint2/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"}); + + auto test_chained_controller_3 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint2/velocity"}}; + test_chained_controller_3->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_3->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_3->set_reference_interface_names({"joint2/velocity"}); + + auto test_chained_controller_4 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_3) + "/joint2/velocity"}}; + test_chained_controller_4->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_4->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_4->set_reference_interface_names({"joint2/velocity"}); + + auto test_chained_controller_5 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_4) + "/joint2/velocity"}}; + test_chained_controller_5->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_5->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_5->set_reference_interface_names({"joint2/velocity"}); + + auto test_chained_controller_6 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_5) + "/joint2/velocity"}}; + test_chained_controller_6->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_6->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_6->set_reference_interface_names({"joint1/position", "joint2/velocity"}); + + auto test_chained_controller_7 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_6) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_6) + "/joint2/velocity"}}; + test_chained_controller_7->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_7->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_7->set_reference_interface_names({"joint1/position", "joint2/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_7) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_7) + "/joint2/velocity"}}; + controller_interface::InterfaceConfiguration state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint2/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_4, TEST_CHAINED_CONTROLLER_4, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + 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_7, TEST_CHAINED_CONTROLLER_7, + 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(8u, result->controller.size()); + ASSERT_EQ(result->controller[0].name, TEST_CHAINED_CONTROLLER_4); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_1); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_3); + ASSERT_EQ(result->controller[3].name, TEST_CHAINED_CONTROLLER_5); + ASSERT_EQ(result->controller[4].name, TEST_CHAINED_CONTROLLER_6); + ASSERT_EQ(result->controller[5].name, TEST_CHAINED_CONTROLLER_2); + // check test controller + ASSERT_EQ(result->controller[6].name, "test_controller_name"); + ASSERT_EQ(result->controller[7].name, TEST_CHAINED_CONTROLLER_7); + + // configure controllers + for (const auto & controller : + {TEST_CHAINED_CONTROLLER_4, TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, + TEST_CHAINED_CONTROLLER_7, TEST_CHAINED_CONTROLLER_2, TEST_CHAINED_CONTROLLER_1, + TEST_CHAINED_CONTROLLER_6, test_controller::TEST_CONTROLLER_NAME}) + cm_->configure_controller(controller); + + // get controller list after configure + result = call_service_and_wait(*client, request, srv_executor); + ASSERT_EQ(8u, result->controller.size()); + + // activate controllers + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_1}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_3}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_6, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2, + TEST_CHAINED_CONTROLLER_4, TEST_CHAINED_CONTROLLER_7}, + {}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true, + rclcpp::Duration(0, 0)); + cm_->switch_controller( + {test_controller::TEST_CONTROLLER_NAME}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + // get controller list after activate + result = call_service_and_wait(*client, request, srv_executor); + + ASSERT_EQ(8u, result->controller.size()); + // reordered controllers + ASSERT_EQ(result->controller[0].name, "test_controller_name"); + ASSERT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_7); + ASSERT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_6); + + auto get_ctrl_pos = [result](const std::string & controller_name) -> int + { + auto it = std::find_if( + result->controller.begin(), result->controller.end(), + [controller_name](auto itf) + { return (itf.name.find(controller_name) != std::string::npos); }); + return std::distance(result->controller.begin(), it); + }; + auto ctrl_1_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_1); + auto ctrl_2_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_2); + auto ctrl_3_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_3); + auto ctrl_4_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_4); + auto ctrl_5_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_5); + auto ctrl_6_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_6); + + // Extra check to see that they are index only after their parent controller (ctrl_6) + ASSERT_GT(ctrl_3_pos, ctrl_6_pos); + ASSERT_GT(ctrl_1_pos, ctrl_6_pos); + + // first branch + ASSERT_GT(ctrl_2_pos, ctrl_6_pos); + ASSERT_GT(ctrl_1_pos, ctrl_2_pos); + + // second branch + ASSERT_GT(ctrl_5_pos, ctrl_6_pos); + ASSERT_GT(ctrl_4_pos, ctrl_5_pos); + ASSERT_GT(ctrl_3_pos, ctrl_4_pos); +} + +TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers) +{ + /// The simulated controller chaining is: + /// test_controller_name_1 -> chain_ctrl_3 -> chain_ctrl_2 -> chain_ctrl_1 + /// && + /// test_controller_name_2 -> chain_ctrl_6 -> chain_ctrl_5 -> chain_ctrl_4 + /// && + /// test_controller_name_7 -> test_controller_name_8 + /// + /// 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"; + static constexpr char TEST_CHAINED_CONTROLLER_3[] = "test_chainable_controller_name_3"; + static constexpr char TEST_CHAINED_CONTROLLER_4[] = "test_chainable_controller_name_4"; + static constexpr char TEST_CHAINED_CONTROLLER_5[] = "test_chainable_controller_name_5"; + static constexpr char TEST_CHAINED_CONTROLLER_6[] = "test_chainable_controller_name_6"; + static constexpr char TEST_CHAINED_CONTROLLER_7[] = "test_chainable_controller_name_7"; + static constexpr char TEST_CHAINED_CONTROLLER_8[] = "test_chainable_controller_name_8"; + static constexpr char TEST_CONTROLLER_1[] = "test_controller_name_1"; + static constexpr char TEST_CONTROLLER_2[] = "test_controller_name_2"; + + // First chain + 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"}); + + auto test_chained_controller_3 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_2) + "/joint1/position"}}; + test_chained_controller_3->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_3->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_3->set_reference_interface_names({"joint1/position", "joint1/velocity"}); + + auto test_controller_1 = std::make_shared(); + controller_interface::InterfaceConfiguration cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_3) + "/joint1/position", + std::string(TEST_CHAINED_CONTROLLER_3) + "/joint1/velocity"}}; + controller_interface::InterfaceConfiguration state_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {"joint1/position", "joint1/velocity"}}; + test_controller_1->set_command_interface_configuration(cmd_cfg); + test_controller_1->set_state_interface_configuration(state_cfg); + + // Second chain + auto test_chained_controller_4 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint2/velocity"}}; + test_chained_controller_4->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_4->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_4->set_reference_interface_names({"joint2/velocity"}); + + auto test_chained_controller_5 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_4) + "/joint2/velocity"}}; + test_chained_controller_5->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_5->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_5->set_reference_interface_names({"joint2/velocity"}); + + auto test_chained_controller_6 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_5) + "/joint2/velocity"}}; + test_chained_controller_6->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_6->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_6->set_reference_interface_names({"joint2/velocity"}); + + auto test_controller_2 = std::make_shared(); + cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_6) + "/joint2/velocity"}}; + state_cfg = {controller_interface::interface_configuration_type::INDIVIDUAL, {"joint2/velocity"}}; + test_controller_2->set_command_interface_configuration(cmd_cfg); + test_controller_2->set_state_interface_configuration(state_cfg); + + // Third chain + auto test_chained_controller_7 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint3/velocity"}}; + test_chained_controller_7->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_7->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_7->set_reference_interface_names({"joint3/velocity"}); + + auto test_chained_controller_8 = std::make_shared(); + chained_cmd_cfg = { + controller_interface::interface_configuration_type::INDIVIDUAL, + {std::string(TEST_CHAINED_CONTROLLER_7) + "/joint3/velocity"}}; + test_chained_controller_8->set_command_interface_configuration(chained_cmd_cfg); + test_chained_controller_8->set_state_interface_configuration(chained_state_cfg); + test_chained_controller_8->set_reference_interface_names({"joint3/velocity"}); + + // add controllers + /// @todo add controllers in random order + /// For now, adding the ordered case to see that current sorting doesn't change order + cm_->add_controller( + test_chained_controller_2, TEST_CHAINED_CONTROLLER_2, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_6, TEST_CHAINED_CONTROLLER_6, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_1, TEST_CHAINED_CONTROLLER_1, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_7, TEST_CHAINED_CONTROLLER_7, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_1, TEST_CONTROLLER_1, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_5, TEST_CHAINED_CONTROLLER_5, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_3, TEST_CHAINED_CONTROLLER_3, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_4, TEST_CHAINED_CONTROLLER_4, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_controller_2, TEST_CONTROLLER_2, test_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + test_chained_controller_8, TEST_CHAINED_CONTROLLER_8, + 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(10u, result->controller.size()); + EXPECT_EQ(result->controller[0].name, TEST_CHAINED_CONTROLLER_2); + EXPECT_EQ(result->controller[1].name, TEST_CHAINED_CONTROLLER_6); + EXPECT_EQ(result->controller[2].name, TEST_CHAINED_CONTROLLER_1); + EXPECT_EQ(result->controller[3].name, TEST_CHAINED_CONTROLLER_7); + EXPECT_EQ(result->controller[4].name, TEST_CONTROLLER_1); + + EXPECT_EQ(result->controller[5].name, TEST_CHAINED_CONTROLLER_5); + EXPECT_EQ(result->controller[6].name, TEST_CHAINED_CONTROLLER_3); + EXPECT_EQ(result->controller[7].name, TEST_CHAINED_CONTROLLER_4); + EXPECT_EQ(result->controller[8].name, TEST_CONTROLLER_2); + EXPECT_EQ(result->controller[9].name, TEST_CHAINED_CONTROLLER_8); + + // configure controllers + auto ctrls_order = {TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, + TEST_CHAINED_CONTROLLER_1, TEST_CONTROLLER_1, + TEST_CHAINED_CONTROLLER_4, TEST_CONTROLLER_2, + TEST_CHAINED_CONTROLLER_2, TEST_CHAINED_CONTROLLER_6, + TEST_CHAINED_CONTROLLER_7, TEST_CHAINED_CONTROLLER_8}; + for (const auto & controller : ctrls_order) cm_->configure_controller(controller); + + // get controller list after configure + result = call_service_and_wait(*client, request, srv_executor); + ASSERT_EQ(10u, result->controller.size()); + + // activate controllers + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_1}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_4}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_7}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CHAINED_CONTROLLER_3, TEST_CHAINED_CONTROLLER_5, TEST_CHAINED_CONTROLLER_2, + TEST_CHAINED_CONTROLLER_6, TEST_CHAINED_CONTROLLER_8}, + {}, controller_manager_msgs::srv::SwitchController::Request::STRICT, true, + rclcpp::Duration(0, 0)); + cm_->switch_controller( + {TEST_CONTROLLER_1, TEST_CONTROLLER_2}, {}, + controller_manager_msgs::srv::SwitchController::Request::STRICT, true, rclcpp::Duration(0, 0)); + // get controller list after activate + result = call_service_and_wait(*client, request, srv_executor); + + ASSERT_EQ(10u, result->controller.size()); + + auto get_ctrl_pos = [result](const std::string & controller_name) -> int + { + auto it = std::find_if( + result->controller.begin(), result->controller.end(), + [controller_name](auto itf) + { return (itf.name.find(controller_name) != std::string::npos); }); + return std::distance(result->controller.begin(), it); + }; + auto ctrl_chain_1_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_1); + auto ctrl_chain_2_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_2); + auto ctrl_chain_3_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_3); + auto ctrl_chain_4_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_4); + auto ctrl_chain_5_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_5); + auto ctrl_chain_6_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_6); + auto ctrl_chain_7_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_7); + auto ctrl_chain_8_pos = get_ctrl_pos(TEST_CHAINED_CONTROLLER_8); + + auto ctrl_1_pos = get_ctrl_pos(TEST_CONTROLLER_1); + auto ctrl_2_pos = get_ctrl_pos(TEST_CONTROLLER_2); + + // Extra check to see that they are indexed after their parent controller + // first chain + ASSERT_GT(ctrl_chain_1_pos, ctrl_chain_2_pos); + ASSERT_GT(ctrl_chain_2_pos, ctrl_chain_3_pos); + ASSERT_GT(ctrl_chain_3_pos, ctrl_1_pos); + + // second tree + ASSERT_GT(ctrl_chain_4_pos, ctrl_chain_5_pos); + ASSERT_GT(ctrl_chain_5_pos, ctrl_chain_6_pos); + ASSERT_GT(ctrl_chain_6_pos, ctrl_2_pos); + + // third tree + ASSERT_GT(ctrl_chain_7_pos, ctrl_chain_8_pos); +} diff --git a/controller_manager/test/test_controller_manager_urdf_passing.cpp b/controller_manager/test/test_controller_manager_urdf_passing.cpp new file mode 100644 index 0000000000..102cbdfbd4 --- /dev/null +++ b/controller_manager/test/test_controller_manager_urdf_passing.cpp @@ -0,0 +1,88 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// 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. + +#include +#include +#include +#include +#include + +#include "controller_manager/controller_manager.hpp" +#include "controller_manager_test_common.hpp" + +#include "ros2_control_test_assets/descriptions.hpp" + +class TestControllerManagerWithTestableCM; + +class TestableControllerManager : public controller_manager::ControllerManager +{ + friend TestControllerManagerWithTestableCM; + + FRIEND_TEST(TestControllerManagerWithTestableCM, initial_no_load_urdf_called); + FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); + FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed); + FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); + FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback); + +public: + TestableControllerManager( + std::unique_ptr resource_manager, + std::shared_ptr executor, + const std::string & manager_node_name = "controller_manager", + const std::string & namespace_ = "") + : controller_manager::ControllerManager( + std::move(resource_manager), executor, manager_node_name, namespace_) + { + } +}; + +class TestControllerManagerWithTestableCM +: public ControllerManagerFixture, + public testing::WithParamInterface +{ +public: + // create cm with no urdf + TestControllerManagerWithTestableCM() + : ControllerManagerFixture("", false) + { + } +}; + +TEST_P(TestControllerManagerWithTestableCM, initial_no_load_urdf_called) +{ + ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); +} + +TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_callback) +{ + ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); + // mimic callback + auto msg = std_msgs::msg::String(); + msg.data = ros2_control_test_assets::minimal_robot_urdf; + cm_->robot_description_callback(msg); + ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded()); +} + +TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed) +{ + ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded()); + // mimic callback + auto msg = std_msgs::msg::String(); + msg.data = ros2_control_test_assets::minimal_robot_missing_command_keys_urdf; + cm_->robot_description_callback(msg); + ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded()); +} + +INSTANTIATE_TEST_SUITE_P( + test_best_effort, TestControllerManagerWithTestableCM, testing::Values(best_effort)); diff --git a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp index 62babe998d..16ba39d953 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -52,6 +52,8 @@ class TestableTestChainableController : public test_chainable_controller::TestCh FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_deactivation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order); }; class TestableControllerManager : public controller_manager::ControllerManager @@ -84,6 +86,8 @@ class TestableControllerManager : public controller_manager::ControllerManager FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_deactivation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order); public: TestableControllerManager( @@ -975,10 +979,132 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); } -// TODO(destogl): Add test case with controllers added in "random" order -// -// new value: "START_DOWNSTREAM_CTRLS" --> start "downstream" controllers in a controllers chain -// +TEST_P(TestControllerChainingWithControllerManager, test_chained_controllers_adding_in_random_order) +{ + SetupControllers(); + + // add all controllers in random order to test the sorting + cm_->add_controller( + pid_left_wheel_controller, PID_LEFT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_right_wheel_controller, PID_RIGHT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller_two, DIFF_DRIVE_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + + CheckIfControllersAreAddedCorrectly(); + + ConfigureAndCheckControllers(); + + SetToChainedModeAndMakeReferenceInterfacesAvailable( + pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeReferenceInterfacesAvailable( + pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_REFERENCE_INTERFACES); + SetToChainedModeAndMakeReferenceInterfacesAvailable( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_REFERENCE_INTERFACES); + + EXPECT_THROW( + cm_->resource_manager_->make_controller_reference_interfaces_available( + POSITION_TRACKING_CONTROLLER), + std::out_of_range); + + // Set ControllerManager into Debug-Mode output to have detailed output on updating controllers + cm_->get_logger().set_level(rclcpp::Logger::Level::Debug); + + // activate controllers - CONTROLLERS HAVE TO ADDED REVERSE EXECUTION ORDER + // (otherwise, interface will be missing) + ActivateAndCheckController( + pid_left_wheel_controller, PID_LEFT_WHEEL, PID_LEFT_WHEEL_CLAIMED_INTERFACES, 1u); + ActivateAndCheckController( + pid_right_wheel_controller, PID_RIGHT_WHEEL, PID_RIGHT_WHEEL_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 3u); + + // Diff-Drive Controller claims the reference interfaces of PID controllers + ActivateAndCheckController( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, DIFF_DRIVE_CLAIMED_INTERFACES, 1u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 3u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 5u); + + // Position-Tracking Controller uses reference interfaces of Diff-Drive Controller + ActivateAndCheckController( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + POSITION_CONTROLLER_CLAIMED_INTERFACES, 1u); + // 'rot_z' reference interface is not claimed + for (const auto & interface : {"diff_drive_controller/rot_z"}) + { + EXPECT_TRUE(cm_->resource_manager_->command_interface_exists(interface)); + EXPECT_TRUE(cm_->resource_manager_->command_interface_is_available(interface)); + EXPECT_FALSE(cm_->resource_manager_->command_interface_is_claimed(interface)); + } + ASSERT_EQ(diff_drive_controller->internal_counter, 3u); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 5u); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 7u); + + // update controllers + std::vector reference = {32.0, 128.0}; + + // update 'Position Tracking' controller + for (auto & value : diff_drive_controller->reference_interfaces_) + { + ASSERT_EQ(value, 0.0); // default reference values are 0.0 + } + position_tracking_controller->external_commands_for_testing_[0] = reference[0]; + position_tracking_controller->external_commands_for_testing_[1] = reference[1]; + position_tracking_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(position_tracking_controller->internal_counter, 2u); + + ASSERT_EQ(diff_drive_controller->reference_interfaces_[0], reference[0]); // position_controller + ASSERT_EQ(diff_drive_controller->reference_interfaces_[1], reference[1]); // is pass-through + + // update 'Diff Drive' Controller + diff_drive_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(diff_drive_controller->internal_counter, 4u); + // default reference values are 0.0 - they should be changed now + EXP_LEFT_WHEEL_REF = chained_ctrl_calculation(reference[0], EXP_LEFT_WHEEL_HW_STATE); // 32-0 + EXP_RIGHT_WHEEL_REF = chained_ctrl_calculation(reference[1], EXP_RIGHT_WHEEL_HW_STATE); // 128-0 + ASSERT_EQ(pid_left_wheel_controller->reference_interfaces_[0], EXP_LEFT_WHEEL_REF); + ASSERT_EQ(pid_right_wheel_controller->reference_interfaces_[0], EXP_RIGHT_WHEEL_REF); + + // update PID controllers that are writing to hardware + pid_left_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(pid_left_wheel_controller->internal_counter, 8u); + pid_right_wheel_controller->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + ASSERT_EQ(pid_right_wheel_controller->internal_counter, 6u); + + // update hardware ('read' is sufficient for test hardware) + cm_->resource_manager_->read(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + // 32 - 0 + EXP_LEFT_WHEEL_CMD = chained_ctrl_calculation(EXP_LEFT_WHEEL_REF, EXP_LEFT_WHEEL_HW_STATE); + // 32 / 2 + EXP_LEFT_WHEEL_HW_STATE = hardware_calculation(EXP_LEFT_WHEEL_CMD); + ASSERT_EQ(pid_left_wheel_controller->command_interfaces_[0].get_value(), EXP_LEFT_WHEEL_CMD); + ASSERT_EQ(pid_left_wheel_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + // DiffDrive uses the same state + ASSERT_EQ(diff_drive_controller->state_interfaces_[0].get_value(), EXP_LEFT_WHEEL_HW_STATE); + + // 128 - 0 + EXP_RIGHT_WHEEL_CMD = chained_ctrl_calculation(EXP_RIGHT_WHEEL_REF, EXP_RIGHT_WHEEL_HW_STATE); + // 128 / 2 + EXP_RIGHT_WHEEL_HW_STATE = hardware_calculation(EXP_RIGHT_WHEEL_CMD); + ASSERT_EQ(pid_right_wheel_controller->command_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_CMD); + ASSERT_EQ(pid_right_wheel_controller->state_interfaces_[0].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + // DiffDrive uses the same state + ASSERT_EQ(diff_drive_controller->state_interfaces_[1].get_value(), EXP_RIGHT_WHEEL_HW_STATE); + + // update all controllers at once and see that all have expected values --> also checks the order + // of controller execution + + reference = {1024.0, 4096.0}; + UpdateAllControllerAndCheck(reference, 3u); +} INSTANTIATE_TEST_SUITE_P( test_strict_best_effort, TestControllerChainingWithControllerManager, diff --git a/controller_manager/test/test_hardware_management_srvs.cpp b/controller_manager/test/test_hardware_management_srvs.cpp index 273e09d6a2..0fc7a2f27e 100644 --- a/controller_manager/test/test_hardware_management_srvs.cpp +++ b/controller_manager/test/test_hardware_management_srvs.cpp @@ -35,6 +35,7 @@ using hardware_interface::lifecycle_state_names::ACTIVE; using hardware_interface::lifecycle_state_names::FINALIZED; using hardware_interface::lifecycle_state_names::INACTIVE; using hardware_interface::lifecycle_state_names::UNCONFIGURED; +using hardware_interface::lifecycle_state_names::UNKNOWN; using ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES; using ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_NAME; @@ -69,9 +70,11 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs cm_->set_parameter( rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf)); cm_->set_parameter(rclcpp::Parameter( - "activate_components_on_start", std::vector({TEST_ACTUATOR_HARDWARE_NAME}))); + "hardware_components_initial_state.unconfigured", + std::vector({TEST_SYSTEM_HARDWARE_NAME}))); cm_->set_parameter(rclcpp::Parameter( - "configure_components_on_start", std::vector({TEST_SENSOR_HARDWARE_NAME}))); + "hardware_components_initial_state.inactive", + std::vector({TEST_SENSOR_HARDWARE_NAME}))); std::string robot_description = ""; cm_->get_parameter("robot_description", robot_description); @@ -199,36 +202,6 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs } }; -class TestControllerManagerHWManagementSrvsWithoutParams -: public TestControllerManagerHWManagementSrvs -{ -public: - void SetUp() override - { - executor_ = std::make_shared(); - cm_ = std::make_shared( - std::make_unique(), executor_, TEST_CM_NAME); - run_updater_ = false; - - // TODO(destogl): separate this to init_tests method where parameter can be set for each test - // separately - cm_->set_parameter( - rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf)); - - std::string robot_description = ""; - cm_->get_parameter("robot_description", robot_description); - if (robot_description.empty()) - { - throw std::runtime_error( - "Unable to initialize resource manager, no robot description found."); - } - - cm_->init_resource_manager(robot_description); - - SetUpSrvsCMExecutor(); - } -}; - TEST_F(TestControllerManagerHWManagementSrvs, list_hardware_components) { // Default status after start: @@ -386,6 +359,36 @@ TEST_F(TestControllerManagerHWManagementSrvs, selective_activate_deactivate_comp })); } +class TestControllerManagerHWManagementSrvsWithoutParams +: public TestControllerManagerHWManagementSrvs +{ +public: + void SetUp() override + { + executor_ = std::make_shared(); + cm_ = std::make_shared( + std::make_unique(), executor_, TEST_CM_NAME); + run_updater_ = false; + + // TODO(destogl): separate this to init_tests method where parameter can be set for each test + // separately + cm_->set_parameter( + rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf)); + + std::string robot_description = ""; + cm_->get_parameter("robot_description", robot_description); + if (robot_description.empty()) + { + throw std::runtime_error( + "Unable to initialize resource manager, no robot description found."); + } + + cm_->init_resource_manager(robot_description); + + SetUpSrvsCMExecutor(); + } +}; + TEST_F(TestControllerManagerHWManagementSrvsWithoutParams, test_default_activation_of_all_hardware) { // "configure_components_on_start" and "activate_components_on_start" are not set (empty) @@ -409,3 +412,62 @@ TEST_F(TestControllerManagerHWManagementSrvsWithoutParams, test_default_activati {{false, false, false, false}, {false, false, false, false, false, false, false}}, // system })); } + +// BEGIN: Remove at the end of 2023 +class TestControllerManagerHWManagementSrvsOldParameters +: public TestControllerManagerHWManagementSrvs +{ +public: + void SetUp() override + { + executor_ = std::make_shared(); + cm_ = std::make_shared( + std::make_unique(), executor_, TEST_CM_NAME); + run_updater_ = false; + + cm_->set_parameter( + rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf)); + cm_->set_parameter(rclcpp::Parameter( + "activate_components_on_start", std::vector({TEST_ACTUATOR_HARDWARE_NAME}))); + cm_->set_parameter(rclcpp::Parameter( + "configure_components_on_start", std::vector({TEST_SENSOR_HARDWARE_NAME}))); + + std::string robot_description = ""; + cm_->get_parameter("robot_description", robot_description); + if (robot_description.empty()) + { + throw std::runtime_error( + "Unable to initialize resource manager, no robot description found."); + } + + cm_->init_resource_manager(robot_description); + + SetUpSrvsCMExecutor(); + } +}; + +TEST_F(TestControllerManagerHWManagementSrvsOldParameters, list_hardware_components) +{ + // Default status after start: + // checks if "configure_components_on_start" and "activate_components_on_start" are correctly read + + list_hardware_components_and_check( + // actuator, sensor, system + std::vector( + {LFC_STATE::PRIMARY_STATE_ACTIVE, LFC_STATE::PRIMARY_STATE_INACTIVE, + LFC_STATE::PRIMARY_STATE_UNCONFIGURED}), + std::vector({ACTIVE, INACTIVE, UNCONFIGURED}), + std::vector>>({ + // is available + {{true, true}, {true, true, true}}, // actuator + {{}, {true}}, // sensor + {{false, false, false, false}, {false, false, false, false, false, false, false}}, // system + }), + std::vector>>({ + // is claimed + {{false, false}, {false, false, false}}, // actuator + {{}, {false}}, // sensor + {{false, false, false, false}, {false, false, false, false, false, false, false}}, // system + })); +} +// END: Remove at the end of 2023 diff --git a/controller_manager/test/test_spawner_unspawner.cpp b/controller_manager/test/test_spawner_unspawner.cpp index c9ba0e6355..d67ae8a7d1 100644 --- a/controller_manager/test/test_spawner_unspawner.cpp +++ b/controller_manager/test/test_spawner_unspawner.cpp @@ -96,6 +96,7 @@ TEST_F(TestLoadController, spawner_test_type_in_param) { cm_->set_parameter(rclcpp::Parameter("ctrl_1.type", test_controller::TEST_CONTROLLER_CLASS_NAME)); + ControllerManagerRunner cm_runner(this); EXPECT_EQ(call_spawner("ctrl_1 -c test_controller_manager"), 0); ASSERT_EQ(cm_->get_loaded_controllers().size(), 1ul); diff --git a/controller_manager_msgs/CHANGELOG.rst b/controller_manager_msgs/CHANGELOG.rst index 66c0285a44..8072652c55 100644 --- a/controller_manager_msgs/CHANGELOG.rst +++ b/controller_manager_msgs/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package controller_manager_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- + 3.13.0 (2023-05-18) ------------------- diff --git a/controller_manager_msgs/package.xml b/controller_manager_msgs/package.xml index 38b24b6b26..f7b9eb5642 100644 --- a/controller_manager_msgs/package.xml +++ b/controller_manager_msgs/package.xml @@ -2,7 +2,7 @@ controller_manager_msgs - 3.13.0 + 3.18.0 Messages and services for the controller manager. Bence Magyar Denis Štogl diff --git a/doc/index.rst b/doc/index.rst index 196ea93285..91f965d601 100644 --- a/doc/index.rst +++ b/doc/index.rst @@ -6,6 +6,8 @@ ros2_control ################# +This is the documentation of the ros2_control framework core. + `GitHub Repository `_ ================= @@ -14,15 +16,12 @@ API Documentation API documentation is parsed by doxygen and can be found `here <../../api/index.html>`_ - - ========= Features ========= * :ref:`Command Line Interface (CLI) ` - ======== Concepts ======== @@ -31,5 +30,6 @@ Concepts :titlesonly: Controller Manager <../controller_manager/doc/userdoc.rst> + Controller Chaining / Cascade Control <../controller_manager/doc/controller_chaining.rst> Hardware Components <../hardware_interface/doc/hardware_components_userdoc.rst> Mock Components <../hardware_interface/doc/mock_components_userdoc.rst> diff --git a/hardware_interface/CHANGELOG.rst b/hardware_interface/CHANGELOG.rst index 245ae211e5..0428cf4f8e 100644 --- a/hardware_interface/CHANGELOG.rst +++ b/hardware_interface/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- +* Add checks if hardware is initialized. (`#1054 `_) +* Contributors: Dr. Denis + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- +* Enable setting of initial state in HW compoments (`#1046 `_) +* Ensure instantiation of hardware classes work for python bindings (`#1058 `_) +* Contributors: Dr. Denis, Olivier Stasse + +3.14.0 (2023-06-14) +------------------- +* Add -Wconversion flag to protect future developments (`#1053 `_) +* [CM] Use `robot_description` topic instead of parameter and don't crash on empty URDF 🦿 (`#940 `_) +* [MockHardware] Enable disabling of command to simulate HW failures. (`#1027 `_) +* enable ReflowComments to also use ColumnLimit on comments (`#1037 `_) +* Docs: Use branch name substitution for all links (`#1031 `_) +* [URDF Parser] Allow empty urdf tag, e.g., parameter (`#1017 `_) +* Use consequently 'mock' instead of 'fake'. (`#1026 `_) +* Contributors: Christoph Fröhlich, Dr. Denis, Felix Exner (fexner), Manuel Muth, Sai Kishor Kothakota, gwalck + 3.13.0 (2023-05-18) ------------------- * Add class for thread management of async hw interfaces (`#981 `_) diff --git a/hardware_interface/CMakeLists.txt b/hardware_interface/CMakeLists.txt index 77eec3ec86..2d6c72ffae 100644 --- a/hardware_interface/CMakeLists.txt +++ b/hardware_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16) project(hardware_interface LANGUAGES CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS @@ -80,6 +80,10 @@ if(BUILD_TESTING) target_include_directories(test_macros PRIVATE include) ament_target_dependencies(test_macros rcpputils) + ament_add_gmock(test_inst_hardwares test/test_inst_hardwares.cpp) + target_link_libraries(test_inst_hardwares hardware_interface) + ament_target_dependencies(test_inst_hardwares rcpputils) + ament_add_gmock(test_joint_handle test/test_handle.cpp) target_link_libraries(test_joint_handle hardware_interface) ament_target_dependencies(test_joint_handle rcpputils) diff --git a/hardware_interface/doc/mock_components_userdoc.rst b/hardware_interface/doc/mock_components_userdoc.rst index 7fd50fc9c8..573037a58d 100644 --- a/hardware_interface/doc/mock_components_userdoc.rst +++ b/hardware_interface/doc/mock_components_userdoc.rst @@ -27,6 +27,11 @@ Features: Parameters ,,,,,,,,,, +disable_commands (optional; boolean; default: false) + Disables mirroring commands to states. + This option is helpful to simulate an erroneous connection to the hardware when nothing breaks, but suddenly there is no feedback from a hardware interface. + Or it can help you to test your setup when the hardware is running without feedback, i.e., in open loop configuration. + mock_sensor_commands (optional; boolean; default: false) Creates fake command interfaces for faking sensor measurements with an external command. Those interfaces are usually used by a :ref:`forward controller ` to provide access from ROS-world. diff --git a/hardware_interface/include/hardware_interface/actuator_interface.hpp b/hardware_interface/include/hardware_interface/actuator_interface.hpp index 64c81b0a34..abfd8eb45a 100644 --- a/hardware_interface/include/hardware_interface/actuator_interface.hpp +++ b/hardware_interface/include/hardware_interface/actuator_interface.hpp @@ -35,8 +35,9 @@ namespace hardware_interface /** * The typical examples are conveyors or motors. * - * Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - * with the following meaning: + * Methods return values have type + * rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following + * meaning: * * \returns CallbackReturn::SUCCESS method execution was successful. * \returns CallbackReturn::FAILURE method execution has failed and and can be called again. @@ -46,7 +47,8 @@ namespace hardware_interface * The hardware ends after each method in a state with the following meaning: * * UNCONFIGURED (on_init, on_cleanup): - * Hardware is initialized but communication is not started and therefore no interface is available. + * Hardware is initialized but communication is not started and therefore no interface is + * available. * * INACTIVE (on_configure, on_deactivate): * Communication with the hardware is started and it is configured. @@ -126,12 +128,12 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod * * \note This is a non-realtime evaluation of whether a set of command interface claims are * possible, and call to start preparing data structures for the upcoming switch that will occur. - * \note All starting and stopping interface keys are passed to all components, so the function should - * return return_type::OK by default when given interface keys not relevant for this component. - * \param[in] start_interfaces vector of string identifiers for the command interfaces starting. - * \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping. - * \return return_type::OK if the new command interface combination can be prepared, - * or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. + * \note All starting and stopping interface keys are passed to all components, so the function + * should return return_type::OK by default when given interface keys not relevant for this + * component. \param[in] start_interfaces vector of string identifiers for the command interfaces + * starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs + * stopping. \return return_type::OK if the new command interface combination can be prepared, or + * if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. */ virtual return_type prepare_command_mode_switch( const std::vector & /*start_interfaces*/, @@ -145,11 +147,11 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod * Perform the mode-switching for the new command interface combination. * * \note This is part of the realtime update loop, and should be fast. - * \note All starting and stopping interface keys are passed to all components, so the function should - * return return_type::OK by default when given interface keys not relevant for this component. - * \param[in] start_interfaces vector of string identifiers for the command interfaces starting. - * \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping. - * \return return_type::OK if the new command interface combination can be switched to, + * \note All starting and stopping interface keys are passed to all components, so the function + * should return return_type::OK by default when given interface keys not relevant for this + * component. \param[in] start_interfaces vector of string identifiers for the command interfaces + * starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs + * stopping. \return return_type::OK if the new command interface combination can be switched to, * or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. */ virtual return_type perform_command_mode_switch( diff --git a/hardware_interface/include/hardware_interface/component_parser.hpp b/hardware_interface/include/hardware_interface/component_parser.hpp index 9f81a2a863..5112f7927e 100644 --- a/hardware_interface/include/hardware_interface/component_parser.hpp +++ b/hardware_interface/include/hardware_interface/component_parser.hpp @@ -26,10 +26,10 @@ namespace hardware_interface { /// Search XML snippet from URDF for information about a control component. /** - * \param[in] urdf string with robot's URDF - * \return vector filled with information about robot's control resources - * \throws std::runtime_error if a robot attribute or tag is not found - */ + * \param[in] urdf string with robot's URDF + * \return vector filled with information about robot's control resources + * \throws std::runtime_error if a robot attribute or tag is not found + */ HARDWARE_INTERFACE_PUBLIC std::vector parse_control_resources_from_urdf(const std::string & urdf); diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp index a588ce691d..00a90ed937 100644 --- a/hardware_interface/include/hardware_interface/resource_manager.hpp +++ b/hardware_interface/include/hardware_interface/resource_manager.hpp @@ -66,8 +66,7 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager * \param[in] validate_interfaces boolean argument indicating whether the exported * interfaces ought to be validated. Defaults to true. * \param[in] activate_all boolean argument indicating if all resources should be immediately - * activated. Currently used only in tests. In typical applications use parameters - * "autostart_components" and "autoconfigure_components" instead. + * activated. Currently used only in tests. */ explicit ResourceManager( const std::string & urdf, bool validate_interfaces = true, bool activate_all = false, @@ -90,6 +89,16 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager */ void load_urdf(const std::string & urdf, bool validate_interfaces = true); + /** + * @brief if the resource manager load_urdf(...) function has been called this returns true. + * We want to permit to load the urdf later on but we currently don't want to permit multiple + * calls to load_urdf (reloading/loading different urdf). + * + * @return true if resource manager's load_urdf() has been already called. + * @return false if resource manager's load_urdf() has not been yet called. + */ + bool is_urdf_already_loaded() const; + /// Claim a state interface given its key. /** * The resource is claimed as long as being in scope. @@ -188,8 +197,9 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager /** * Return list of cached controller names that use the hardware with name \p hardware_name. * - * \param[in] hardware_name the name of the hardware for which cached controllers should be returned. - * \returns list of cached controller names that depend on hardware with name \p hardware_name. + * \param[in] hardware_name the name of the hardware for which cached controllers should be + * returned. \returns list of cached controller names that depend on hardware with name \p + * hardware_name. */ std::vector get_cached_controllers_to_hardware(const std::string & hardware_name); @@ -369,7 +379,7 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager * Reads from all active hardware components. * * Part of the real-time critical update loop. - * It is realtime-safe if used hadware interfaces are implemented adequately. + * It is realtime-safe if used hardware interfaces are implemented adequately. */ HardwareReadWriteStatus read(const rclcpp::Time & time, const rclcpp::Duration & period); @@ -378,18 +388,10 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager * Writes to all active hardware components. * * Part of the real-time critical update loop. - * It is realtime-safe if used hadware interfaces are implemented adequately. + * It is realtime-safe if used hardware interfaces are implemented adequately. */ HardwareReadWriteStatus write(const rclcpp::Time & time, const rclcpp::Duration & period); - /// Activates all available hardware components in the system. - /** - * All available hardware components int the ros2_control framework are activated. - * This is used to preserve default behavior from previous versions where all hardware components - * are activated per default. - */ - void activate_all_components(); - /// Checks whether a command interface is registered under the given key. /** * \param[in] key string identifying the interface to check. @@ -418,6 +420,8 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager // Structure to store read and write status so it is not initialized in the real-time loop HardwareReadWriteStatus read_write_status; + + bool is_urdf_loaded__ = false; }; } // namespace hardware_interface diff --git a/hardware_interface/include/hardware_interface/sensor_interface.hpp b/hardware_interface/include/hardware_interface/sensor_interface.hpp index 2b2a4ce7cb..14a59e4588 100644 --- a/hardware_interface/include/hardware_interface/sensor_interface.hpp +++ b/hardware_interface/include/hardware_interface/sensor_interface.hpp @@ -35,8 +35,9 @@ namespace hardware_interface /** * The typical examples are Force-Torque Sensor (FTS), Interial Measurement Unit (IMU). * - * Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - * with the following meaning: + * Methods return values have type + * rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following + * meaning: * * \returns CallbackReturn::SUCCESS method execution was successful. * \returns CallbackReturn::FAILURE method execution has failed and and can be called again. @@ -46,7 +47,8 @@ namespace hardware_interface * The hardware ends after each method in a state with the following meaning: * * UNCONFIGURED (on_init, on_cleanup): - * Hardware is initialized but communication is not started and therefore no interface is available. + * Hardware is initialized but communication is not started and therefore no interface is + * available. * * INACTIVE (on_configure, on_deactivate): * Communication with the hardware is started and it is configured. diff --git a/hardware_interface/include/hardware_interface/system.hpp b/hardware_interface/include/hardware_interface/system.hpp index 4c9ae67ae2..ece14f814d 100644 --- a/hardware_interface/include/hardware_interface/system.hpp +++ b/hardware_interface/include/hardware_interface/system.hpp @@ -35,6 +35,8 @@ class SystemInterface; class System final { public: + System() = default; + HARDWARE_INTERFACE_PUBLIC explicit System(std::unique_ptr impl); diff --git a/hardware_interface/include/hardware_interface/system_interface.hpp b/hardware_interface/include/hardware_interface/system_interface.hpp index 75e1a1bc29..e5c6f2f542 100644 --- a/hardware_interface/include/hardware_interface/system_interface.hpp +++ b/hardware_interface/include/hardware_interface/system_interface.hpp @@ -36,8 +36,9 @@ namespace hardware_interface * The common examples for these types of hardware are multi-joint systems with or without sensors * such as industrial or humanoid robots. * - * Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn - * with the following meaning: + * Methods return values have type + * rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following + * meaning: * * \returns CallbackReturn::SUCCESS method execution was successful. * \returns CallbackReturn::FAILURE method execution has failed and and can be called again. @@ -47,7 +48,8 @@ namespace hardware_interface * The hardware ends after each method in a state with the following meaning: * * UNCONFIGURED (on_init, on_cleanup): - * Hardware is initialized but communication is not started and therefore no interface is available. + * Hardware is initialized but communication is not started and therefore no interface is + * available. * * INACTIVE (on_configure, on_deactivate): * Communication with the hardware is started and it is configured. @@ -127,12 +129,12 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI * * \note This is a non-realtime evaluation of whether a set of command interface claims are * possible, and call to start preparing data structures for the upcoming switch that will occur. - * \note All starting and stopping interface keys are passed to all components, so the function should - * return return_type::OK by default when given interface keys not relevant for this component. - * \param[in] start_interfaces vector of string identifiers for the command interfaces starting. - * \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping. - * \return return_type::OK if the new command interface combination can be prepared, - * or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. + * \note All starting and stopping interface keys are passed to all components, so the function + * should return return_type::OK by default when given interface keys not relevant for this + * component. \param[in] start_interfaces vector of string identifiers for the command interfaces + * starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs + * stopping. \return return_type::OK if the new command interface combination can be prepared, or + * if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. */ virtual return_type prepare_command_mode_switch( const std::vector & /*start_interfaces*/, @@ -146,11 +148,11 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI * Perform the mode-switching for the new command interface combination. * * \note This is part of the realtime update loop, and should be fast. - * \note All starting and stopping interface keys are passed to all components, so the function should - * return return_type::OK by default when given interface keys not relevant for this component. - * \param[in] start_interfaces vector of string identifiers for the command interfaces starting. - * \param[in] stop_interfaces vector of string identifiers for the command interfacs stopping. - * \return return_type::OK if the new command interface combination can be switched to, + * \note All starting and stopping interface keys are passed to all components, so the function + * should return return_type::OK by default when given interface keys not relevant for this + * component. \param[in] start_interfaces vector of string identifiers for the command interfaces + * starting. \param[in] stop_interfaces vector of string identifiers for the command interfacs + * stopping. \return return_type::OK if the new command interface combination can be switched to, * or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise. */ virtual return_type perform_command_mode_switch( diff --git a/hardware_interface/include/mock_components/generic_system.hpp b/hardware_interface/include/mock_components/generic_system.hpp index 9506139c4a..c244ee1254 100644 --- a/hardware_interface/include/mock_components/generic_system.hpp +++ b/hardware_interface/include/mock_components/generic_system.hpp @@ -114,6 +114,8 @@ class HARDWARE_INTERFACE_PUBLIC GenericSystem : public hardware_interface::Syste double position_state_following_offset_; std::string custom_interface_with_following_offset_; size_t index_custom_interface_with_following_offset_; + + bool command_propagation_disabled_; }; typedef GenericSystem GenericRobot; diff --git a/hardware_interface/package.xml b/hardware_interface/package.xml index a024ad4a27..e3a2f4f71e 100644 --- a/hardware_interface/package.xml +++ b/hardware_interface/package.xml @@ -1,7 +1,7 @@ hardware_interface - 3.13.0 + 3.18.0 ros2_control hardware interface Bence Magyar Denis Štogl diff --git a/hardware_interface/src/component_parser.cpp b/hardware_interface/src/component_parser.cpp index 305c7ff7aa..8e9b6bf16b 100644 --- a/hardware_interface/src/component_parser.cpp +++ b/hardware_interface/src/component_parser.cpp @@ -304,11 +304,11 @@ hardware_interface::InterfaceInfo parse_interfaces_from_xml( /// Search XML snippet from URDF for information about a control component. /** - * \param[in] component_it pointer to the iterator where component - * info should be found - * \return ComponentInfo filled with information about component - * \throws std::runtime_error if a component attribute or tag is not found - */ + * \param[in] component_it pointer to the iterator where component + * info should be found + * \return ComponentInfo filled with information about component + * \throws std::runtime_error if a component attribute or tag is not found + */ ComponentInfo parse_component_from_xml(const tinyxml2::XMLElement * component_it) { ComponentInfo component; @@ -367,7 +367,8 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp component.command_interfaces.push_back(parse_interfaces_from_xml(command_interfaces_it)); component.command_interfaces.back().data_type = parse_data_type_attribute(command_interfaces_it); - component.command_interfaces.back().size = parse_size_attribute(command_interfaces_it); + component.command_interfaces.back().size = + static_cast(parse_size_attribute(command_interfaces_it)); command_interfaces_it = command_interfaces_it->NextSiblingElement(kCommandInterfaceTag); } @@ -377,7 +378,8 @@ ComponentInfo parse_complex_component_from_xml(const tinyxml2::XMLElement * comp { component.state_interfaces.push_back(parse_interfaces_from_xml(state_interfaces_it)); component.state_interfaces.back().data_type = parse_data_type_attribute(state_interfaces_it); - component.state_interfaces.back().size = parse_size_attribute(state_interfaces_it); + component.state_interfaces.back().size = + static_cast(parse_size_attribute(state_interfaces_it)); state_interfaces_it = state_interfaces_it->NextSiblingElement(kStateInterfaceTag); } @@ -417,10 +419,10 @@ ActuatorInfo parse_transmission_actuator_from_xml(const tinyxml2::XMLElement * e /// Search XML snippet from URDF for information about a transmission. /** - * \param[in] transmission_it pointer to the iterator where transmission info should be found - * \return TransmissionInfo filled with information about transmission - * \throws std::runtime_error if an attribute or tag is not found - */ + * \param[in] transmission_it pointer to the iterator where transmission info should be found + * \return TransmissionInfo filled with information about transmission + * \throws std::runtime_error if an attribute or tag is not found + */ TransmissionInfo parse_transmission_from_xml(const tinyxml2::XMLElement * transmission_it) { TransmissionInfo transmission; diff --git a/hardware_interface/src/mock_components/generic_system.cpp b/hardware_interface/src/mock_components/generic_system.cpp index d490784dbd..13a5a8b679 100644 --- a/hardware_interface/src/mock_components/generic_system.cpp +++ b/hardware_interface/src/mock_components/generic_system.cpp @@ -119,6 +119,18 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i } } + // check if there is parameter that disables commands + // this way we simulate disconnected driver + it = info_.hardware_parameters.find("disable_commands"); + if (it != info.hardware_parameters.end()) + { + command_propagation_disabled_ = hardware_interface::parse_bool(it->second); + } + else + { + command_propagation_disabled_ = false; + } + // process parameters about state following position_state_following_offset_ = 0.0; custom_interface_with_following_offset_ = ""; @@ -359,6 +371,13 @@ std::vector GenericSystem::export_command_ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { + if (command_propagation_disabled_) + { + RCUTILS_LOG_WARN_NAMED( + "mock_generic_system", "Command propagation is disabled - no values will be returned!"); + return return_type::OK; + } + auto mirror_command_to_state = [](auto & states_, auto commands_, size_t start_index = 0) { for (size_t i = start_index; i < states_.size(); ++i) diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp index fd4a172268..67b73ea0ae 100644 --- a/hardware_interface/src/resource_manager.cpp +++ b/hardware_interface/src/resource_manager.cpp @@ -516,9 +516,18 @@ class ResourceStorage { check_for_duplicates(hardware_info); load_hardware(hardware_info, actuator_loader_, container); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); - import_command_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + import_command_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "Actuator hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -537,8 +546,17 @@ class ResourceStorage { check_for_duplicates(hardware_info); load_hardware(hardware_info, sensor_loader_, container); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "Sensor hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -557,9 +575,18 @@ class ResourceStorage { check_for_duplicates(hardware_info); load_hardware(hardware_info, system_loader_, container); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); - import_command_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + import_command_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "System hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -578,9 +605,18 @@ class ResourceStorage auto init_actuators = [&](auto & container) { container.emplace_back(Actuator(std::move(actuator))); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); - import_command_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + import_command_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "Actuator hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -599,8 +635,17 @@ class ResourceStorage auto init_sensors = [&](auto & container) { container.emplace_back(Sensor(std::move(sensor))); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "Sensor hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -619,9 +664,18 @@ class ResourceStorage auto init_systems = [&](auto & container) { container.emplace_back(System(std::move(system))); - initialize_hardware(hardware_info, container.back()); - import_state_interfaces(container.back()); - import_command_interfaces(container.back()); + if (initialize_hardware(hardware_info, container.back())) + { + import_state_interfaces(container.back()); + import_command_interfaces(container.back()); + } + else + { + RCUTILS_LOG_WARN_NAMED( + "resource_manager", + "System hardware component '%s' from plugin '%s' failed to initialize.", + hardware_info.name.c_str(), hardware_info.hardware_plugin_name.c_str()); + } }; if (hardware_info.is_async) @@ -705,6 +759,7 @@ ResourceManager::ResourceManager( // CM API: Called in "callback/slow"-thread void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfaces) { + is_urdf_loaded__ = true; const std::string system_type = "system"; const std::string sensor_type = "sensor"; const std::string actuator_type = "actuator"; @@ -743,6 +798,8 @@ void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfac resource_storage_->systems_.size()); } +bool ResourceManager::is_urdf_already_loaded() const { return is_urdf_loaded__; } + // CM API: Called in "update"-thread LoanedStateInterface ResourceManager::claim_state_interface(const std::string & key) { @@ -1362,25 +1419,4 @@ void ResourceManager::validate_storage( // END: private methods -// Temporary method to keep old interface and reduce framework changes in the PRs -void ResourceManager::activate_all_components() -{ - using lifecycle_msgs::msg::State; - rclcpp_lifecycle::State active_state( - State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE); - - for (auto & component : resource_storage_->actuators_) - { - set_component_state(component.get_name(), active_state); - } - for (auto & component : resource_storage_->sensors_) - { - set_component_state(component.get_name(), active_state); - } - for (auto & component : resource_storage_->systems_) - { - set_component_state(component.get_name(), active_state); - } -} - } // namespace hardware_interface diff --git a/hardware_interface/test/mock_components/test_generic_system.cpp b/hardware_interface/test/mock_components/test_generic_system.cpp index e82d7d1fb2..8e78ade7fb 100644 --- a/hardware_interface/test/mock_components/test_generic_system.cpp +++ b/hardware_interface/test/mock_components/test_generic_system.cpp @@ -483,6 +483,24 @@ class TestGenericSystem : public ::testing::Test )"; + + disabled_commands_ = + R"( + + + fake_components/GenericSystem + True + + + + + + 3.45 + + + + +)"; } std::string hardware_robot_2dof_; @@ -503,6 +521,7 @@ class TestGenericSystem : public ::testing::Test std::string valid_urdf_ros2_control_system_robot_with_gpio_mock_command_True_; std::string sensor_with_initial_value_; std::string gpio_with_initial_value_; + std::string disabled_commands_; }; // Forward declaration @@ -1604,3 +1623,51 @@ TEST_F(TestGenericSystem, gpio_with_initial_value) ASSERT_EQ(1, state.get_value()); } + +TEST_F(TestGenericSystem, disabled_commands_flag_is_active) +{ + auto urdf = + ros2_control_test_assets::urdf_head + disabled_commands_ + ros2_control_test_assets::urdf_tail; + TestableResourceManager rm(urdf); + // Activate components to get all interfaces available + activate_components(rm); + + // Check interfaces + EXPECT_EQ(1u, rm.system_components_size()); + ASSERT_EQ(2u, rm.state_interface_keys().size()); + EXPECT_TRUE(rm.state_interface_exists("joint1/position")); + EXPECT_TRUE(rm.state_interface_exists("joint1/velocity")); + + ASSERT_EQ(2u, rm.command_interface_keys().size()); + EXPECT_TRUE(rm.command_interface_exists("joint1/position")); + EXPECT_TRUE(rm.command_interface_exists("joint1/velocity")); + + // Check initial values + hardware_interface::LoanedStateInterface j1p_s = rm.claim_state_interface("joint1/position"); + hardware_interface::LoanedStateInterface j1v_s = rm.claim_state_interface("joint1/velocity"); + hardware_interface::LoanedCommandInterface j1p_c = rm.claim_command_interface("joint1/position"); + + ASSERT_EQ(3.45, j1p_s.get_value()); + ASSERT_EQ(0.0, j1v_s.get_value()); + ASSERT_TRUE(std::isnan(j1p_c.get_value())); + + // set some new values in commands + j1p_c.set_value(0.11); + + // State values should not be changed + ASSERT_EQ(3.45, j1p_s.get_value()); + ASSERT_EQ(0.0, j1v_s.get_value()); + ASSERT_EQ(0.11, j1p_c.get_value()); + + // write() does not change values + rm.write(TIME, PERIOD); + ASSERT_EQ(3.45, j1p_s.get_value()); + ASSERT_EQ(0.0, j1v_s.get_value()); + ASSERT_EQ(0.11, j1p_c.get_value()); + + // read() also does not change values + rm.read(TIME, PERIOD); + ASSERT_EQ(3.45, j1p_s.get_value()); + ASSERT_EQ(0.0, j1v_s.get_value()); + ASSERT_EQ(0.11, j1p_c.get_value()); +} diff --git a/hardware_interface/test/test_components/test_actuator.cpp b/hardware_interface/test/test_components/test_actuator.cpp index 8fec418dcf..5f9c09e95e 100644 --- a/hardware_interface/test/test_components/test_actuator.cpp +++ b/hardware_interface/test/test_components/test_actuator.cpp @@ -40,7 +40,7 @@ class TestActuator : public ActuatorInterface * if (info_.joints[0].command_interfaces.size() != 1) {return CallbackReturn::ERROR;} * // can only give feedback state for position and velocity * if (info_.joints[0].state_interfaces.size() != 2) {return CallbackReturn::ERROR;} - */ + */ return CallbackReturn::SUCCESS; } diff --git a/hardware_interface/test/test_inst_hardwares.cpp b/hardware_interface/test/test_inst_hardwares.cpp new file mode 100644 index 0000000000..ddd3aea0ad --- /dev/null +++ b/hardware_interface/test/test_inst_hardwares.cpp @@ -0,0 +1,34 @@ +// Copyright 2023 LAAS CNRS +// +// 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. + +#include + +#include "hardware_interface/actuator.hpp" +#include "hardware_interface/actuator_interface.hpp" +#include "hardware_interface/sensor.hpp" +#include "hardware_interface/sensor_interface.hpp" +#include "hardware_interface/system.hpp" +#include "hardware_interface/system_interface.hpp" + +class TestInstantiationHardwares : public ::testing::Test +{ +protected: + static void SetUpTestCase() {} +}; + +TEST_F(TestInstantiationHardwares, build_actuator) { hardware_interface::Actuator anActuator; } + +TEST_F(TestInstantiationHardwares, build_sensor) { hardware_interface::Sensor aSensor; } + +TEST_F(TestInstantiationHardwares, build_system) { hardware_interface::System aSystem; } diff --git a/hardware_interface/test/test_resource_manager.cpp b/hardware_interface/test/test_resource_manager.cpp index e1b9e240e7..aedf2b862d 100644 --- a/hardware_interface/test/test_resource_manager.cpp +++ b/hardware_interface/test/test_resource_manager.cpp @@ -212,6 +212,34 @@ TEST_F(ResourceManagerTest, initialization_with_urdf_unclaimed) } } +TEST_F(ResourceManagerTest, no_load_urdf_function_called) +{ + TestableResourceManager rm; + ASSERT_FALSE(rm.is_urdf_already_loaded()); +} + +TEST_F(ResourceManagerTest, load_urdf_called_if_urdf_is_invalid) +{ + TestableResourceManager rm; + EXPECT_THROW( + rm.load_urdf(ros2_control_test_assets::minimal_robot_missing_state_keys_urdf), std::exception); + ASSERT_TRUE(rm.is_urdf_already_loaded()); +} + +TEST_F(ResourceManagerTest, load_urdf_called_if_urdf_is_valid) +{ + TestableResourceManager rm(ros2_control_test_assets::minimal_robot_urdf); + ASSERT_TRUE(rm.is_urdf_already_loaded()); +} + +TEST_F(ResourceManagerTest, can_load_urdf_later) +{ + TestableResourceManager rm; + ASSERT_FALSE(rm.is_urdf_already_loaded()); + rm.load_urdf(ros2_control_test_assets::minimal_robot_urdf); + ASSERT_TRUE(rm.is_urdf_already_loaded()); +} + TEST_F(ResourceManagerTest, resource_claiming) { TestableResourceManager rm(ros2_control_test_assets::minimal_robot_urdf); diff --git a/joint_limits/CHANGELOG.rst b/joint_limits/CHANGELOG.rst index 211828a28b..46acee3f8d 100644 --- a/joint_limits/CHANGELOG.rst +++ b/joint_limits/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package joint_limits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- +* Add -Wconversion flag to protect future developments (`#1053 `_) +* enable ReflowComments to also use ColumnLimit on comments (`#1037 `_) +* Contributors: Sai Kishor Kothakota, gwalck + 3.13.0 (2023-05-18) ------------------- diff --git a/joint_limits/CMakeLists.txt b/joint_limits/CMakeLists.txt index 9ec9221220..82467514a3 100644 --- a/joint_limits/CMakeLists.txt +++ b/joint_limits/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16) project(joint_limits LANGUAGES CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") - add_compile_options(-Wall -Wextra) + add_compile_options(-Wall -Wextra -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/joint_limits/include/joint_limits/joint_limits_rosparam.hpp b/joint_limits/include/joint_limits/joint_limits_rosparam.hpp index 5d1fd6a1f7..2f32d49271 100644 --- a/joint_limits/include/joint_limits/joint_limits_rosparam.hpp +++ b/joint_limits/include/joint_limits/joint_limits_rosparam.hpp @@ -28,11 +28,11 @@ namespace // utilities { /// Declare and initialize a parameter with a type. /** - * - * Wrapper function for templated node's declare_parameter() which checks if - * parameter is already declared. - * For use in all components that inherit from ControllerInterface - */ + * + * Wrapper function for templated node's declare_parameter() which checks if + * parameter is already declared. + * For use in all components that inherit from ControllerInterface + */ template auto auto_declare( const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf, @@ -149,10 +149,9 @@ inline bool declare_parameters(const std::string & joint_name, const rclcpp::Nod } /** - * Declare JointLimits and SoftJointLimits parameters for joint with joint_name for the lifecycle_node - * object. - * This is a convenience function. - * For parameters structure see the underlying `declare_parameters` function. + * Declare JointLimits and SoftJointLimits parameters for joint with joint_name for the + * lifecycle_node object. This is a convenience function. For parameters structure see the + * underlying `declare_parameters` function. * * \param[in] joint_name name of the joint for which parameters will be declared. * \param[in] lifecycle_node lifecycle node for parameters should be declared. @@ -217,10 +216,12 @@ inline bool declare_parameters( * \param[in] joint_name Name of joint whose limits are to be fetched, e.g., "foo_joint". * \param[in] param_itf node parameters interface of the node where parameters are specified. * \param[in] logging_itf node logging interface to provide log errors. - * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. Values in \p limits not specified in the parameter server remain unchanged. + * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter + * server will overwrite existing values. Values in \p limits not specified in the parameter server + * remain unchanged. * - * \returns True if a limits specification is found (i.e., the \p joint_limits/joint_name parameter exists in \p node), false otherwise. + * \returns True if a limits specification is found (i.e., the \p joint_limits/joint_name parameter + * exists in \p node), false otherwise. */ inline bool get_joint_limits( const std::string & joint_name, @@ -385,8 +386,9 @@ inline bool get_joint_limits( * * \param[in] joint_name Name of joint whose limits are to be fetched. * \param[in] node Node object for which parameters should be fetched. - * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. Values in \p limits not specified in the parameter server remain unchanged. + * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter + * server will overwrite existing values. Values in \p limits not specified in the parameter server + * remain unchanged. * * \returns True if a limits specification is found, false otherwise. */ @@ -404,8 +406,9 @@ inline bool get_joint_limits( * * \param[in] joint_name Name of joint whose limits are to be fetched. * \param[in] lifecycle_node Lifecycle node object for which parameters should be fetched. - * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. Values in \p limits not specified in the parameter server remain unchanged. + * \param[out] limits Where joint limit data gets written into. Limits specified in the parameter + * server will overwrite existing values. Values in \p limits not specified in the parameter server + * remain unchanged. * * \returns True if a limits specification is found, false otherwise. */ @@ -445,10 +448,10 @@ inline bool get_joint_limits( * \param[in] joint_name Name of joint whose limits are to be fetched, e.g., "foo_joint". * \param[in] param_itf node parameters interface of the node where parameters are specified. * \param[in] logging_itf node logging interface to provide log errors. - * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. - * \return True if a complete soft limits specification is found (ie. if all \p k_position, \p k_velocity, \p soft_lower_limit and - * \p soft_upper_limit exist in \p joint_limits/joint_name namespace), false otherwise. + * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the + * parameter server will overwrite existing values. \return True if a complete soft limits + * specification is found (ie. if all \p k_position, \p k_velocity, \p soft_lower_limit and \p + * soft_upper_limit exist in \p joint_limits/joint_name namespace), false otherwise. */ inline bool get_joint_limits( const std::string & joint_name, @@ -512,8 +515,8 @@ inline bool get_joint_limits( * * \param[in] joint_name Name of joint whose limits are to be fetched. * \param[in] node Node object for which parameters should be fetched. - * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. + * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the + * parameter server will overwrite existing values. * * \returns True if a soft limits specification is found, false otherwise. */ @@ -533,8 +536,8 @@ inline bool get_joint_limits( * * \param[in] joint_name Name of joint whose limits are to be fetched. * \param[in] lifecycle_node Lifecycle node object for which parameters should be fetched. - * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the parameter server will overwrite - * existing values. + * \param[out] soft_limits Where soft joint limit data gets written into. Limits specified in the + * parameter server will overwrite existing values. * * \returns True if a soft limits specification is found, false otherwise. */ diff --git a/joint_limits/package.xml b/joint_limits/package.xml index 7bcf465d24..f1c0365cfd 100644 --- a/joint_limits/package.xml +++ b/joint_limits/package.xml @@ -1,6 +1,6 @@ joint_limits - 3.13.0 + 3.18.0 Interfaces for handling of joint limits for controllers or hardware. Bence Magyar diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.hpp b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.hpp index 3f17ceea78..db553948d1 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.hpp +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.hpp @@ -144,8 +144,8 @@ class JointSoftLimitsHandle : public JointLimitHandle joint_limits_interface::SoftJointLimits soft_limits_; }; -/** A handle used to enforce position and velocity limits of a position-controlled joint that does not have - soft limits. */ +/** A handle used to enforce position and velocity limits of a position-controlled joint that does + not have soft limits. */ class PositionJointSaturationHandle : public JointLimitHandle { public: @@ -170,8 +170,8 @@ class PositionJointSaturationHandle : public JointLimitHandle /// Enforce position and velocity limits for a joint that is not subject to soft limits. /** - * \param[in] period Control period. - */ + * \param[in] period Control period. + */ void enforce_limits(const rclcpp::Duration & period) { if (std::isnan(prev_pos_)) @@ -209,9 +209,9 @@ class PositionJointSaturationHandle : public JointLimitHandle /// A handle used to enforce position and velocity limits of a position-controlled joint. /** - * This class implements a very simple position and velocity limits enforcing policy, and tries to impose the least - * amount of requisites on the underlying hardware platform. - * This lowers considerably the entry barrier to use it, but also implies some limitations. + * This class implements a very simple position and velocity limits enforcing policy, and tries to + * impose the least amount of requisites on the underlying hardware platform. This lowers + * considerably the entry barrier to use it, but also implies some limitations. * * Requisites * - Position (for non-continuous joints) and velocity limits specification. @@ -219,21 +219,22 @@ class PositionJointSaturationHandle : public JointLimitHandle * * Open loop nature * - * Joint position and velocity limits are enforced in an open-loop fashion, that is, the command is checked for - * validity without relying on the actual position/velocity values. + * Joint position and velocity limits are enforced in an open-loop fashion, that is, the command is + * checked for validity without relying on the actual position/velocity values. * - * - Actual position values are \e not used because in some platforms there might be a substantial lag - * between sending a command and executing it (propagate command to hardware, reach control objective, - * read from hardware). + * - Actual position values are \e not used because in some platforms there might be a substantial + * lag between sending a command and executing it (propagate command to hardware, reach control + * objective, read from hardware). * - * - Actual velocity values are \e not used because of the above reason, and because some platforms might not expose - * trustworthy velocity measurements, or none at all. + * - Actual velocity values are \e not used because of the above reason, and because some platforms + * might not expose trustworthy velocity measurements, or none at all. * - * The downside of the open loop behavior is that velocity limits will not be enforced when recovering from large - * position tracking errors. Only the command is guaranteed to comply with the limits specification. + * The downside of the open loop behavior is that velocity limits will not be enforced when + * recovering from large position tracking errors. Only the command is guaranteed to comply with the + * limits specification. * - * \note: This handle type is \e stateful, ie. it stores the previous position command to estimate the command - * velocity. + * \note: This handle type is \e stateful, ie. it stores the previous position command to estimate + * the command velocity. */ // TODO(anyone): Leverage %Reflexxes Type II library for acceleration limits handling? @@ -553,8 +554,8 @@ class VelocityJointSaturationHandle : public JointLimitHandle /** * A handle used to enforce position, velocity, and acceleration limits of a - * velocity-controlled joint. - */ + * velocity-controlled joint. + */ class VelocityJointSoftLimitsHandle : public JointSoftLimitsHandle { public: diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_urdf.hpp b/joint_limits_interface/include/joint_limits_interface/joint_limits_urdf.hpp index 6f26a997ee..80cf7f0ed4 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_urdf.hpp +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_urdf.hpp @@ -27,8 +27,8 @@ namespace joint_limits_interface /** * Populate a JointLimits instance from URDF joint data. * \param[in] urdf_joint URDF joint. - * \param[out] limits Where URDF joint limit data gets written into. Limits in \e urdf_joint will overwrite existing - * values. Values in \e limits not present in \e urdf_joint remain unchanged. + * \param[out] limits Where URDF joint limit data gets written into. Limits in \e urdf_joint will + * overwrite existing values. Values in \e limits not present in \e urdf_joint remain unchanged. * \return True if \e urdf_joint has a valid limits specification, false otherwise. */ inline bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits & limits) diff --git a/ros2_control-not-released.galactic.repos b/ros2_control-not-released.galactic.repos deleted file mode 100644 index 56f46b6f79..0000000000 --- a/ros2_control-not-released.galactic.repos +++ /dev/null @@ -1 +0,0 @@ -repositories: diff --git a/ros2_control-not-released.foxy.repos b/ros2_control-not-released.iron.repos similarity index 100% rename from ros2_control-not-released.foxy.repos rename to ros2_control-not-released.iron.repos diff --git a/ros2_control.galactic.repos b/ros2_control.galactic.repos deleted file mode 100644 index afb1cbf640..0000000000 --- a/ros2_control.galactic.repos +++ /dev/null @@ -1,9 +0,0 @@ -repositories: - ros-controls/realtime_tools: - type: git - url: https://github.com/ros-controls/realtime_tools.git - version: foxy-devel - ros-controls/control_msgs: - type: git - url: https://github.com/ros-controls/control_msgs.git - version: galactic-devel diff --git a/ros2_control.foxy.repos b/ros2_control.iron.repos similarity index 82% rename from ros2_control.foxy.repos rename to ros2_control.iron.repos index a52f653b54..c93d8f4ef6 100644 --- a/ros2_control.foxy.repos +++ b/ros2_control.iron.repos @@ -2,8 +2,8 @@ repositories: ros-controls/realtime_tools: type: git url: https://github.com/ros-controls/realtime_tools.git - version: foxy-devel + version: master ros-controls/control_msgs: type: git url: https://github.com/ros-controls/control_msgs.git - version: foxy-devel + version: master diff --git a/ros2_control/CHANGELOG.rst b/ros2_control/CHANGELOG.rst index d6e3effbb0..272c2d3fe4 100644 --- a/ros2_control/CHANGELOG.rst +++ b/ros2_control/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package ros2_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- + 3.13.0 (2023-05-18) ------------------- diff --git a/ros2_control/package.xml b/ros2_control/package.xml index ddc9ae5edd..15a379933a 100644 --- a/ros2_control/package.xml +++ b/ros2_control/package.xml @@ -1,7 +1,7 @@ ros2_control - 3.13.0 + 3.18.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 e5b824a921..d633c415d1 100644 --- a/ros2_control_test_assets/CHANGELOG.rst +++ b/ros2_control_test_assets/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package ros2_control_test_assets ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- +* [URDF Parser] Allow empty urdf tag, e.g., parameter (`#1017 `_) +* Contributors: Felix Exner (fexner) + 3.13.0 (2023-05-18) ------------------- diff --git a/ros2_control_test_assets/package.xml b/ros2_control_test_assets/package.xml index 00c489b6a2..c77b828276 100644 --- a/ros2_control_test_assets/package.xml +++ b/ros2_control_test_assets/package.xml @@ -2,7 +2,7 @@ ros2_control_test_assets - 3.13.0 + 3.18.0 The package provides shared test resources for ros2_control stack Bence Magyar diff --git a/ros2controlcli/CHANGELOG.rst b/ros2controlcli/CHANGELOG.rst index 0af749a91a..a5a153faf1 100644 --- a/ros2controlcli/CHANGELOG.rst +++ b/ros2controlcli/CHANGELOG.rst @@ -2,6 +2,27 @@ Changelog for package ros2controlcli ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- +* Add info where the pdf is saved to view_controller_chains (`#1094 `_) +* Contributors: Christoph Fröhlich + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- +* Improve list hardware components output and code for better readability. (`#1060 `_) +* Contributors: Dr. Denis + +3.14.0 (2023-06-14) +------------------- +* Docs: Use branch name substitution for all links (`#1031 `_) +* Contributors: Christoph Fröhlich + 3.13.0 (2023-05-18) ------------------- * Fix github links on control.ros.org (`#1019 `_) diff --git a/ros2controlcli/doc/userdoc.rst b/ros2controlcli/doc/userdoc.rst index dba173cfbf..5880c054cb 100644 --- a/ros2controlcli/doc/userdoc.rst +++ b/ros2controlcli/doc/userdoc.rst @@ -268,4 +268,14 @@ view_controller_chains $ ros2 control view_controller_chains -h usage: ros2 view_controller_chains - Creates a graphviz image from loaded controllers. + Generates a diagram of the loaded chained controllers into /tmp/controller_diagram.gv.pdf + + options: + -h, --help show this help message and exit + --spin-time SPIN_TIME + Spin time in seconds to wait for discovery (only applies when not using an already running daemon) + -s, --use-sim-time Enable ROS simulation time + -c CONTROLLER_MANAGER, --controller-manager CONTROLLER_MANAGER + Name of the controller manager ROS node + --include-hidden-nodes + Consider hidden nodes as well diff --git a/ros2controlcli/package.xml b/ros2controlcli/package.xml index ca01cbe271..92eba51b62 100644 --- a/ros2controlcli/package.xml +++ b/ros2controlcli/package.xml @@ -2,7 +2,7 @@ ros2controlcli - 3.13.0 + 3.18.0 The ROS 2 command line tools for ROS2 Control. diff --git a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py index 54dff21bb6..8a5884f2cb 100644 --- a/ros2controlcli/ros2controlcli/verb/list_hardware_components.py +++ b/ros2controlcli/ros2controlcli/verb/list_hardware_components.py @@ -40,7 +40,7 @@ def main(self, *, args): for idx, component in enumerate(hardware_components.component): print( - f"Hardware Component {idx}\n\tname: {component.name}\n\ttype: {component.type}" + f"Hardware Component {idx+1}\n\tname: {component.name}\n\ttype: {component.type}" ) if hasattr(component, "plugin_name"): plugin_name = component.plugin_name @@ -48,7 +48,9 @@ def main(self, *, args): plugin_name = f"{bcolors.WARNING}plugin name missing!{bcolors.ENDC}" print( - f"\tplugin name: {plugin_name}\n\tstate: id={component.state.id} label={component.state.label}\n\tcommand interfaces" + f"\tplugin name: {plugin_name}\n" + f"\tstate: id={component.state.id} label={component.state.label}\n" + f"\tcommand interfaces" ) for cmd_interface in component.command_interfaces: if cmd_interface.is_available: diff --git a/ros2controlcli/ros2controlcli/verb/view_controller_chains.py b/ros2controlcli/ros2controlcli/verb/view_controller_chains.py index fbd999192e..f838a96e1c 100644 --- a/ros2controlcli/ros2controlcli/verb/view_controller_chains.py +++ b/ros2controlcli/ros2controlcli/verb/view_controller_chains.py @@ -195,7 +195,7 @@ def parse_response(list_controllers_response, list_hardware_response, visualize= class ViewControllerChainsVerb(VerbExtension): - """Generates a diagram of the loaded chained controllers.""" + """Generates a diagram of the loaded chained controllers into /tmp/controller_diagram.gv.pdf.""" def add_arguments(self, parser, cli_name): add_arguments(parser) diff --git a/ros2controlcli/setup.py b/ros2controlcli/setup.py index b916f1a2af..aa2b19b830 100644 --- a/ros2controlcli/setup.py +++ b/ros2controlcli/setup.py @@ -19,7 +19,7 @@ setup( name=package_name, - version="3.13.0", + version="3.18.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 f57aa7fcbd..9996ff5a85 100644 --- a/rqt_controller_manager/CHANGELOG.rst +++ b/rqt_controller_manager/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package rqt_controller_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- + 3.13.0 (2023-05-18) ------------------- diff --git a/rqt_controller_manager/package.xml b/rqt_controller_manager/package.xml index acd6496e8d..4888459d49 100644 --- a/rqt_controller_manager/package.xml +++ b/rqt_controller_manager/package.xml @@ -2,7 +2,7 @@ rqt_controller_manager - 3.13.0 + 3.18.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 7d12c68e1f..318cf556d2 100644 --- a/rqt_controller_manager/setup.py +++ b/rqt_controller_manager/setup.py @@ -6,7 +6,7 @@ setup( name=package_name, - version="3.13.0", + version="3.18.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 7dded27cc1..c45b040c1b 100644 --- a/transmission_interface/CHANGELOG.rst +++ b/transmission_interface/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package transmission_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3.18.0 (2023-08-17) +------------------- + +3.17.0 (2023-08-07) +------------------- + +3.16.0 (2023-07-09) +------------------- + +3.15.0 (2023-06-23) +------------------- + +3.14.0 (2023-06-14) +------------------- +* Add -Wconversion flag to protect future developments (`#1053 `_) +* enable ReflowComments to also use ColumnLimit on comments (`#1037 `_) +* Contributors: Sai Kishor Kothakota, gwalck + 3.13.0 (2023-05-18) ------------------- diff --git a/transmission_interface/CMakeLists.txt b/transmission_interface/CMakeLists.txt index 8ae2cc224c..d4674366e9 100644 --- a/transmission_interface/CMakeLists.txt +++ b/transmission_interface/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16) project(transmission_interface LANGUAGES CXX) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") - add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wall -Wextra -Wpedantic -Wconversion) endif() set(THIS_PACKAGE_INCLUDE_DEPENDS diff --git a/transmission_interface/include/transmission_interface/differential_transmission.hpp b/transmission_interface/include/transmission_interface/differential_transmission.hpp index 6bc89ab893..2002f6f9d7 100644 --- a/transmission_interface/include/transmission_interface/differential_transmission.hpp +++ b/transmission_interface/include/transmission_interface/differential_transmission.hpp @@ -30,9 +30,8 @@ namespace transmission_interface /// Implementation of a differential transmission. /** * - * This transmission relates two actuators and two joints through a differential mechanism, as illustrated - * below. - * \image html differential_transmission.png + * This transmission relates two actuators and two joints through a differential + * mechanism, as illustrated below. \image html differential_transmission.png * *
* @@ -76,28 +75,33 @@ namespace transmission_interface * *
* \f{eqnarray*}{ - * x_{a_1} & = & n_{a_1} \left[ n_{j_1} (x_{j_1} - x_{off_1}) + n_{j_2} (x_{j_2} - x_{off_2}) \right] \\[2.5em] - * x_{a_2} & = & n_{a_2} \left[ n_{j_1} (x_{j_1} - x_{off_1}) - n_{j_2} (x_{j_2} - x_{off_2}) \right] - * \f} + * x_{a_1} & = & n_{a_1} \left[ n_{j_1} (x_{j_1} - x_{off_1}) + n_{j_2} (x_{j_2} - x_{off_2}) + * \right] \\[2.5em] x_{a_2} & = & n_{a_2} \left[ n_{j_1} (x_{j_1} - x_{off_1}) - n_{j_2} (x_{j_2} - + * x_{off_2}) \right] \f} *
*
* * where: - * - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, respectively. - * - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space variables, respectively. - * - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position coordinates - * (cf. SimpleTransmission class documentation for a more detailed description of this variable). - * - \f$ n \f$ represents a transmission ratio. Reducers/amplifiers are allowed on both the actuator and joint sides - * (depicted as timing belts in the figure). - * A transmission ratio can take any real value \e except zero. In particular: - * - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, while if its absolute - * value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. - * - Negative values represent a direction flip, ie. input and output move in opposite directions. - * - Important: Use transmission ratio signs to match this class' convention of positive actuator/joint - * directions with a given mechanical design, as they will in general not match. + * - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, + * respectively. + * - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space + * variables, respectively. + * - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position + * coordinates (cf. SimpleTransmission class documentation for a more detailed description of this + * variable). + * - \f$ n \f$ represents a transmission ratio. Reducers/amplifiers are allowed on both the actuator + * and joint sides (depicted as timing belts in the figure). A transmission ratio can take any real + * value \e except zero. In particular: + * - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, + * while if its absolute value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. + * - Negative values represent a direction flip, ie. input and output move in opposite + * directions. + * - Important: Use transmission ratio signs to match this class' convention of positive + * actuator/joint directions with a given mechanical design, as they will in general not match. * - * \note This implementation currently assumes a specific layout for location of the actuators and joint axes which is - * common in robotic mechanisms. Please file an enhancement ticket if your use case does not adhere to this layout. + * \note This implementation currently assumes a specific layout for location of the actuators and + * joint axes which is common in robotic mechanisms. Please file an enhancement ticket if your use + * case does not adhere to this layout. * * \ingroup transmission_types */ @@ -126,14 +130,16 @@ class DifferentialTransmission : public Transmission /// Transform variables from actuator to joint space. /** * \pre Actuator and joint vectors must have size 2 and point to valid data. - * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. + * To call this method it is not required that all other data vectors contain valid data, and can + * even remain empty. */ void actuator_to_joint() override; /// Transform variables from joint to actuator space. /** * \pre Actuator and joint vectors must have size 2 and point to valid data. - * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. + * To call this method it is not required that all other data vectors contain valid data, and can + * even remain empty. */ void joint_to_actuator() override; diff --git a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.hpp b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.hpp index b8eb05e8d3..39f5df6f61 100644 --- a/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.hpp +++ b/transmission_interface/include/transmission_interface/four_bar_linkage_transmission.hpp @@ -29,77 +29,80 @@ namespace transmission_interface { /// Implementation of a four-bar-linkage transmission. /** -* -* This transmission relates two actuators and two joints through a mechanism in which the state of the -* first joint only depends on the first actuator, while the second joint depends on both actuators, as -* illustrated below. -* Although the class name makes specific reference to the four-bar-linkage, there are other mechanical layouts -* that yield the same behavior, such as the remote actuation example also depicted below. -* \image html four_bar_linkage_transmission.png -* -*
-* -* -* -* -* -* -* -* -* -* -*
Effort
Velocity
Position
-* Actuator to joint -* -* \f{eqnarray*}{ -* \tau_{j_1} & = & n_{j_1} n_{a_1} \tau_{a_1} \\ -* \tau_{j_2} & = & n_{j_2} (n_{a_2} \tau_{a_2} - n_{j_1} n_{a_1} \tau_{a_1}) -* \f} -* -* \f{eqnarray*}{ -* \dot{x}_{j_1} & = & \frac{ \dot{x}_{a_1} }{ n_{j_1} n_{a_1} } \\ -* \dot{x}_{j_2} & = & \frac{ \dot{x}_{a_2} / n_{a_2} - \dot{x}_{a_1} / (n_{j_1} n_{a_1}) }{ n_{j_2} } -* \f} -* -* \f{eqnarray*}{ -* x_{j_1} & = & \frac{ x_{a_1} }{ n_{j_1} n_{a_1} } + x_{off_1} \\ -* x_{j_2} & = & \frac{ x_{a_2} / n_{a_2} - x_{a_1} / (n_{j_1} n_{a_1}) }{ n_{j_2} } + x_{off_2} -* \f} -*
-* Joint to actuator -* -* \f{eqnarray*}{ -* \tau_{a_1} & = & \tau_{j_1} / (n_{j_1} n_{a_1}) \\ -* \tau_{a_2} & = & \frac{ \tau_{j_1} + \tau_{j_2} / n_{j_2} }{ n_{a_2} } -* \f} -* -* \f{eqnarray*}{ -* \dot{x}_{a_1} & = & n_{j_1} n_{a_1} \dot{x}_{j_1} \\ -* \dot{x}_{a_2} & = & n_{a_2} (\dot{x}_{j_1} + n_{j_2} \dot{x}_{j_2}) -* \f} -* -* \f{eqnarray*}{ -* x_{a_1} & = & n_{j_1} n_{a_1} (x_{j_1} - x_{off_1}) \\ -* x_{a_2} & = & n_{a_2} \left[(x_{j_1} - x_{off_1}) + n_{j_2} (x_{j_2} - x_{off_2})\right] -* \f} -*
-*
-* -* where: -* - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, respectively. -* - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space variables, respectively. -* - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position coordinates. -* (cf. SimpleTransmission class documentation for a more detailed description of this variable). -* - \f$ n \f$ represents a transmission ratio (reducers/amplifiers are depicted as timing belts in the figure). -* A transmission ratio can take any real value \e except zero. In particular: -* - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, while if its absolute -* value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. -* - Negative values represent a direction flip, ie. input and output move in opposite directions. -* - Important: Use transmission ratio signs to match this class' convention of positive actuator/joint -* directions with a given mechanical design, as they will in general not match. -* -* \ingroup transmission_types -*/ + * + * This transmission relates two actuators and two joints through a mechanism in which + * the state of the first joint only depends on the first actuator, while the second joint depends + * on both actuators, as illustrated below. Although the class name makes specific reference to the + * four-bar-linkage, there are other mechanical layouts that yield the same behavior, such as the + * remote actuation example also depicted below. \image html four_bar_linkage_transmission.png + * + *
+ * + * + * + * + * + * + * + * + * + * + *
Effort
Velocity
Position
+ * Actuator to joint + * + * \f{eqnarray*}{ + * \tau_{j_1} & = & n_{j_1} n_{a_1} \tau_{a_1} \\ + * \tau_{j_2} & = & n_{j_2} (n_{a_2} \tau_{a_2} - n_{j_1} n_{a_1} \tau_{a_1}) + * \f} + * + * \f{eqnarray*}{ + * \dot{x}_{j_1} & = & \frac{ \dot{x}_{a_1} }{ n_{j_1} n_{a_1} } \\ + * \dot{x}_{j_2} & = & \frac{ \dot{x}_{a_2} / n_{a_2} - \dot{x}_{a_1} / (n_{j_1} n_{a_1}) }{ n_{j_2} + * } \f} + * + * \f{eqnarray*}{ + * x_{j_1} & = & \frac{ x_{a_1} }{ n_{j_1} n_{a_1} } + x_{off_1} \\ + * x_{j_2} & = & \frac{ x_{a_2} / n_{a_2} - x_{a_1} / (n_{j_1} n_{a_1}) }{ n_{j_2} } + x_{off_2} + * \f} + *
+ * Joint to actuator + * + * \f{eqnarray*}{ + * \tau_{a_1} & = & \tau_{j_1} / (n_{j_1} n_{a_1}) \\ + * \tau_{a_2} & = & \frac{ \tau_{j_1} + \tau_{j_2} / n_{j_2} }{ n_{a_2} } + * \f} + * + * \f{eqnarray*}{ + * \dot{x}_{a_1} & = & n_{j_1} n_{a_1} \dot{x}_{j_1} \\ + * \dot{x}_{a_2} & = & n_{a_2} (\dot{x}_{j_1} + n_{j_2} \dot{x}_{j_2}) + * \f} + * + * \f{eqnarray*}{ + * x_{a_1} & = & n_{j_1} n_{a_1} (x_{j_1} - x_{off_1}) \\ + * x_{a_2} & = & n_{a_2} \left[(x_{j_1} - x_{off_1}) + n_{j_2} (x_{j_2} - x_{off_2})\right] + * \f} + *
+ *
+ * + * where: + * - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, + * respectively. + * - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space + * variables, respectively. + * - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position + * coordinates. (cf. SimpleTransmission class documentation for a more detailed description of this + * variable). + * - \f$ n \f$ represents a transmission ratio (reducers/amplifiers are depicted as timing belts in + * the figure). A transmission ratio can take any real value \e except zero. In particular: + * - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, + * while if its absolute value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. + * - Negative values represent a direction flip, ie. input and output move in opposite + * directions. + * - Important: Use transmission ratio signs to match this class' convention of positive + * actuator/joint directions with a given mechanical design, as they will in general not match. + * + * \ingroup transmission_types + */ class FourBarLinkageTransmission : public Transmission { public: @@ -125,14 +128,16 @@ class FourBarLinkageTransmission : public Transmission /// Transform variables from actuator to joint space. /** * \pre Actuator and joint vectors must have size 2 and point to valid data. - * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. + * To call this method it is not required that all other data vectors contain valid data, and can + * even remain empty. */ void actuator_to_joint() override; /// Transform variables from joint to actuator space. /** * \pre Actuator and joint vectors must have size 2 and point to valid data. - * To call this method it is not required that all other data vectors contain valid data, and can even remain empty. + * To call this method it is not required that all other data vectors contain valid data, and can + * even remain empty. */ void joint_to_actuator() override; diff --git a/transmission_interface/include/transmission_interface/simple_transmission.hpp b/transmission_interface/include/transmission_interface/simple_transmission.hpp index a74cc3dddd..809472ab75 100644 --- a/transmission_interface/include/transmission_interface/simple_transmission.hpp +++ b/transmission_interface/include/transmission_interface/simple_transmission.hpp @@ -28,9 +28,9 @@ namespace transmission_interface { /// Implementation of a simple reducer transmission. /** - * This transmission relates one actuator and one joint through a reductor (or amplifier). - * Timing belts and gears are examples of this transmission type, and are illustrated below. - * \image html simple_transmission.png + * This transmission relates one actuator and one joint through a reductor (or + * amplifier). Timing belts and gears are examples of this transmission type, and are illustrated + * below. \image html simple_transmission.png * *
* @@ -63,17 +63,20 @@ namespace transmission_interface * * * where: - * - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, respectively. - * - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space variables, respectively. - * - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position coordinates. - * - \f$ n \f$ is the transmission ratio, and can be computed as the ratio between the output and input pulley - * radii for the timing belt; or the ratio between output and input teeth for the gear system. - * The transmission ratio can take any real value \e except zero. In particular: - * - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, while if its absolute - * value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. - * - Negative values represent a direction flip, ie. actuator and joint move in opposite directions. For example, - * in timing belts actuator and joint move in the same direction, while in single-stage gear systems actuator and - * joint move in opposite directions. + * - \f$ x \f$, \f$ \dot{x} \f$ and \f$ \tau \f$ are position, velocity and effort variables, + * respectively. + * - Subindices \f$ _a \f$ and \f$ _j \f$ are used to represent actuator-space and joint-space + * variables, respectively. + * - \f$ x_{off}\f$ represents the offset between motor and joint zeros, expressed in joint position + * coordinates. + * - \f$ n \f$ is the transmission ratio, and can be computed as the ratio between the output and + * input pulley radii for the timing belt; or the ratio between output and input teeth for the gear + * system. The transmission ratio can take any real value \e except zero. In particular: + * - If its absolute value is greater than one, it's a velocity reducer / effort amplifier, + * while if its absolute value lies in \f$ (0, 1) \f$ it's a velocity amplifier / effort reducer. + * - Negative values represent a direction flip, ie. actuator and joint move in opposite + * directions. For example, in timing belts actuator and joint move in the same direction, while in + * single-stage gear systems actuator and joint move in opposite directions. * * \ingroup transmission_types */ @@ -102,14 +105,16 @@ class SimpleTransmission : public Transmission /// Transform variables from actuator to joint space. /** * This method operates on the handles provided when configuring the transmission. - * To call this method it is not required that all supported interface types are provided, e.g. one can supply only velocity handles + * To call this method it is not required that all supported interface types are provided, e.g. + * one can supply only velocity handles */ void actuator_to_joint() override; /// Transform variables from joint to actuator space. /** * This method operates on the handles provided when configuring the transmission. - * To call this method it is not required that all supported interface types are provided, e.g. one can supply only velocity handles + * To call this method it is not required that all supported interface types are provided, e.g. + * one can supply only velocity handles */ void joint_to_actuator() override; diff --git a/transmission_interface/include/transmission_interface/transmission.hpp b/transmission_interface/include/transmission_interface/transmission.hpp index 8ca0196c4c..697e1a4eb7 100644 --- a/transmission_interface/include/transmission_interface/transmission.hpp +++ b/transmission_interface/include/transmission_interface/transmission.hpp @@ -26,21 +26,23 @@ namespace transmission_interface { /// Abstract base class for representing mechanical transmissions. /** - * Mechanical transmissions transform effort/flow variables such that their product (power) remains constant. - * Effort variables for linear and rotational domains are \e force and \e torque; while the flow variables are - * respectively linear velocity and angular velocity. + * Mechanical transmissions transform effort/flow variables such that their product (power) remains + * constant. Effort variables for linear and rotational domains are \e force and \e torque; while + * the flow variables are respectively linear velocity and angular velocity. * - * In robotics it is customary to place transmissions between actuators and joints. This interface adheres to this - * naming to identify the input and output spaces of the transformation. - * The provided interfaces allow bidirectional mappings between actuator and joint spaces for effort, velocity and - * position. Position is not a power variable, but the mappings can be implemented using the velocity map plus an - * integration constant representing the offset between actuator and joint zeros. + * In robotics it is customary to place transmissions between actuators and joints. This interface + * adheres to this naming to identify the input and output spaces of the transformation. The + * provided interfaces allow bidirectional mappings between actuator and joint spaces for effort, + * velocity and position. Position is not a power variable, but the mappings can be implemented + * using the velocity map plus an integration constant representing the offset between actuator and + * joint zeros. * * \par Credit - * This interface was inspired by similar existing implementations by PAL Robotics, S.L. and Willow Garage Inc. + * This interface was inspired by similar existing implementations by PAL Robotics, S.L. and Willow + * Garage Inc. * - * \note Implementations of this interface must take care of realtime-safety if the code is to be run in realtime - * contexts, as is often the case in robot control. + * \note Implementations of this interface must take care of realtime-safety if the code is to be + * run in realtime contexts, as is often the case in robot control. */ class Transmission { @@ -55,20 +57,20 @@ class Transmission /** * \param[in] act_data Actuator-space variables. * \param[out] jnt_data Joint-space variables. - * \pre All non-empty vectors must contain valid data and their size should be consistent with the number of - * transmission actuators and joints. - * Data vectors not used in this map can remain empty. + * \pre All non-empty vectors must contain valid data and their size should be consistent with the + * number of transmission actuators and joints. Data vectors not used in this map can remain + * empty. */ virtual void actuator_to_joint() = 0; /// Transform \e effort variables from joint to actuator space. /** - * \param[in] jnt_data Joint-space variables. - * \param[out] act_data Actuator-space variables. - * \pre All non-empty vectors must contain valid data and their size should be consistent with the number of - * transmission actuators and joints. - * Data vectors not used in this map can remain empty. - */ + * \param[in] jnt_data Joint-space variables. + * \param[out] act_data Actuator-space variables. + * \pre All non-empty vectors must contain valid data and their size should be consistent with the + * number of transmission actuators and joints. Data vectors not used in this map can remain + * empty. + */ virtual void joint_to_actuator() = 0; /** \return Number of actuators managed by transmission, diff --git a/transmission_interface/package.xml b/transmission_interface/package.xml index 99d864bf6a..9e2b2fded2 100644 --- a/transmission_interface/package.xml +++ b/transmission_interface/package.xml @@ -2,7 +2,7 @@ transmission_interface - 3.13.0 + 3.18.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 diff --git a/transmission_interface/test/random_generator_utils.hpp b/transmission_interface/test/random_generator_utils.hpp index e6088f1b2f..fbacd1ba3b 100644 --- a/transmission_interface/test/random_generator_utils.hpp +++ b/transmission_interface/test/random_generator_utils.hpp @@ -31,7 +31,7 @@ struct RandomDoubleGenerator public: RandomDoubleGenerator(double min_val, double max_val) : min_val_(min_val), max_val_(max_val) { - srand(time(nullptr)); + srand(static_cast(time(nullptr))); } double operator()() {