[
  {
    "path": ".clang-format",
    "content": "---\nLanguage: Cpp\nBasedOnStyle: Google\n\nAccessModifierOffset: -2\nAlignAfterOpenBracket: AlwaysBreak\nBreakBeforeBraces: Allman\nColumnLimit: 100\nConstructorInitializerIndentWidth: 0\nContinuationIndentWidth: 2\nIndentWidth: 2\nTabWidth: 2\nDerivePointerAlignment: false\nPointerAlignment: Middle\nReflowComments: true\nIncludeBlocks: Preserve\n...\n"
  },
  {
    "path": ".codespellignore",
    "content": "ons\n"
  },
  {
    "path": ".github/ISSUE_TEMPLATE/bug_report.md",
    "content": "---\nname: Bug report\nabout: Create a report to help us improve\ntitle: ''\nlabels: bug\nassignees: ''\n\n---\n\n**Describe the bug**\nA clear and concise description of what the bug is.\n\n**To Reproduce**\nSteps to reproduce the behavior\n\n**Expected behavior**\nA clear and concise description of what you expected to happen.\n\n**Logs**\n\n**Setup:**\n - Device:\n - OS:\n - ROS-Distro:\n - Branch/Commit:\n\n**Additional context**\nAdd any other context about the problem here.\n"
  },
  {
    "path": ".github/ISSUE_TEMPLATE/feature_request.md",
    "content": "---\nname: Feature request\nabout: Suggest an idea for this project\ntitle: ''\nlabels: enhancement\nassignees: ''\n\n---\n\n**Is your feature request related to a problem? Please describe.**\nA clear and concise description of what the problem is. Ex. I'm always frustrated when [...]\n\n**Describe the solution you'd like**\nA clear and concise description of what you want to happen.\n\n**Describe alternatives you've considered**\nA clear and concise description of any alternative solutions or features you've considered.\n\n**Additional context**\nAdd any other context or screenshots about the feature request here.\n"
  },
  {
    "path": ".github/ISSUE_TEMPLATE/question.md",
    "content": "---\nname: Question\nabout: Create a report to help us improve\ntitle: ''\nlabels: question\nassignees: ''\n\n---\n\n**Describe the bug**\nA clear and concise description of what the bug is.\n\n**Logs**\nAdd build or execution log for context.\n\n**Setup:**\n - Device:\n - OS:\n - ROS-Distro:\n - Branch/Commit:\n\n**Additional context**\nAdd any other context about the problem here.\n"
  },
  {
    "path": ".github/dependabot.yaml",
    "content": "# Set update schedule for GitHub Actions\n\nversion: 2\nupdates:\n\n  - package-ecosystem: \"github-actions\"\n    directory: \"/\"\n    schedule:\n      # Check for updates to GitHub Actions every week\n      interval: \"weekly\"\n"
  },
  {
    "path": ".github/workflows/ci-format.yml",
    "content": "# This is a format job. Pre-commit has a first-party GitHub action, so we use\n# that: https://github.com/pre-commit/action\n\nname: Pre-commit Format\n\non:\n  workflow_dispatch:\n  pull_request:\n\njobs:\n  pre-commit:\n    name: Format\n    runs-on: ubuntu-22.04\n    steps:\n    - uses: actions/checkout@v6\n    - uses: actions/setup-python@v6\n      with:\n        python-version: 3.10.6\n    - name: Install system hooks\n      run: sudo apt update && sudo apt install -qq clang-format-14 cppcheck\n    - uses: pre-commit/action@v3.0.1\n      with:\n        extra_args: --all-files --hook-stage manual\n"
  },
  {
    "path": ".github/workflows/ci-ros-lint.yml.backup",
    "content": "name: ROS Lint\non:\n  pull_request:\n\njobs:\n  ament_lint:\n    name: ament_${{ matrix.linter }}\n    runs-on: ubuntu-20.04\n    strategy:\n      fail-fast: false\n      matrix:\n          linter: [cppcheck, copyright, lint_cmake]\n    steps:\n    - uses: actions/checkout@v3\n    - uses: ros-tooling/setup-ros@v0.2\n    - uses: ros-tooling/action-ros-lint@v0.1\n      with:\n        distribution: rolling\n        linter: ${{ matrix.linter }}\n        package-name:\n          $PKG_NAME$\n\n  ament_lint_100:\n    name: ament_${{ matrix.linter }}\n    runs-on: ubuntu-20.04\n    strategy:\n      fail-fast: false\n      matrix:\n          linter: [cpplint]\n    steps:\n    - uses: actions/checkout@v3\n    - uses: ros-tooling/setup-ros@v0.2\n    - uses: ros-tooling/action-ros-lint@v0.1\n      with:\n        distribution: rolling\n        linter: cpplint\n        arguments: \"--linelength=100 --filter=-whitespace/newline\"\n        package-name:\n          ros2_canopen\n"
  },
  {
    "path": ".github/workflows/docker.yml",
    "content": "name: Create and publish a Docker image\non:\n  push:\n    branches: ['master']\n  workflow_dispatch:\n\nenv:\n  REGISTRY: ghcr.io\n  IMAGE_NAME: ${{ github.repository }}\n\njobs:\n  build-and-push-image:\n    runs-on: ubuntu-22.04\n\n    permissions:\n      contents: read\n      packages: write\n\n    steps:\n      - name: Checkout repository\n        uses: actions/checkout@v6\n      - name: Log in to the Container registry\n        uses: docker/login-action@v4\n        with:\n          registry: ${{ env.REGISTRY }}\n          username: ${{ github.actor }}\n          password: ${{ secrets.GITHUB_TOKEN }}\n\n      - name: Extract metadata (tags, labels) for Docker\n        id: meta\n        uses: docker/metadata-action@v6\n        with:\n          images: ${{ env.REGISTRY }}/${{ env.IMAGE_NAME }}\n\n      - name: Build and push Docker image\n        uses: docker/build-push-action@v7\n        with:\n          context: .\n          push: true\n          tags: ${{ steps.meta.outputs.tags }}\n          labels: ${{ steps.meta.outputs.labels }}\n"
  },
  {
    "path": ".github/workflows/humble.yml",
    "content": "name: Industrial CI Humble\r\n\r\non:\r\n  push:\r\n    branches: [ humble ]\r\n  pull_request:\r\n    branches: [ humble ]\r\n  workflow_dispatch:\r\n\r\njobs:\r\n  industrial_ci:\r\n    name: ROS ${{ matrix.ROS_DISTRO }} (${{ matrix.ROS_REPO }})\r\n    runs-on: ubuntu-22.04\r\n    strategy:\r\n      fail-fast: false\r\n      matrix:\r\n        ROS_DISTRO: [humble]\r\n        ROS_REPO: [testing]\r\n    env:\r\n      CCACHE_DIR: \"${{ github.workspace }}/.ccache\"\r\n    steps:\r\n      - uses: actions/checkout@v6\r\n      - uses: actions/cache@v4\r\n        with:\r\n          path: ${{ env.CCACHE_DIR }}\r\n          key: ccache-${{ matrix.ROS_DISTRO }}-${{ matrix.ROS_REPO }}-${{github.run_id}}\r\n          restore-keys: |\r\n            ccache-${{ matrix.ROS_DISTRO }}-${{ matrix.ROS_REPO }}-\r\n      - uses: 'ros-industrial/industrial_ci@master'\r\n        env:\r\n          BEFORE_INSTALL_TARGET_DEPENDENCIES: 'sudo apt-get update'\r\n          ROS_DISTRO: ${{ matrix.ROS_DISTRO }}\r\n          ROS_REPO: ${{ matrix.ROS_REPO }}\r\n"
  },
  {
    "path": ".github/workflows/humble_documentation.yml",
    "content": "name: Documentation Humble\n\n# Controls when the workflow will run\non:\n  # Triggers the workflow on push or pull request events but only for the master branch\n  push:\n    branches: [ humble ]\n    paths:\n      - 'canopen/**'\n      - '.github/workflows/humble_documentation.yml'\n\n  # Allows you to run this workflow manually from the Actions tab\n  workflow_dispatch:\n\n# A workflow run is made up of one or more jobs that can run sequentially or in parallel\njobs:\n  # This workflow contains a single job called \"build\"\n  build_documentation:\n    # The type of runner that the job will run on\n    runs-on: ubuntu-22.04\n\n    # Steps represent a sequence of tasks that will be executed as part of the job\n    steps:\n      # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it\n      - uses: actions/checkout@v6\n\n      - name: Install dependencies\n        run: |\n            sudo apt-get update -qq\n            sudo apt-get install -y -qq doxygen graphviz plantuml\n            pip install sphinx-rtd-theme\n            pip install sphinxcontrib-plantuml\n            pip install sphinx-mdinclude\n            pip install breathe\n            pip install exhale\n\n      - name: Build doxygen\n        run: |\n            cd ./canopen/doxygen/\n            doxygen\n            cd ../..\n\n      - name: Build documentation\n        run: |\n            cd ./canopen/sphinx/\n            make html\n            cd ../..\n\n      - name: Create commit\n        run: |\n            git clone https://github.com/ros-industrial/ros2_canopen.git --branch gh-pages --single-branch gh-pages\n            mkdir -p gh-pages/manual/humble/\n            mkdir -p gh-pages/api/humble/\n            cp -r ./canopen/sphinx/_build/html/* gh-pages/manual/humble/\n            cp -r ./canopen/doxygen/_build/html/* gh-pages/api/humble/\n            cd gh-pages\n            git config --local user.email \"action@github.com\"\n            git config --local user.name \"GitHub Action\"\n            git add .\n            git commit -m \"Update documentation\" -a || true\n\n      - name: Push changes\n        uses: ad-m/github-push-action@master\n        with:\n          branch: gh-pages\n          directory: gh-pages\n          github_token: ${{ secrets.GITHUB_TOKEN }}\n"
  },
  {
    "path": ".github/workflows/prerelease-rolling.yml",
    "content": "name: Prerelease-Test Rolling\n\non:\n  workflow_dispatch:\n  push:\n    tags:\n      - \"*\"\n\njobs:\n  industrial_ci:\n    name: ROS ${{ matrix.ROS_DISTRO }} (${{ matrix.ROS_REPO }})\n    runs-on: ubuntu-22.04\n    strategy:\n      fail-fast: false\n      matrix:\n        ROS_DISTRO: [rolling]\n        ROS_REPO: [testing]\n    steps:\n      - uses: actions/checkout@v6\n      - uses: 'ros-industrial/industrial_ci@master'\n        env:\n          BEFORE_INSTALL_TARGET_DEPENDENCIES: 'sudo apt-get update'\n          AFTER_BUILD_TARGET_WORKSPACE: 'set +u && COLCON_TRACE=0 AMENT_TRACE_SETUP_FILES=0 source /root/target_ws/install/setup.bash && set -u'\n          ROS_DISTRO: ${{ matrix.ROS_DISTRO }}\n          ROS_REPO: ${{ matrix.ROS_REPO }}\n          PRERELEASE: true\n"
  },
  {
    "path": ".github/workflows/rolling.yml",
    "content": "name: Industrial CI\r\n\r\non:\r\n  push:\r\n    branches: [ master ]\r\n  pull_request:\r\n    branches: [ master ]\r\n  workflow_dispatch:\r\n\r\njobs:\r\n  industrial_ci:\r\n    name: ROS ${{ matrix.ROS_DISTRO }} (${{ matrix.ROS_REPO }})\r\n    runs-on: ubuntu-24.04\r\n    strategy:\r\n      fail-fast: false\r\n      matrix:\r\n        include:\r\n          - ROS_DISTRO: rolling\r\n            ROS_REPO: testing\r\n          - ROS_DISTRO: jazzy\r\n            ROS_REPO: testing\r\n          - ROS_DISTRO: kilted\r\n            ROS_REPO: testing\r\n    env:\r\n      CCACHE_DIR: \"${{ github.workspace }}/.ccache\"\r\n    steps:\r\n      - uses: actions/checkout@v6\r\n      - uses: actions/cache@v4\r\n        with:\r\n          path: ${{ env.CCACHE_DIR }}\r\n          key: ccache-${{ matrix.ROS_DISTRO }}-${{ matrix.ROS_REPO }}-${{github.run_id}}\r\n          restore-keys: |\r\n            ccache-${{ matrix.ROS_DISTRO }}-${{ matrix.ROS_REPO }}-\r\n      - uses: 'ros-industrial/industrial_ci@master'\r\n        if: ${{ github.event_name != 'pull_request' || matrix.ROS_DISTRO == 'rolling' }}\r\n        env:\r\n          BEFORE_INSTALL_TARGET_DEPENDENCIES: 'sudo apt-get update'\r\n          AFTER_BUILD_TARGET_WORKSPACE: 'set +u && COLCON_TRACE=0 AMENT_TRACE_SETUP_FILES=0 source /root/target_ws/install/setup.bash && set -u'\r\n          ROS_DISTRO: ${{ matrix.ROS_DISTRO }}\r\n          ROS_REPO: ${{ matrix.ROS_REPO }}\r\n          PRERELEASE: false\r\n"
  },
  {
    "path": ".github/workflows/rolling_documentation.yml",
    "content": "name: Documentation\n\n# Controls when the workflow will run\non:\n  # Triggers the workflow on push or pull request events but only for the master branch\n  push:\n    branches: [ master ]\n    paths:\n      - 'canopen/**'\n      - '.github/workflows/rolling_documentation.yml'\n\n  # Allows you to run this workflow manually from the Actions tab\n  workflow_dispatch:\n\n# A workflow run is made up of one or more jobs that can run sequentially or in parallel\njobs:\n  # This workflow contains a single job called \"build\"\n  build_documentation:\n    # The type of runner that the job will run on\n    runs-on: ubuntu-24.04\n    strategy:\n      fail-fast: false\n      matrix:\n        ROS_DISTRO: [rolling, jazzy, kilted]\n\n    # Steps represent a sequence of tasks that will be executed as part of the job\n    steps:\n      # Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it\n      - uses: actions/checkout@v6\n\n      - name: Install dependencies\n        run: |\n            sudo apt-get update -qq\n            sudo apt-get install -y -qq doxygen graphviz plantuml\n            pip install sphinx-rtd-theme\n            pip install sphinxcontrib-plantuml\n            pip install sphinx-mdinclude\n            pip install breathe\n            pip install exhale\n\n      - name: Build doxygen\n        run: |\n            cd ./canopen/doxygen/\n            doxygen\n            cd ../..\n\n      - name: Build documentation\n        run: |\n            cd ./canopen/sphinx/\n            make html\n            cd ../..\n\n      - name: Create commit\n        run: |\n            git clone https://github.com/ros-industrial/ros2_canopen.git --branch gh-pages --single-branch gh-pages\n            mkdir -p gh-pages/manual/${{ matrix.ROS_DISTRO }}/\n            mkdir -p gh-pages/api/${{ matrix.ROS_DISTRO }}/\n            cp -r ./canopen/sphinx/_build/html/* gh-pages/manual/${{ matrix.ROS_DISTRO }}/\n            cp -r ./canopen/doxygen/_build/html/* gh-pages/api/${{ matrix.ROS_DISTRO }}/\n            cd gh-pages\n            git config --local user.email \"action@github.com\"\n            git config --local user.name \"GitHub Action\"\n            git add .\n            git commit -m \"Update documentation\" -a || true\n\n      - name: Push changes\n        uses: ad-m/github-push-action@master\n        with:\n          branch: gh-pages\n          directory: gh-pages\n          github_token: ${{ secrets.GITHUB_TOKEN }}\n"
  },
  {
    "path": ".gitignore",
    "content": ".vscode/\n**/doc_output/\n**/__pycache__/\n**/_build\n**/api\n"
  },
  {
    "path": ".pre-commit-config.yaml",
    "content": "# To use:\n#\n#     pre-commit run -a\n#\n# Or:\n#\n#     pre-commit install  # (runs every time you commit in git)\n#\n# To update this file:\n#\n#     pre-commit autoupdate\n#\n# See https://github.com/pre-commit/pre-commit\nexclude: '.*\\.patch'\nrepos:\n  # Standard hooks\n  - repo: https://github.com/pre-commit/pre-commit-hooks\n    rev: v4.6.0\n    hooks:\n      - id: check-added-large-files\n      - id: check-ast\n      - id: check-case-conflict\n      - id: check-docstring-first\n      - id: check-merge-conflict\n      - id: check-symlinks\n      - id: check-xml\n      - id: check-yaml\n        exclude: canopen_core/test/bus_configs/bad_driver_duplicate.yml\n      - id: debug-statements\n      - id: end-of-file-fixer\n      - id: mixed-line-ending\n      - id: trailing-whitespace\n      - id: fix-byte-order-marker\n\n  # Python hooks\n  - repo: https://github.com/asottile/pyupgrade\n    rev: v3.17.0\n    hooks:\n    -   id: pyupgrade\n        args: [--py36-plus]\n\n  - repo: https://github.com/psf/black\n    rev: 24.8.0\n    hooks:\n      - id: black\n        args: [\"--line-length=99\"]\n\n  # CPP hooks\n  - repo: local\n    hooks:\n      - id: clang-format\n        name: clang-format\n        description: Format files with ClangFormat.\n        entry: clang-format-14\n        language: system\n        files: \\.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$\n        args: ['-fallback-style=none', '-i']\n\n  # Cmake hooks\n  # - repo: local\n  #   hooks:\n  #     - id: ament_lint_cmake\n  #       name: ament_lint_cmake\n  #       description: Check format of CMakeLists.txt files.\n  #       stages: [commit]\n  #       entry: ament_lint_cmake\n  #       language: system\n  #       files: CMakeLists\\.txt$\n  #       exclude: lely_core_libraries\\/CMakeLists\\.txt$\n\n  # # Copyright\n  - repo: local\n    hooks:\n      - id: ament_copyright\n        name: ament_copyright\n        description: Check if copyright notice is available in all files.\n        stages: [commit]\n        entry: ament_copyright\n        args: [\"--add-missing\", \"ROS-Industrial\", \"apache2\"]\n        language: system\n\n  # Docs - RestructuredText hooks\n  - repo: https://github.com/PyCQA/doc8\n    rev: v1.1.1\n    hooks:\n      - id: doc8\n        args: ['--max-line-length=100', '--ignore=D001']\n        exclude: CHANGELOG\\.rst$\n\n  - repo: https://github.com/pre-commit/pygrep-hooks\n    rev: v1.10.0\n    hooks:\n      - id: rst-backticks\n        exclude: CHANGELOG\\.rst$\n      - id: rst-directive-colons\n      - id: rst-inline-touching-normal\n\n  # Spellcheck in comments and docs\n  # skipping of *.svg files is not working...\n  - repo: https://github.com/codespell-project/codespell\n    rev: v2.2.1\n    hooks:\n      - id: codespell\n        args: ['--write-changes', '-I', '.codespellignore']\n        exclude: CHANGELOG\\.rst|\\.(svg|pyc|drawio|dcf|eds)$\n"
  },
  {
    "path": "Dockerfile",
    "content": "FROM ros:rolling-ros-core\n\n\nRUN apt-get update \\\n    && apt-get install -y \\\n        python3-rosdep \\\n        python3-argcomplete \\\n        python3-colcon-common-extensions \\\n        build-essential \\\n        pkg-config \\\n        python3-wheel\n\nWORKDIR /home/can_ws/src\nCOPY . ros2_canopen\n\nWORKDIR /home/can_ws/\nRUN . /opt/ros/rolling/setup.sh \\\n    && rosdep init && rosdep update \\\n    && rosdep install --from-paths src --ignore-src -r -y \\\n    && colcon build \\\n    && . install/setup.sh\n"
  },
  {
    "path": "README.md",
    "content": "# ROS2 CANopen\n\n## Status\n\n| Build Process | Status |\n|---------------|--------|\n| Industrial CI Build | [![Industrial CI](https://github.com/ros-industrial/ros2_canopen/actions/workflows/rolling.yml/badge.svg)](https://github.com/ros-industrial/ros2_canopen/actions/workflows/rolling.yml) |\n| Documentation Build | [![Documentation](https://github.com/ros-industrial/ros2_canopen/actions/workflows/rolling_documentation.yml/badge.svg)](https://github.com/ros-industrial/ros2_canopen/actions/workflows/rolling_documentation.yml) |\n| Buildfarm Build (rolling) | [![Buildfarm Status](https://build.ros2.org/job/Rdev__ros2_canopen__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Rdev__ros2_canopen__ubuntu_noble_amd64/) |\n| Buildfarm Build (kilted) | [![Buildfarm Status](https://build.ros2.org/job/Kdev__ros2_canopen__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Kdev__ros2_canopen__ubuntu_noble_amd64/) |\n| Buildfarm Build (jazzy) | [![Buildfarm Status](https://build.ros2.org/job/Jdev__ros2_canopen__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Jdev__ros2_canopen__ubuntu_noble_amd64/) |\n\nThe stack is currently under development and not yet ready for production use.\n\n## Documentation\nThe documentation consists of two parts: a manual and an api reference.\nThe documentation is built for rolling (master), kilted, jazzy, iron and humble and hosted on github pages.\nOlder ROS 2 releases are EOL and are not supported anymore.\n\n***Note:** Master branch works with ROS2 **Jazzy**, **Kilted** and **Rolling** distributions. For **Humble** distribution use the `humble` branch.*\n\n### Rolling\n* Manual: https://ros-industrial.github.io/ros2_canopen/manual/rolling/\n* API reference: https://ros-industrial.github.io/ros2_canopen/api/rolling/\n\n### Humble\n* Manual: https://ros-industrial.github.io/ros2_canopen/manual/humble/\n* API reference: https://ros-industrial.github.io/ros2_canopen/api/humble/\n\n## Features\nThese are some of the features this stack implements. For further information please refer to the documentation.\n\n* **YAML-Bus configuration**\n  This canopen stack enables you to configure the bus using a YAML file. In this file you define the nodes that are connected to the bus by specifying their node id, the corresponding EDS file and the driver to run for the node. You can also specify further parameters that overwrite EDS parameters or are inputs to the driver.\n* **Service based operation**\n  The stack can be operated using standard ROS2 nodes. In this case the device container will load the drivers for master and slave nodes. Each driver will be visible as a\n  node and expose a ROS 2 interface. All drivers are brought up when the device manager is launched.\n* **Managed service based operation**\n  The stack can be opeprated using managed ROS2 nodes. In\n  this case the device container will load the drivers for master and slave nodes based on the bus configuration. Each driver will be a lifecycle node and expose a ROS 2 interface. The lifecycle manager can be used to bring all\n  device up and down in the correct sequence.\n* **ROS2 control based operation**\n  Currently, multiple ros2_control interfaces are available. These can be used for controlling CANopen devices. The interfaces are:\n  * canopen_ros2_control/CANopenSystem\n  * canopen_ros2_control/CIA402System\n  * canopen_ros2_control/RobotSystem\n* **CANopen drivers**\n  Currently, the following drivers are available:\n    * ProxyDriver\n    * Cia402Driver\n\n\n## Post testing\nTo test stack after it was built from source you should first setup a virtual can network.\n```bash\nsudo modprobe vcan\nsudo ip link add dev vcan0 type vcan\nsudo ip link set vcan0 txqueuelen 1000\nsudo ip link set up vcan0\n```\nThen you can launch a managed example\n```bash\nros2 launch canopen_tests cia402_lifecycle_setup.launch.py\nros2 lifecycle set /lifecycle_manager configure\nros2 lifecycle set /lifecycle_manager activate\n```\n\nOr you can launch a standard example\n```bash\nros2 launch canopen_tests cia402_setup.launch.py\n```\n\nOr you can launch a ros2_control example\n```bash\nros2 launch canopen_tests robot_control_setup.launch.py\n```\n\n## Contributing\nThis repository uses `pre-commit` for code formatting.\nThis program has to be setup locally and installed inside the repository.\nFor this execute in the repository folder following commands:\n```\nsudo apt install -y pre-commit\npre-commit install\n```\nThe checks are automatically executed before each commit.\nThis helps you to always commit well formatted code.\nTo run all the checks manually use `pre-commit run -a` command.\nFor the other options check `pre-commit --help`.\n\nIn a case of an \"emergency\" you can avoid execution of pre-commit hooks by adding `-n` flag to `git commit` command - this is NOT recommended to do if you don't know what are you doing!\n\n## Rolling Distribution (Noble & RHEL9)\n\n| Package                  | Noble (Ubuntu)                                                                                                                  | RHEL9                                                                                                                            |\n|--------------------------|---------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------|\n| canopen_interfaces       | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/) |\n| lely_core_libraries      | [![Build Status](https://build.ros2.org/job/Rbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/) |\n| canopen_core             | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_core__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_core__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/) |\n| canopen_master_driver    | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/) |\n| canopen_base_driver      | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/) |\n| canopen_proxy_driver     | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/) |\n| canopen_402_driver       | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/) |\n| canopen_ros2_control     | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/) |\n| canopen_ros2_controllers | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/) |\n| canopen_tests            | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/) |\n| canopen_utils            | [![Build Status](https://build.ros2.org/job/Rbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Rbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Rbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Rbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/) |\n\n## Kilted Distribution (Noble & RHEL9)\n| Package                  | Noble (Ubuntu)                                                                                                                  | RHEL9                                                                                                                            |\n|--------------------------|---------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------|\n| canopen_interfaces       | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/) |\n| lely_core_libraries      | [![Build Status](https://build.ros2.org/job/Kbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/) |\n| canopen_core             | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_core__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_core__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/) |\n| canopen_master_driver    | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/) |\n| canopen_base_driver      | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/) |\n| canopen_proxy_driver     | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/) |\n| canopen_402_driver       | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/) |\n| canopen_ros2_control     | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/) |\n| canopen_ros2_controllers | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/) |\n| canopen_tests            | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/) |\n| canopen_utils            | [![Build Status](https://build.ros2.org/job/Kbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Kbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Kbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Kbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/) |\n\n## Jazzy Distribution (Noble & RHEL9)\n| Package                  | Noble (Ubuntu)                                                                                                                  | RHEL9                                                                                                                            |\n|--------------------------|---------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------|\n| canopen_interfaces       | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_interfaces__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_interfaces__rhel_9_x86_64__binary/) |\n| lely_core_libraries      | [![Build Status](https://build.ros2.org/job/Jbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__lely_core_libraries__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__lely_core_libraries__rhel_9_x86_64__binary/) |\n| canopen_core             | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_core__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_core__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_core__rhel_9_x86_64__binary/) |\n| canopen_master_driver    | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_master_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_master_driver__rhel_9_x86_64__binary/) |\n| canopen_base_driver      | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_base_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_base_driver__rhel_9_x86_64__binary/) |\n| canopen_proxy_driver     | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_proxy_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_proxy_driver__rhel_9_x86_64__binary/) |\n| canopen_402_driver       | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_402_driver__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_402_driver__rhel_9_x86_64__binary/) |\n| canopen_ros2_control     | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_ros2_control__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_ros2_control__rhel_9_x86_64__binary/) |\n| canopen_ros2_controllers | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_ros2_controllers__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_ros2_controllers__rhel_9_x86_64__binary/) |\n| canopen_tests            | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_tests__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_tests__rhel_9_x86_64__binary/) |\n| canopen_utils            | [![Build Status](https://build.ros2.org/job/Jbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/badge/icon)](https://build.ros2.org/job/Jbin_uN64__canopen_utils__ubuntu_noble_amd64__binary/) | [![Build Status](https://build.ros2.org/job/Jbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/badge/icon)](https://build.ros2.org/job/Jbin_rhel_el964__canopen_utils__rhel_9_x86_64__binary/) |\n"
  },
  {
    "path": "canopen/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* add pdo 6077 torque actual value to the joint state interface as effort (`#316 <https://github.com/ros-industrial/ros2_canopen/issues/316>`_)\n* Fix configuration parsing and logging\n* Refactor on_init method for improved readability and consistency\n* Fix deprecated hardware_interface API (`#386 <https://github.com/ros-industrial/ros2_canopen/issues/386>`_)\n* Fix typos in warning messages and comments for clarity\n* `#379 <https://github.com/ros-industrial/ros2_canopen/issues/379>`_: Fix data conversion in the Lely Bridge to enable more data types and proper handling of Emcy in ros2_control\n* Return error on Emcy and add correct data conversion for Emcy\n* Fixed types handling in canopen_ros2_control and optimized debug output\n* Fixed sending values\n* `#376 <https://github.com/ros-industrial/ros2_canopen/issues/376>`_: increase boot timeout\n* `#400 <https://github.com/ros-industrial/ros2_canopen/issues/400>`_: Update controllers for ROS Rolling API changes and fix fake slave type handling\n* Refactor GetValue method to use std::type_index for type comparisons\n* `motion_generator` as shared library (`#295 <https://github.com/ros-industrial/ros2_canopen/issues/295>`_)\n* Enhance SimpleSlave class with vendor ID parsing and adjust bus configuration timeouts\n* Multiple SDO types for slaves (`#278 <https://github.com/ros-industrial/ros2_canopen/issues/278>`_)\n* Enhance command interface error handling and feedback reporting in CanopenProxyController\n* Contributors: Christoph Fröhlich, Christoph Hellmann Santos, Dr. Denis Stogl, Patrick Roncagliolo, Vishnuprasad Prachandabhanu, synsi23b\n\n0.3.1 (2025-06-23)\n------------------\n* Sync upstream 'master' into homing_timeout_pr.\n  Fix homing info message to include both offset\n  and homing timeout information.\n* Add namespacing support\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.3.0 (2024-12-12)\n------------------\n* Update CiA402 bus config docs\n* Remove set heartbeat service from master documentation (`#294 <https://github.com/ros-industrial/ros2_canopen/issues/294>`_)\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n* Add cyclic torque mode to cia402 driver and robot system controller (`#293 <https://github.com/ros-industrial/ros2_canopen/issues/293>`_)\n  * Add base functions for switching to cyclic torque mode\n  * Add cyclic torque mode as effort interface to robot_system controller\n  * Add documentation about cyclic torque mode.\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n\n0.2.12 (2024-04-22)\n-------------------\n* Merge pull request `#280 <https://github.com/ros-industrial/ros2_canopen/issues/280>`_ from ipa-vsp/fix/yaml-build-error\n  Fix undefined reference to yaml library\n* pre-commit update\n* Merge pull request `#261 <https://github.com/ros-industrial/ros2_canopen/issues/261>`_ from gsalinas/configurable-sdo-timeout\n  Configurable SDO timeout\n* 0.2.9\n* forthcoming\n* Merge pull request `#272 <https://github.com/ros-industrial/ros2_canopen/issues/272>`_ from ros-industrial/ipa-vsp-patch-1\n  Update maintainer list\n* Update package.xml\n* Merge pull request `#220 <https://github.com/ros-industrial/ros2_canopen/issues/220>`_ from ipa-vsp/feature/timeout-config\n  Add timeouts\n* Add SDO timeout to device config documentation.\n* change from 100ms to 2000ms\n* timeout for booting slave\n* Contributors: Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n* Documentation: Fix launch file spelling (`#208 <https://github.com/ros-industrial/ros2_canopen/issues/208>`_)\n* Documentation: Fix package creation command.  (`#176 <https://github.com/ros-industrial/ros2_canopen/issues/176>`_)\n  * Fix package creation\n  * Fixed bus.yml nodes list\n  * docs: fixed launch file path in instructions\n  Co-authored-by: waterlinux <water@gmail.com>\n* Contributors: Lewe Christiansen, Vishnuprasad Prachandabhanu\n\n0.2.9 (2024-04-16)\n------------------\n* Update maintainer list\n* Update package.xml\n* Add timeouts\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.2.7 (2023-06-30)\n------------------\n* Update ros2_control docs.\n* Contributors: Christoph Hellmann Santos, Dr. Denis, Xi Huang\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Borong Yuan, Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen NONE)\nfind_package(ament_cmake REQUIRED)\nament_package()\n"
  },
  {
    "path": "canopen/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen/doxygen/Doxyfile",
    "content": "# All settings not listed here will use the Doxygen default values.\n\nPROJECT_NAME           = \"ros2_canopen\"\nPROJECT_NUMBER         = master\nPROJECT_BRIEF          = \"C++ ROS CANopen Library\"\n\n# Use these lines to include the generated logging.hpp (update install path if needed)\nINPUT                  = ../../canopen_core/include ../../canopen_base_driver/include ../../canopen_402_driver/include ../../canopen_proxy_driver/include\n\nRECURSIVE              = YES\nOUTPUT_DIRECTORY       = _build\n\nEXTRACT_ALL            = YES\nSORT_MEMBER_DOCS       = NO\n\nGENERATE_LATEX         = NO\nGENERATE_XML           = YES\n\nENABLE_PREPROCESSING   = YES\n\nDOT_GRAPH_MAX_NODES    = 101\n\nFILE_PATTERNS = *.cpp *.h *.hpp *.md\n"
  },
  {
    "path": "canopen/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen</name>\n  <version>0.3.2</version>\n  <description>Meta-package aggregating the ros2_canopen packages and documentation</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <maintainer email=\"vishnuprasad.prachandabhanu@ipa.fraunhofer.de\">Vishnuprasad Prachandabhanu</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <exec_depend>canopen_interfaces</exec_depend>\n  <exec_depend>canopen_core</exec_depend>\n  <exec_depend>canopen_base_driver</exec_depend>\n  <exec_depend>lely_core_libraries</exec_depend>\n  <exec_depend>canopen_proxy_driver</exec_depend>\n  <exec_depend>canopen_base_driver</exec_depend>\n  <exec_depend>canopen_402_driver</exec_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen/sphinx/Makefile",
    "content": "# Minimal makefile for Sphinx documentation\n#\n\n# You can set these variables from the command line, and also\n# from the environment for the first two.\nSPHINXOPTS    ?=\nSPHINXBUILD   ?= sphinx-build\nSOURCEDIR     = .\nBUILDDIR      = _build\n\n# Put it first so that \"make\" without argument is like \"make help\".\nhelp:\n\t@$(SPHINXBUILD) -M help \"$(SOURCEDIR)\" \"$(BUILDDIR)\" $(SPHINXOPTS) $(O)\n\n.PHONY: help Makefile clean\n\nclean:\n\trm -rf \"_doxygen/\" \"api/\"\n\t@$(SPHINXBUILD) -M clean \"$(SOURCEDIR)\" \"$(BUILDDIR)\" $(SPHINXOPTS) $(O)\n\n# Catch-all target: route all unknown targets to Sphinx using the new\n# \"make mode\" option.  $(O) is meant as a shortcut for $(SPHINXOPTS).\n%: Makefile\n\t@$(SPHINXBUILD) -M $@ \"$(SOURCEDIR)\" \"$(BUILDDIR)\" $(SPHINXOPTS) $(O)\n"
  },
  {
    "path": "canopen/sphinx/_static/css/custom.css",
    "content": "\n.wy-table-responsive table td,\n.wy-table-responsive table th {\n white-space:normal;\n}\n\ntr {\n    white-space: normal;\n}\n\nthead {\n    white-space: normal;\n}\n\ntable {\n    white-space: normal;\n}\n"
  },
  {
    "path": "canopen/sphinx/application/prbt_robot.rst",
    "content": "Pilz manipulator PRBT 6\n=======================\n\nThis guide provides instructions on how to set up Pilz manipulators PRBT 6 using ros2_canopen.\nBefore following this guide, make sure to refer to the user guide to :doc:`../user-guide/configuration`,\n:doc:`../user-guide/how-to-create-a-configuration` and :doc:`../user-guide/how-to-create-a-robot-system`.\nAdditionally, this guide is based on: `pilz_robots <https://github.com/PilzDE/pilz_robots>`_.\n\nTo configure the PRBT 6 using ros2_canopen, please refer to the pre-existing configuration in the `pilz_robot <https://github.com/ipa-cmh/prbt_robot.git>`_ package.\n\n\nPackage creation and setup\n----------------------------\n- Create a new configuration package for the robot with the name ``prbt_robot_support``.\n\n    .. code-block:: console\n\n        $ ros2 pkg create --dependencies ros2_canopen lely_core_libraries --build-type ament_cmake prbt_robot_support\n        $ cd prbt_robot_support\n        $ rm -rf src\n        $ rm -rf include\n        $ mkdir -p launch\n        $ mkdir -p config\n        $ mkdir -p urdf\n        $ touch config/prbt_ros2_control.yaml\n\n- Create a new bus configuration folder with name ``prbt``. And create ``bus.yml`` and copy ``prbt_0_1.dcf`` from `pilz_support <https://github.com/PilzDE/pilz_robots/tree/noetic-devel/prbt_support/config>`_ package.\n\n    Now the package structure should look like this:\n\n    ::\n\n        prbt_robot_support\n            ├── config\n            │   ├── prbt\n            │   |   ├── bus.yml\n            │   |   └── prbt_0_1.dcf\n            │   └── prbt_ros2_control.yaml\n            ├── launch\n            ├── urdf\n            ├── CMakeLists.txt\n            └── package.xml\n\n- Add the following to the ``bus.yml``\n\n    .. code-block:: yaml\n\n        options:\n            dcf_path: \"@BUS_CONFIG_PATH@\"\n            master:\n                node_id: 1\n                driver: \"ros2_canopen::MasterDriver\"\n                package: \"canopen_master_driver\"\n                sync_period: 10000\n\n            defaults:\n                dcf: \"prbt_0_1.dcf\"\n                driver: \"ros2_canopen::Cia402Driver\"\n                package: \"canopen_402_driver\"\n                period: 10\n                heartbeat_producer: 1000\n                switching_state: 2\n                position_mode: 7\n                scale_pos_from_dev: 0.00001745329252\n                scale_pos_to_dev: 57295.7795131\n                sdo:\n                    - {index: 0x6081, sub_index: 0, value: 1000}\n                    - {index: 0x60C2, sub_index: 1, value: 10} # Interpolation time period at 10 ms matches the period.\n\n                tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n                    1:\n                    enabled: true\n                    cob_id: \"auto\"\n                    transmission: 0x01\n                    mapping:\n                        - {index: 0x6041, sub_index: 0} # status word\n                        - {index: 0x6061, sub_index: 0} # mode of operation display\n                    2:\n                    enabled: true\n                    cob_id: \"auto\"\n                    transmission: 0x01\n                    mapping:\n                        - {index: 0x6064, sub_index: 0} # position actual value\n                        - {index: 0x606c, sub_index: 0} # velocity actual position\n                    3:\n                    enabled: false\n                    4:\n                    enabled: false\n                rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n                    1:\n                    enabled: true\n                    cob_id: \"auto\"\n                    mapping:\n                    - {index: 0x6040, sub_index: 0} # controlword\n                    - {index: 0x6060, sub_index: 0} # mode of operation\n                    - {index: 0x60C1, sub_index: 1} # interpolated position data\n                    2:\n                    enabled: true\n                    cob_id: \"auto\"\n                    mapping:\n                    - {index: 0x607A, sub_index: 0} # target position\n\n            nodes:\n                prbt_joint_1:\n                    node_id: 3\n                prbt_joint_2:\n                    node_id: 4\n                prbt_joint_3:\n                    node_id: 5\n                prbt_joint_4:\n                    node_id: 6\n                prbt_joint_5:\n                    node_id: 7\n                prbt_joint_6:\n                    node_id: 8\n\n- Create ``prbt.ros2_control.xacro`` file in ``urdf`` folder and add the following to the file:\n\n    .. code-block:: xml\n\n        <?xml version=\"1.0\"?>\n        <robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n\n            <xacro:macro name=\"prbt_ros2_control\" params=\"\n                name\n                prefix\n                bus_config\n                master_config\n                can_interface_name\n                master_bin\">\n\n                <ros2_control name=\"${name}\" type=\"system\">\n                    <hardware>\n                        <plugin>canopen_ros2_control/RobotSystem</plugin>\n                        <param name=\"bus_config\">${bus_config}</param>\n                        <param name=\"master_config\">${master_config}</param>\n                        <param name=\"can_interface_name\">${can_interface_name}</param>\n                        <param name=\"master_bin\">\"${master_bin}\"</param>\n                    </hardware>\n                    <joint name=\"${prefix}joint_1\">\n                        <param name=\"device_name\">prbt_joint_1</param>\n                    </joint>\n                    <joint name=\"${prefix}joint_2\">\n                        <param name=\"device_name\">prbt_joint_2</param>\n                    </joint>\n                    <joint name=\"${prefix}joint_3\">\n                        <param name=\"device_name\">prbt_joint_3</param>\n                    </joint>\n                    <joint name=\"${prefix}joint_4\">\n                        <param name=\"device_name\">prbt_joint_4</param>\n                    </joint>\n                    <joint name=\"${prefix}joint_5\">\n                        <param name=\"device_name\">prbt_joint_5</param>\n                    </joint>\n                    <joint name=\"${prefix}joint_6\">\n                        <param name=\"device_name\">prbt_joint_6</param>\n                    </joint>\n                </ros2_control>\n\n            </xacro:macro>\n\n        </robot>\n\n- Add the following to the ``prbt_ros2_control.yaml`` file:\n\n    .. code-block:: yaml\n\n        controller_manager:\n            ros__parameters:\n                update_rate: 100  # Hz\n\n                joint_state_broadcaster:\n                type: joint_state_broadcaster/JointStateBroadcaster\n\n                arm_controller:\n                type: joint_trajectory_controller/JointTrajectoryController\n\n        arm_controller:\n            ros__parameters:\n                joints:\n                    - prbt_joint_1\n                    - prbt_joint_2\n                    - prbt_joint_3\n                    - prbt_joint_4\n                    - prbt_joint_5\n                    - prbt_joint_6\n                command_interfaces:\n                    - position\n                state_interfaces:\n                    - position\n                    - velocity\n                stop_trajectory_duration: 0.2\n                state_publish_rate:  100.0\n                action_monitor_rate: 25.0\n                goal_time: 0.0\n                limits:\n                    prbt_joint_1:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n                    prbt_joint_2:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n                    prbt_joint_3:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n                    prbt_joint_4:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n                    prbt_joint_5:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n                    prbt_joint_6:\n                        has_acceleration_limits: true\n                        max_acceleration: 6.0\n\n- Create a launch file with name ``robot.launch.py`` in the launch directory of your package. Follow the instructions :doc:`../user-guide/how-to-create-a-robot-system`  to complete the launch file. The launch file should look like this:\n\n    .. code-block:: python\n\n        import os\n        from ament_index_python import get_package_share_directory\n        from launch import LaunchDescription\n        from launch.actions import DeclareLaunchArgument\n        from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\n        from launch_ros.actions import Node\n        from launch_ros.substitutions import FindPackageShare\n        from launch.actions import IncludeLaunchDescription\n        from launch.launch_description_sources import PythonLaunchDescriptionSource\n\n        from launch.actions import IncludeLaunchDescription\n        from launch.launch_description_sources import PythonLaunchDescriptionSource\n        import launch_ros\n\n        def generate_launch_description():\n            declared_arguments = []\n\n            declared_arguments.append(\n                DeclareLaunchArgument(\n                    \"description_package\",\n                    description=\"Package where urdf file is stored.\",\n                    default_value=\"prbt_robot_support\"\n                )\n            )\n            declared_arguments.append(\n                DeclareLaunchArgument(\n                    \"can_interface_name\",\n                    default_value=\"vcan0\",\n                    description=\"Interface name for can\",\n                )\n            )\n            declared_arguments.append(\n                DeclareLaunchArgument(\n                    \"use_ros2_control\",\n                    default_value=\"true\",\n                    description=\"Use ros2_control\",\n                )\n            )\n\n            controller_config = PathJoinSubstitution([FindPackageShare(\"prbt_robot_support\"), \"config\", \"prbt_ros2_control.yaml\"])\n            bus_config = PathJoinSubstitution([FindPackageShare(\"prbt_robot_support\"), \"config\", \"prbt\", \"bus.yml\"])\n            master_config = PathJoinSubstitution([FindPackageShare(\"prbt_robot_support\"), \"config\", \"prbt\", \"master.dcf\"])\n            can_interface_name = LaunchConfiguration(\"can_interface_name\")\n\n            master_bin_path = os.path.join(\n                        get_package_share_directory(\"prbt_robot_support\"),\n                        \"config\",\n                        \"prbt\",\n                        \"master.bin\",\n                    )\n            if not os.path.exists(master_bin_path):\n                master_bin_path = \"\"\n            robot_description_content = Command(\n                [\n                    PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n                    \" \",\n                    PathJoinSubstitution([FindPackageShare(LaunchConfiguration(\"description_package\")), \"urdf\", \"prbt.xacro\"]),\n                    \" \",\n                    \"bus_config:=\",\n                    bus_config,\n                    \" \",\n                    \"master_config:=\",\n                    master_config,\n                    \" \",\n                    \"master_bin:=\",\n                    master_bin_path,\n                    \" \",\n                    \"can_interface_name:=\",\n                    can_interface_name,\n                ]\n            )\n            robot_description = {\"robot_description\": launch_ros.descriptions.ParameterValue(robot_description_content, value_type=str)}\n\n            robot_state_publisher_node = Node(\n                package=\"robot_state_publisher\",\n                executable=\"robot_state_publisher\",\n                output=\"both\",\n                parameters=[robot_description],\n            )\n\n            # Controller manager\n            controller_manager_node = Node(\n                package=\"controller_manager\",\n                executable=\"ros2_control_node\",\n                output=\"both\",\n                parameters=[robot_description, controller_config],\n            )\n\n            joint_state_broadcaster_spawner = Node(\n                package=\"controller_manager\",\n                executable=\"spawner\",\n                arguments=[\"joint_state_broadcaster\", \"--controller-manager\", \"/controller_manager\"],\n            )\n            arm_controller_spawner = Node(\n                package=\"controller_manager\",\n                executable=\"spawner\",\n                arguments=[\"arm_controller\", \"--controller-manager\", \"/controller_manager\"],\n            )\n\n            nodes_list = [\n                robot_state_publisher_node,\n                controller_manager_node,\n                joint_state_broadcaster_spawner,\n                arm_controller_spawner,\n            ]\n\n            return LaunchDescription(declared_arguments + nodes_list)\n\n- Edit the CMakeLists.txt file of your package and add the following lines after the find_package section.\n\n    .. code-block:: cmake\n\n        cogen_dcf(prbt)\n\n        install(DIRECTORY\n        launch urdf meshes\n        DESTINATION share/${PROJECT_NAME})\n\n        install(FILES config/prbt_ros2_control.yaml\n        DESTINATION share/${PROJECT_NAME}/config)\n\n- Build your package and source the setup file.\n\nMoveIt2 setup\n-------------\n\nFollow the `MoveIt Setup Assistance <https://moveit.picknik.ai/main/doc/examples/setup_assistant/setup_assistant_tutorial.html?highlight=setup%20assistance>`_ tutorial\nand create the MoveIt2 package for your robot. The MoveIt2 package should be created in the same workspace as your robot package.\n\n- Update ``moveit_controller.yaml`` file in the config directory of your MoveIt2 package. The file should look like this:\n\n    .. code-block:: yaml\n\n        # MoveIt uses this configuration for controller management\n        trajectory_execution:\n        allowed_execution_duration_scaling: 1.2\n        allowed_goal_duration_margin: 0.5\n        allowed_start_tolerance: 0.01\n\n        moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager\n\n        moveit_simple_controller_manager:\n        controller_names:\n            - arm_controller\n\n        arm_controller:\n            type: FollowJointTrajectory\n            action_ns: follow_joint_trajectory\n            default: True\n            joints:\n            - prbt_joint_1\n            - prbt_joint_2\n            - prbt_joint_3\n            - prbt_joint_4\n            - prbt_joint_5\n            - prbt_joint_6\n\n- Create a launch file ``moveit_planning_execution.launch.py`` to launch moveit and robot components.\n\n    .. code-block:: python\n\n        from launch import LaunchDescription\n        from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription\n        from launch.substitutions import LaunchConfiguration, PathJoinSubstitution\n        from launch_ros.substitutions import FindPackageShare\n        from launch.actions import IncludeLaunchDescription\n        from launch.launch_description_sources import PythonLaunchDescriptionSource\n\n        from launch.actions import TimerAction\n\n        from moveit_configs_utils import MoveItConfigsBuilder\n\n\n        def generate_launch_description():\n            moveit_config = MoveItConfigsBuilder(\n                \"prbt\", package_name=\"prbt_robot_moveit_config\"\n            ).to_moveit_configs()\n            declared_arguments = []\n\n            declared_arguments.append(\n                DeclareLaunchArgument(\n                    \"can_interface_name\",\n                    default_value=\"can0\",\n                    description=\"Interface name for can\",\n                )\n            )\n\n            robot_hw_node = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    [PathJoinSubstitution([FindPackageShare(\"prbt_robot_support\"), \"launch\", \"robot.launch.py\"])],\n                ),\n                launch_arguments={\n                    \"can_interface_name\": LaunchConfiguration(\"can_interface_name\"),\n                }.items(),\n            )\n\n            virtual_joints = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    str(\n                        moveit_config.package_path / \"launch/static_virtual_joint_tfs.launch.py\"\n                    )\n                ),\n            )\n\n            move_group = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    str(moveit_config.package_path / \"launch/move_group.launch.py\")\n                ),\n            )\n\n            rviz = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    str(moveit_config.package_path / \"launch/moveit_rviz.launch.py\")\n                ),\n            )\n\n\n            node_list = [\n                robot_hw_node,\n                virtual_joints,\n                move_group,\n                rviz,\n            ]\n\n            return LaunchDescription(declared_arguments + node_list)\n\nRunning the PRBT robot\n------------------------\nThere are two ways to run the demo. First you can use ``canopen_fake_slave`` to simulate the robot using CAN interface ``vcan0``. Second you can use the real robot.\nRefer :doc:`../quickstart/operation` to configure CAN interface.\n\n.. code-block:: bash\n\n    # Run the demo using fake robot\n    ros2 launch prbt_robot_moveit_config moveit_planning_execution.launch.py can_interface_name:=vcan0\n\n    # Run the demo using real robot\n    ros2 launch prbt_robot_moveit_config moveit_planning_execution.launch.py can_interface_name:=can0\n\nRviz2:\n\n.. image:: ../images/prbt_rviz2.png\n    :width: 90%\n    :align: center\n"
  },
  {
    "path": "canopen/sphinx/application/trinamic.rst",
    "content": "Trinamic Stepper Motor control\n==============================\n\nIntroduction\n------------\n\nThis tutorial is a simple example of how to use the ros2_canopen package to control a `Trinamic smart stepper motor <https://www.trinamic.com/products/drives/details/pd42-x-1270/>`_.\n\nGetting started\n---------------\n\nIf you haven't already done so, follow the steps in the :doc:`../user-guide/configuration`.\n\nConfiguration\n-------------\n\n- Create a new folder in the ``config`` folder of your configuration package. Name it ``single-pd42``.\n- Download ``.eds`` file from `Trinamic <https://www.trinamic.com/fileadmin/assets/Products/Drives_Software/TMCM-1270_CANopen_V326.zip>`_ and place ``TMCM-1270.eds`` in the ``single-pd42`` folder.\n- Create a ``bus.yml`` file in the ``single-pd42`` folder with the following content:\n\n    .. code-block:: yaml\n\n        options:\n            dcf_path: \"@BUS_CONFIG_PATH@\"\n\n        master:\n            node_id: 2\n            driver: \"ros2_canopen::MasterDriver\"\n            package: \"canopen_master_driver\"\n            sync_period: 20000\n\n\n        defaults:\n            dcf: \"TMCM-1270.eds\"\n            driver: \"ros2_canopen::Cia402Driver\"\n            package: \"canopen_402_driver\"\n            polling: false\n            heartbeat_producer: 1000 # Heartbeat every 1000 ms\n            sdo: # SDO executed during config\n                - {index: 0x6081, sub_index: 0, value: 500000} # Set velocity\n                - {index: 0x6083, sub_index: 0, value: 1000000} # Set acceleration\n                - {index: 0x6083, sub_index: 0, value: 1000000} # Set deceleration\n                - {index: 0x6085, sub_index: 0, value: 1000000} # Set quickstop deceleration\n                - {index: 0x6098, sub_index: 0, value: 35} # Set default homing mode to 35\n                - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n                - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n\n        nodes:\n            trinamic_pd42:\n                node_id: 1\n\n\n- Edit the ``CMakeLists.txt`` file in the ``config`` folder of your configuration package and add the following lines:\n\n    .. code-block:: cmake\n\n        cmake_minimum_required(VERSION 3.8)\n        project(trinamic_pd42_can)\n\n        if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n        add_compile_options(-Wall -Wextra -Wpedantic)\n        endif()\n\n        # find dependencies\n        find_package(ament_cmake REQUIRED)\n        find_package(rclcpp REQUIRED)\n        find_package(std_srvs REQUIRED)\n        find_package(canopen REQUIRED)\n        find_package(lely_core_libraries REQUIRED)\n        find_package(canopen_interfaces REQUIRED)\n\n        # generate_dcf(single-pd42)\n        cogen_dcf(single-pd42)\n\n        add_executable(position_tick_client src/position_tick_motor.cpp)\n        target_link_libraries(position_tick_client\n            ${canopen_interfaces_TARGETS}\n            ${std_srvs_TARGETS}\n            rclcpp::rclcpp\n        )\n\n        install(TARGETS\n        position_tick_client\n        DESTINATION lib/${PROJECT_NAME})\n\n        # install launch file\n        install(DIRECTORY\n        launch/\n        DESTINATION share/${PROJECT_NAME}\n        )\n\n        if(BUILD_TESTING)\n        find_package(ament_lint_auto REQUIRED)\n        endif()\n\n        ament_package()\n\n- Create launch file in folder ``launch`` and add the following content:\n\n    .. code-block:: python\n\n        import os\n        import sys\n\n        import launch\n        from launch.actions import IncludeLaunchDescription\n        from launch.launch_description_sources import PythonLaunchDescriptionSource\n        from ament_index_python import get_package_share_directory\n        from launch import LaunchDescription\n\n\n        def generate_launch_description():\n            ld = LaunchDescription()\n            slave_eds_path = os.path.join(\n                get_package_share_directory(\"trinamic_pd42_can\"), \"config\", \"single-pd42\", \"TMCM-1270.eds\"\n            )\n\n            slave_node_1 = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    [\n                        os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                        \"/cia402_slave.launch.py\",\n                    ]\n                ),\n                launch_arguments={\n                    \"node_id\": \"1\",\n                    \"node_name\": \"pd42_slave\",\n                    \"slave_config\": slave_eds_path,\n                }.items(),\n            )\n            master_bin_path = os.path.join(\n                get_package_share_directory(\"trinamic_pd42_can\"),\n                \"config\",\n                \"single-pd42\",\n                \"master.bin\",\n            )\n            if not os.path.exists(master_bin_path):\n                master_bin_path = \"\"\n\n            device_container = IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    [\n                        os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                        \"/canopen.launch.py\",\n                    ]\n                ),\n                launch_arguments={\n                    \"master_config\": os.path.join(\n                        get_package_share_directory(\"trinamic_pd42_can\"),\n                        \"config\",\n                        \"single-pd42\",\n                        \"master.dcf\",\n                    ),\n                    \"master_bin\": master_bin_path,\n                    \"bus_config\": os.path.join(\n                        get_package_share_directory(\"trinamic_pd42_can\"),\n                        \"config\",\n                        \"single-pd42\",\n                        \"bus.yml\",\n                    ),\n                    \"can_interface_name\": \"vcan0\",\n                }.items(),\n            )\n\n            ld.add_action(device_container)\n            ld.add_action(slave_node_1)\n\n            return ld\n\nRunning the example\n-------------------\n\nTo begin, follow the instructions for :doc:`../quickstart/operation`, which can be done using either a virtual or peak CAN interface.\n\nIf you prefer to use a real CAN interface, you will need to modify the launch file by changing the ``can_interface_name`` argument to ``can0``.\nAdditionally, if you are using real hardware, you should comment out the fake slave launch by adding a *#* in front of the line *ld.add_action(slave_node_1)*.\nOnce these changes have been made, you can launch the example.\n\n.. code-block:: console\n\n    ros2 launch trinamic_pd42_can <your launch file>.launch.py\n\nInitilaize the motor by calling the service ``/trinamic_pd42/init``:\n\n.. code-block:: console\n\n    ros2 service call /trinamic_pd42/init std_srvs/srv/Trigger\n\nSet the operation mode to ``Profile Position Mode`` by calling the service ``/trinamic_pd42/position_mode``:\n\n.. code-block:: console\n\n    ros2 service call /trinamic_pd42/position_mode std_srvs/srv/Trigger\n\nSet the target to the motor by calling the service ``/trinamic_pd42/target``:\n\n.. code-block:: console\n\n    ros2 service call /trinamic_pd42/target canopen_interfaces/srv/COTargetDouble \"{ target: 10.0 }\"\n\nReference\n---------\nYou can find the source code for this example in the `trinamic_pd42_can <https://github.com/ipa-cmh/trinamic_pd42_can.git>`_ package.\n"
  },
  {
    "path": "canopen/sphinx/conf.py",
    "content": "# Copyright 2023 ROS-Industrial\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\n# Configuration file for the Sphinx documentation builder.\n#\n# This file only contains a selection of the most common options. For a full\n# list see the documentation:\n# https://www.sphinx-doc.org/en/master/usage/configuration.html\n\n# -- Path setup --------------------------------------------------------------\n\n# If extensions (or modules to document with autodoc) are in another directory,\n# add these directories to sys.path here. If the directory is relative to the\n# documentation root, use os.path.abspath to make it absolute, like shown here.\n#\nfrom pathlib import Path\n\n# -- Project information -----------------------------------------------------\n\nproject = \"ros2_canopen\"\ncopyright = \"2022, Christoph Hellmann Santos,  Harshavardhan Deshpande\"\nauthor = \"Christoph Hellmann Santos,  Harshavardhan Deshpande\"\n\n# The full version, including alpha/beta/rc tags\nrelease = \"0.0.1\"\n\n\n# -- General configuration ---------------------------------------------------\n\n# Add any Sphinx extension module names here, as strings. They can be\n# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom\n# ones.\nextensions = [\n    \"sphinx_rtd_theme\",\n    \"sphinx_mdinclude\",\n    \"sphinx.ext.imgmath\",\n    \"sphinx.ext.todo\",\n    \"sphinx.ext.graphviz\",\n    \"sphinxcontrib.plantuml\",\n    \"breathe\",\n]\n\nbreathe_default_project = \"ros2_canopen\"\n\n\ndef get_package(package: str):\n    path = Path(__file__).parent.parent.parent.joinpath(f\"{package}/include/{package}\")\n    files_gen = path.glob(\"*.hpp\")\n    files = []\n    for file in files_gen:\n        files.append(file.name)\n    return (path, files)\n\n\nbreathe_projects = {\n    \"ros2_canopen\": \"../doxygen/_build/xml/\",\n}\n\n\n# Tell sphinx what the primary language being documented is.\nprimary_domain = \"cpp\"\n\n# Tell sphinx what the pygments highlight language should be.\nhighlight_language = \"cpp\"\n\n\n# Add any paths that contain templates here, relative to this directory.\ntemplates_path = [\"_templates\"]\n\n# List of patterns, relative to source directory, that match files and\n# directories to ignore when looking for source files.\n# This pattern also affects html_static_path and html_extra_path.\nexclude_patterns = [\"_build\", \"Thumbs.db\", \".DS_Store\"]\n\n\n# -- Options for HTML output -------------------------------------------------\n\n# The theme to use for HTML and HTML Help pages.  See the documentation for\n# a list of builtin themes.\n#\nhtml_theme = \"sphinx_rtd_theme\"\n\n# Add any paths that contain custom static files (such as style sheets) here,\n# relative to this directory. They are copied after the builtin static files,\n# so a file named \"default.css\" will overwrite the builtin \"default.css\".\nhtml_static_path = [\"_static\"]\nhtml_logo = \"images/ros2-canopen-logo.png\"\nhtml_css_files = [\"css/custom.css\"]\npygments_style = \"sphinx\"\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/architecture.rst",
    "content": "Architecture\n=============\n\nThe architecture of the ROS2 CANopen stack is based on the composition\nconcept of ROS2. In ROS2 components are dynamically loadable ROS2 nodes\nwhich are loaded by a component manager.\n\nDevice Container\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe core of the ROS2 CANopen stack is the ros2_canopen::DeviceContainer which implements\nthe rclcpp::ComponentManager class. The DeviceContainer enables loading drivers for the\nCANopen master and the devices on the bus, that have been exported as rclcpp_components.\nCANopen Master drivers need to implement the ros2_canopen::CanopenMasterInterface, CANopen\nDevice drivers need to implement the ros2_canopen::CanopenDriverInterface.\n\nThe difference between the ros2_canopen::DeviceContainer and the rclcpp::ComponentContainer\nis that the device container loads only master and driver components specified in the bus\nconfiguration (bus.yml). It does not have services for loading components online. All components\nthat are connected or will be connected to the CANopen Bus need to be known and specified in\nthe bus.yml before starting the device container.\n\n.. uml::\n\n  rclcpp::ComponentManager <|-- ros2_canopen::DeviceContainer\n\n  class rclcpp::ComponentManager\n  {\n    std::weak_ptr<rclcpp::Executor> executor_\n    std::vector<ComponentResource> get_component_resources(std::string package_name)\n    std::shared_ptr<NodeFactory> create_component_factory(ComponentResource resource)\n    void on_list_nodes(...)\n    virtual void set_executor(const std::weak_ptr<rclcpp::Executor> executor)\n  }\n\n\n  class ros2_canopen::DeviceContainer\n  {\n    std::shared_ptr<CanopenMasterInterface> can_master_\n    std::shared_ptr<LifecycleManager> lifecycle_manager_\n    std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>> drivers_\n    void on_list_nodes(...) override\n    virtual void set_executor(const std::weak_ptr<rclcpp::Executor> executor) override\n  }\n\nThe device container will first load the master specified in the bus configuration. Then\nit will load the drivers specified in the bus configuration. If the master and drivers\nspecified in the bus configuration are managed nodes it will as well load the ros2_canopen::LifecycleManager.\n\n\nCANopen Master Driver Architecture\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\n\nThe architecture for CANopen master drivers looks as depicted in the class diagram. All master drivers\nconsist of three main classes.\n\nThe first class is the functionality class that contains the drivers functionailities independently of\nthe ROS2 node type. This class needs to implement the ros2_canopen::node_interfaces::NodeCanopenMasterInterface.\nros2_canopen::node_interfaces::NodeCanopenMaster is an abstract class that provides some useful functionality and\nimplements the ros2_canopen::node_interfaces::NodeCanopenMasterInterface. Usually, master drivers will inherit from\nros2_canopen::node_interfaces::NodeCanopenMaster.\n\nThe second class is the class that wraps the functionality class in a rclcpp::Node. This class should implement the\nros2_canopen::CanopenMasterInterface. The canopen_core package provides a convenience class ros2_canopen::CanopenMaster\nthat should be inherited from and implements the ros2_canopen::CanopenMasterInterface.\n\nThe third class is the class that wraps the functionality class in a rclcpp_lifecycle::LifecycleNode. This class should implement the\nros2_canopen::CanopenMasterInterface. The canopen_core package provides a convenience class ros2_canopen::LifecycleCanopenMaster\nthat should be inherited from and implements the ros2_canopen::CanopenMasterInterface.\n\n.. uml::\n\n\n  package \"canopen_core\" {\n    interface ros2_canopen::CanopenMasterInterface\n    interface ros2_canopen::node_interfaces::NodeCanopenMasterInterface\n    abstract ros2_canopen::LifecycleCanopenMaster\n    abstract ros2_canopen::node_interfaces::NodeCanopenMaster\n    abstract ros2_canopen::CanopenMaster\n\n\n    ros2_canopen::node_interfaces::NodeCanopenMasterInterface - ros2_canopen::CanopenMaster : < has\n    ros2_canopen::LifecycleCanopenMaster - ros2_canopen::node_interfaces::NodeCanopenMasterInterface : > has\n\n    ros2_canopen::CanopenMasterInterface <|-- ros2_canopen::LifecycleCanopenMaster\n    ros2_canopen::node_interfaces::NodeCanopenMasterInterface <|-- ros2_canopen::node_interfaces::NodeCanopenMaster\n    ros2_canopen::CanopenMasterInterface <|-- ros2_canopen::CanopenMaster\n\n  }\n\n  package \"canopen_master_driver\" {\n\n    class ros2_canopen::LifecycleMasterDriver << (C, blue) Component>>\n    class ros2_canopen::node_interfaces::NodeCanopenBasicMaster\n    class ros2_canopen::MasterDriver << (C, blue) Component>>\n    ros2_canopen::LifecycleMasterDriver - ros2_canopen::node_interfaces::NodeCanopenBasicMaster: > has\n    ros2_canopen::node_interfaces::NodeCanopenBasicMaster - ros2_canopen::MasterDriver : < has\n    ros2_canopen::LifecycleCanopenMaster <|-- ros2_canopen::LifecycleMasterDriver\n    ros2_canopen::node_interfaces::NodeCanopenMaster <|-- ros2_canopen::node_interfaces::NodeCanopenBasicMaster\n    ros2_canopen::CanopenMaster <|-- ros2_canopen::MasterDriver\n  }\n\n\nCANopen Device Driver Architecture\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\n\nThe architecture for CANopen device drivers looks as depicted in the class diagram. All device drivers\nconsist of three main classes.\n\nThe first class is the functionality class that contains the drivers functionailities independently of\nthe ROS2 node type. This class needs to implement the ros2_canopen::node_interfaces::NodeCanopenDriverInterface.\nros2_canopen::node_interfaces::NodeCanopenDriver is an abstract class that provides some useful functionality and\nimplements the ros2_canopen::node_interfaces::NodeCanopenDriverInterface. If you plan to write a driver from scratch\nbased on Lely Core library, your functionality class should inherit from ros2_canopen::node_interfaces::NodeCanopenDriver.\nIf you want to use the existing lely_driver_bridge, your functionality class should inherit from ros2_canopen::NodeCanopenBaseDriver.\n\nThe second class is the class that wraps the functionality class in a rclcpp::Node. This class should implement the\nros2_canopen::CanopenDriverInterface. The canopen_core package provides a convenience class ros2_canopen::CanopenDriver\nthat should be inherited from and implements the ros2_canopen::CanopenDriverInterface.\n\nThe third class is the class that wraps the functionality class in a rclcpp_lifecycle::LifecycleNode. This class should implement the\nros2_canopen::CanopenDriverInterface. The canopen_core package provides a convenience class ros2_canopen::LifecycleCanopenDriver\nthat should be inherited from and implements the ros2_canopen::CanopenDriverInterface.\n\n.. uml::\n\n  package \"canopen_core\" {\n    interface ros2_canopen::CanopenDriverInterface\n    interface ros2_canopen::node_interfaces::NodeCanopenDriverInterface\n    abstract ros2_canopen::LifecycleCanopenDriver\n    abstract ros2_canopen::node_interfaces::NodeCanopenDriver\n    abstract ros2_canopen::CanopenDriver\n\n\n    ros2_canopen::node_interfaces::NodeCanopenDriverInterface - ros2_canopen::CanopenDriver : < has\n    ros2_canopen::LifecycleCanopenDriver - ros2_canopen::node_interfaces::NodeCanopenDriverInterface : > has\n\n    ros2_canopen::CanopenDriverInterface <|-- ros2_canopen::LifecycleCanopenDriver\n    ros2_canopen::node_interfaces::NodeCanopenDriverInterface <|-- ros2_canopen::node_interfaces::NodeCanopenDriver\n    ros2_canopen::CanopenDriverInterface <|-- ros2_canopen::CanopenDriver\n\n  }\n\n\n  package \"canopen_base_driver\" {\n\n    class ros2_canopen::LifecycleBaseDriver << (C, blue) Component>>\n    class ros2_canopen::node_interfaces::NodeCanopenBaseDriver\n    class ros2_canopen::BaseDriver << (C, blue) Component>>\n    ros2_canopen::LifecycleBaseDriver - ros2_canopen::node_interfaces::NodeCanopenBaseDriver: > has\n    ros2_canopen::node_interfaces::NodeCanopenBaseDriver - ros2_canopen::BaseDriver : < has\n    ros2_canopen::LifecycleCanopenDriver <|-- ros2_canopen::LifecycleBaseDriver\n    ros2_canopen::node_interfaces::NodeCanopenDriver <|-- ros2_canopen::node_interfaces::NodeCanopenBaseDriver\n    ros2_canopen::CanopenDriver <|-- ros2_canopen::BaseDriver\n  }\n\n  package \"canopen_proxy_driver\" {\n    class ros2_canopen::LifecycleProxyDriver << (C, blue) Component>>\n    class ros2_canopen::node_interfaces::NodeCanopenProxyDriver\n    class ros2_canopen::ProxyDriver << (C, blue) Component>>\n    ros2_canopen::LifecycleProxyDriver - ros2_canopen::node_interfaces::NodeCanopenProxyDriver: > has\n    ros2_canopen::node_interfaces::NodeCanopenProxyDriver - ros2_canopen::ProxyDriver : < has\n    ros2_canopen::LifecycleCanopenDriver <|-- ros2_canopen::LifecycleProxyDriver\n    ros2_canopen::node_interfaces::NodeCanopenBaseDriver <|-- ros2_canopen::node_interfaces::NodeCanopenProxyDriver\n    ros2_canopen::CanopenDriver <|-- ros2_canopen::ProxyDriver\n  }\n\n  package \"canopen_402_driver\" {\n    class ros2_canopen::LifecycleCia402Driver << (C, blue) Component>>\n    class ros2_canopen::node_interfaces::NodeCanopen402Driver\n    class ros2_canopen::Cia402Driver << (C, blue) Component>>\n    ros2_canopen::LifecycleCia402Driver - ros2_canopen::node_interfaces::NodeCanopen402Driver: > has\n    ros2_canopen::node_interfaces::NodeCanopen402Driver - ros2_canopen::Cia402Driver : < has\n    ros2_canopen::LifecycleCanopenDriver <|-- ros2_canopen::LifecycleCia402Driver\n    ros2_canopen::node_interfaces::NodeCanopenProxyDriver <|-- ros2_canopen::node_interfaces::NodeCanopen402Driver\n    ros2_canopen::CanopenDriver <|-- ros2_canopen::Cia402Driver\n  }\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/design-objectives.rst",
    "content": "Design Objectives\n======================\n\nThe ros_canopen stack had a number of drawbacks especially when it came\nto maintainablity and complexity. In order to address these drawbacks, we\nhave decided to redesign the ros2_canopen stack completely with the following\ndevelopment goals.\n\n\n.. csv-table:: Development Objectives\n  :header-rows: 1\n  :class: longtable\n  :delim: ;\n  :widths: 1 2\n\n  Objective; Description\n  Understandability and Extendability; One major drawback of ros_canopen was that actually extending it with new drivers required to understand the complex stack with its different layers.\n  Robust Parallel Requests; When multiple nodes are running on the same bus, it should be possible to make requests to the nodes concurrently from ROS2 and have the canopen master handle the sequencing.\n  Easy Maintenance; Maintenance effort should be reduced as much as possible. Therefore, a clean and clear code structure and documentation is needed and only funcitonalities that are not already available from other high quality open source libraries should be self implemented.\n  Enable controlling drives via ros2_control; A driver for CIA402 and a ros2_control interface need to be developed.\n  Enable controlling drives via ros2 ervice interface; A driver for CIA402 and a service interface need to be developed.\n  Enable proxy functionalities via ros2 interface; For debugging purposes a proxy driver should be developed, which enables sending and receiving CANopen objects via a ros2 interface.\n  Good enough documentation; Write documentation for using and understanding the ros2_canopen stack.\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/new-device-manager.rst",
    "content": "Creating your device manager\n============================\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/new-driver.rst",
    "content": "Creating a new device driver\n============================\n\nCreating your own device driver is fairly easy in ros2_canopen. You should do this if you\nneed to create a driver for a specific device or a specific device profile that is not yet supported. If you create\na driver for a device profile we are happy to integrate the package into this repository - simply create\na PR.\n\nWhat you need to do\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nTo create a new driver you need to implement at least two classes. One being the functional class,\nthat contains your drivers functionalities. The other being a ROS2 wrapper node. Generally we recommend\ncreating one ROS2 wrapper node and another ROS2 lifecycle wrapper node.\n\nHow you do it\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nFirst you need to decide from which extension point you want to start. Usually, this is either the core interface, the base driver\nor the proxy driver. Base driver provides you with all necessary callbacks for CANopen functionalities but does\nnot come with any ROS2 interface. Proxy driver has a simple forwarding ROS2 interface that is useful for any driver.\nThe core interface comes without any functionality, you need to implement everything on your own.\nWe recommend creating you driver based on Proxy driver, this will be explained here.\n\nCreate the package\n------------------\nCreate your new package using the standard ros2 pkg commands. Make sure you add the following dependencies:\n\n* rclcpp\n* rclcpp_components\n* rclcpp_lifecycle\n* lifecycle_msgs\n* canopen_core\n* canopen_interfaces\n* canopen_base_driver\n* canopen_proxy_driver\n* lely_core_libraries\n* std_msgs\n* std_srvs\n\nOnce done add a subfolder ``node_interfaces`` in the ``src/`` and the ``include/[pacakge_name]/`` folders.\n\n\nCreate the functionality class\n------------------------------\nThe functionality class is structured similar to a LifecycleNode. The functionality class\nhas the following callback functions that are related to lifecycle which you can override:\n\n* void configure(bool called_from_base)\n* void activate(bool called_from_base)\n* void deactivate(bool called_from_base)\n* void cleanup(bool called_from_base)\n* void shutdown(bool called_from_base)\n\nCANopen functionality\n*********************\nIn addition to the functions there are callbacks for CANopen functionality that you can\noverride:\n\n* void on_rpdo(COData data)\n* void on_nmt(NmtState nmt_state)\n\nTo interact with the CANopen device you can use the ros2_canopen::LelyDriverBridge object,\nthat is stored in the functionality class (this->driver_). The ros2_canopen::LelyDriverBridge\nprovides the following functions you should use in your driver:\n\n* void nmt_command(NmtState nmt_state)\n* void tpdo_transmit(COData data)\n* std::future<bool>async_sdo_write(COData data)\n* std::future<COData>async_sdo_read(COData data)\n\n.. note::\n\n   The CANopen related functionality can only be used in the activate function or timers/threads that\n   were started by the activate function. If you start timers or threads in the activate function, that\n   use CANopen functionality, these have to be stopped in the deactivate function.\n\nROS2 functionality\n******************\nROS2 functionality is available via the ``node_`` object of the functionality class. This\nobject has a templated type and can either be a ``rclcpp::Node`` or ``rclcpp_lifecycle::LifecycleNode``.\nYou can use the standard functions like create_timer, create_publisher etc.\n\n.. note::\n\n   Currently it seems, that when you use template functions i.e. ``node_->create_publisher<xyz>(...)`` you\n   need to create a template specialisation.\n\n\n\nYour class declaration should look like this:\n\n.. code-block:: C++\n   :name: \"node_interfaces/node_canopen_xxx_driver.hpp\"\n\n   node_interfaces/node_canopen_xxx_driver.hpp:\n\n   #include <canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp>\n\n   template <class NODETYPE>\n   class NodeCanopenXXXDriver : public NodeCanopenProxyDriver<NODETYPE>\n   {\n      static_assert(\n            std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n               std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n            \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n   public:\n      NodeCanopenXXXDriver(NODETYPE *node);\n\n      /*Your overrides etc. go here*/\n   };\n\nYour member definitions go here:\n\n.. code-block:: C++\n   :name: \"node_interfaces/node_canopen_xxx_driver_impl.hpp\"\n\n   node_interfaces/node_canopen_xxx_driver.hpp:\n\n   #include node_interfaces/node_canopen_xxx_driver.hpp\n\n   /*Your function definitions go here.*/\n\nYour explicit template instantiations go here:\n\n.. code-block:: C++\n   :name: \"node_interfaces/node_canopen_xxx_driver.cpp\"\n\n   node_interfaces/node_canopen_xxx_driver.cpp:\n\n   #include node_interfaces/node_canopen_xxx_driver.hpp\n   #include node_interfaces/node_canopen_xxx_driver_impl.hpp\n\n   template class <ros2_canopen>::node_interfaces::NodeCanopenXXXDriver<rclcpp::Node>;\n   template class <ros2_canopen>::node_interfaces::NodeCanopenXXXDriver<rclcpp_lifecycle::LifecycleNode>;\n\n\nCreate the ROS2 wrapper classes\n-------------------------------\n\nThe ROS2 wrapper classes are fairly easy to create once you wrote the functionality\nclass. The wrappers simply use the functionality class to provide the functionality.\nThe ROS2 wrapper class should always be derived from ``ros2_canopen::CanopenDriver`` or\n``ros2_canopen::LifecycleCanopenDriver`` .\n\n\nThe declaration should look like this:\n\n.. code::\n\n   lifecycle_xxx_driver.hpp:\n\n   #include \"canopen_xxx_driver/node_interfaces/node_canopen_xxx_driver.hpp\"\n   #include \"canopen_core/driver_node.hpp\"\n\n   /**\n      * @brief Lifecycle Proxy Driver\n      *\n      * A very basic driver without any functionality.\n      *\n      */\n   class LifecycleXXXDriver : public ros2_canopen::LifecycleCanopenDriver\n   {\n      std::shared_ptr<node_interfaces::NodeCanopenXXXDriver<rclcpp_lifecycle::LifecycleNode>> node_canopen_xxx_driver_;\n   public:\n      LifecycleXXXDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n   };\n\nThe definitions should look like this:\n\n.. code::\n\n\n   #include \"canopen_xxx_driver/lifecycle_proxy_driver.hpp\"\n\n   using namespace ros2_canopen;\n\n\n   LifecycleXXXDriver::LifecycleXXXDriver(rclcpp::NodeOptions node_options) : LifecycleCanopenDriver(node_options)\n   {\n   node_canopen_xxx_driver_ = std::make_shared<node_interfaces::NodeCanopenXXXDriver<rclcpp_lifecycle::LifecycleNode>>(this);\n   node_canopen_proxy_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenProxyDriver>(node_canopen_xxx_driver_);\n   node_canopen_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(node_canopen_xxx_driver_);\n   }\n\n   #include \"rclcpp_components/register_node_macro.hpp\"\n   RCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleXXXDriver)\n\n\nAdapt the CMakeLists.txt\n************************\nThe CMakeLists.txt file should look like this:\n\n.. code:: CMAKE\n\n   cmake_minimum_required(VERSION 3.8)\n   project(canopen_xxx_driver)\n\n   if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n   add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\n   endif()\n\n   # find dependencies\n   find_package(ament_cmake REQUIRED)\n   find_package(ament_cmake_ros REQUIRED)\n   find_package(rclcpp REQUIRED)\n   find_package(rclcpp_lifecycle REQUIRED)\n   find_package(rclcpp_components REQUIRED)\n   find_package(canopen_core REQUIRED)\n   find_package(canopen_interfaces REQUIRED)\n   find_package(canopen_base_driver REQUIRED)\n   find_package(canopen_proxy_driver REQUIRED)\n   find_package(std_msgs REQUIRED)\n   find_package(std_srvs REQUIRED)\n\n   # Functionality library\n   add_library(node_canopen_xxx_driver\n   src/node_interfaces/node_canopen_xxx_driver.cpp\n   )\n   target_compile_features(node_canopen_xxx_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\n   target_compile_options(node_canopen_xxx_driver PUBLIC -Wl,--no-undefined)\n   target_include_directories(node_canopen_xxx_driver PUBLIC\n   $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n   $<INSTALL_INTERFACE:include>)\n\n   target_link_libraries(node_canopen_xxx_driver PUBLIC\n     canopen_proxy_driver::node_canopen_proxy_driver\n   )\n\n   # Lifecycle driver\n   add_library(lifecycle_xxx_driver\n   src/lifecycle_xxx_driver.cpp\n   )\n   target_compile_features(lifecycle_xxx_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\n   target_compile_options(lifecycle_xxx_driver PUBLIC -Wl,--no-undefined)\n   target_include_directories(lifecycle_xxx_driver PUBLIC\n   $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n   $<INSTALL_INTERFACE:include>)\n\n   target_link_libraries(lifecycle_xxx_driver PUBLIC\n     canopen_core::node_canopen_driver\n     node_canopen_xxx_driver\n     rclcpp_components::component\n     rclcpp_lifecycle::rclcpp_lifecycle\n   )\n   # Causes the visibility macros to use dllexport rather than dllimport,\n   # which is appropriate when building the dll but not consuming it.\n   target_compile_definitions(lifecycle_xxx_driver PRIVATE \"CANOPEN_XXX_DRIVER_BUILDING_LIBRARY\")\n\n   rclcpp_components_register_nodes(lifecycle_xxx_driver \"ros2_canopen::LifecycleXXXDriver\")\n   set(node_plugins \"${node_plugins}ros2_canopen::LifecycleXXXDriver;$<TARGET_FILE:lifecycle_xxx_driver >\\n\")\n\n\n   # Non lifecycle driver\n   add_library(xxx_driver\n   src/xxx_driver.cpp\n   )\n   target_compile_features(xxx_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\n   target_compile_options(xxx_driver PUBLIC -Wl,--no-undefined)\n   target_include_directories(xxx_driver PUBLIC\n   $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n   $<INSTALL_INTERFACE:include>)\n\n   target_link_libraries(xxx_driver PUBLIC\n     canopen_core::node_canopen_driver\n     node_canopen_xxx_driver\n     rclcpp_components::component\n   )\n\n   # Causes the visibility macros to use dllexport rather than dllimport,\n   # which is appropriate when building the dll but not consuming it.\n   target_compile_definitions(xxx_driver PRIVATE \"CANOPEN_XXX_DRIVER_BUILDING_LIBRARY\")\n\n   rclcpp_components_register_nodes(xxx_driver \"ros2_canopen::XXXDriver\")\n   set(node_plugins \"${node_plugins}ros2_canopen::XXXDriver;$<TARGET_FILE:xxx_driver >\\n\")\n\n   install(\n   DIRECTORY include/\n   DESTINATION include\n   )\n\n   install(\n   TARGETS lifecycle_xxx_driver xxx_driver node_canopen_xxx_driver\n   EXPORT export_${PROJECT_NAME}\n   ARCHIVE DESTINATION lib\n   LIBRARY DESTINATION lib\n   RUNTIME DESTINATION bin\n   )\n\n   if(BUILD_TESTING)\n   endif()\n\n   ament_export_include_directories(\n   include\n   )\n   ament_export_libraries(\n   lifecycle_xxx_driver\n   xxx_driver\n   node_canopen_xxx_driver\n   )\n   ament_export_targets(\n   export_${PROJECT_NAME}\n   )\n   ament_export_dependencies(\n     canopen_base_driver\n     canopen_core\n     canopen_interfaces\n     canopen_proxy_driver\n     rclcpp\n     rclcpp_components\n     rclcpp_lifecycle\n     std_msgs\n     std_srvs\n   )\n\n   ament_package()\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/new-master.rst",
    "content": "Creating a new master\n=====================\n"
  },
  {
    "path": "canopen/sphinx/developers-guide/overview.rst",
    "content": "Overview\n========\nros2_canopen provides nodes for interfacing with CANopen devices. The library builds upon the professional and open source\nlelycore canopen library as opposed to the previous ros_canopen stack.\nIn ros2_canopen the bus configuration is simplified through the use of\nlelycore's configutaration toolchain.\n\nros2_canopen contains a number of packages that serve different serve different purposes.\n\n* **canopen**:\n\n  Meta-package for easy installation and contains overall documentation\n  of the ros2_canopen stack.\n\n* **lely_core_libraries**:\n\n  A colcon package wrapper for the lelycore canopen library, for convenient\n  installation with rosdep.\n\n* **canopen_core**:\n\n  Contains the core structures of the ros2_canopen stack such as the device manager\n  and the master node and the driver node interface.\n\n* **canopen_base_driver**:\n\n  This package contains the base implementation of a ROS2 CANopen device driver. It can base\n  used by other drivers for easy extension.\n\n* **canopen_proxy_driver**:\n\n  Contains an implementation of a proxy driver which simply forwards CANopen functionality\n  for a specific device via ROS2 services and messages.\n\n* **canopen_402_driver**:\n\n  Contains an implementation of the CIA402 profile for motion controllers and exposes\n  the profiles functionalities via ROS2 services and messages. The implementation is\n  copied from ros_canopen/canopen_402 and this package is licensed accordingly under\n  GNU Lesser General Public License v3.0!\n"
  },
  {
    "path": "canopen/sphinx/index.rst",
    "content": "ROS2 CANopen Stack\n==================\n\nThis is the documentation of the ROS2 CANopen stack.\n\n.. toctree::\n  :maxdepth: 1\n  :caption: Quickstart\n  :glob:\n\n  quickstart/installation\n  quickstart/operation\n  quickstart/examples\n\n.. toctree::\n  :maxdepth: 1\n  :caption: User Guide\n  :glob:\n\n  user-guide/operation\n  user-guide/configuration\n  user-guide/master\n  user-guide/proxy-driver\n  user-guide/cia402-driver\n  user-guide/how-to-create-a-configuration\n  user-guide/how-to-create-a-cia301-system\n  user-guide/how-to-create-a-robot-system\n\n\n.. toctree::\n  :maxdepth: 1\n  :caption: Developer Guide\n  :glob:\n\n  developers-guide/design-objectives\n  developers-guide/overview\n  developers-guide/architecture\n  developers-guide/new-driver\n  developers-guide/new-master\n  API Reference <https://ros-industrial.github.io/ros2_canopen/api/>\n\n.. toctree::\n  :maxdepth: 1\n  :caption: Software Tests\n  :glob:\n\n  software-tests/**\n\n.. toctree::\n  :maxdepth: 1\n  :caption: Application Demos\n  :glob:\n\n  application/**\n"
  },
  {
    "path": "canopen/sphinx/make.bat",
    "content": "@ECHO OFF\r\n\r\npushd %~dp0\r\n\r\nREM Command file for Sphinx documentation\r\n\r\nif \"%SPHINXBUILD%\" == \"\" (\r\n\tset SPHINXBUILD=sphinx-build\r\n)\r\nset SOURCEDIR=.\r\nset BUILDDIR=_build\r\n\r\nif \"%1\" == \"\" goto help\r\n\r\n%SPHINXBUILD% >NUL 2>NUL\r\nif errorlevel 9009 (\r\n\techo.\r\n\techo.The 'sphinx-build' command was not found. Make sure you have Sphinx\r\n\techo.installed, then set the SPHINXBUILD environment variable to point\r\n\techo.to the full path of the 'sphinx-build' executable. Alternatively you\r\n\techo.may add the Sphinx directory to PATH.\r\n\techo.\r\n\techo.If you don't have Sphinx installed, grab it from\r\n\techo.https://www.sphinx-doc.org/\r\n\texit /b 1\r\n)\r\n\r\n%SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O%\r\ngoto end\r\n\r\n:help\r\n%SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O%\r\n\r\n:end\r\npopd\r\n"
  },
  {
    "path": "canopen/sphinx/quickstart/examples.rst",
    "content": "Running Examples\n================\n\nIn order to tryout the library a few examples are provided in the ``canopen_tests`` directory.\nYou can run them if you have :ref:`started the vcan0 interface <quick-start-setup-can-controller>`.\n\nService Interface\n---------------------\n\n.. code-block:: bash\n\n    ros2 launch canopen_tests cia402_setup.launch.py\n\n\nManaged Service Interface\n-------------------------\n\n.. code-block:: bash\n\n    ros2 launch canopen_tests cia402_lifecycle_setup.launch.py\n\nROS2 Control\n------------\n\nProxy Setup\n,,,,,,,,,,,\n\n.. code-block:: bash\n\n   ros2 launch canopen_tests canopen_system.launch.py\n\n\nCiA402 Setup\n,,,,,,,,,,,,\n\n.. code-block:: bash\n\n   ros2 launch canopen_tests cia402_system.launch.py\n\n\nRobot Setup\n,,,,,,,,,,,,\n\n.. code-block:: bash\n\n    ros2 launch canopen_tests robot_control_setup.launch.py\n"
  },
  {
    "path": "canopen/sphinx/quickstart/installation.rst",
    "content": "Installation\n===============================\nClone ros2_canopen into your ROS2 workspace's source folder, install dependencies and\nbuild with colcon and your done.\n\n.. code-block:: console\n\n   $ git clone https://github.com/ros-industrial/ros2_canopen.git\n   $ cd ..\n   $ rosdep install --from-paths src/ros2_canopen --ignore-src -r -y\n   $ colcon build\n"
  },
  {
    "path": "canopen/sphinx/quickstart/operation.rst",
    "content": "Setup CAN Controller\n====================\n.. _quick-start-setup-can-controller:\n\n**Option 1**: Virtual CANController\n\n.. code-block:: console\n\n  $ sudo modprobe vcan\n  $ sudo ip link add dev vcan0 type vcan\n  $ sudo ip link set vcan0 txqueuelen 1000\n  $ sudo ip link set up vcan0\n\n**Option 2**: Peak CANController\n\n.. code-block:: console\n\n  $ sudo modprobe peak_usb\n  $ sudo ip link set can0 up type can bitrate 1000000\n  $ sudo ip link set can0 txqueuelen 1000\n  $ sudo ip link set up can0\n\nBitrate depends on your bus and devices capabilities.\n\n**Option 3**: candleLight USB-CAN Adapter\n\n.. code-block:: console\n\n  $ sudo modprobe gs_usb\n  $ sudo ip link set can0 up type can bitrate 500000\n  $ sudo ip link set can0 txqueuelen 1000\n  $ sudo ip link set up can0\n\nBitrate depends on your bus and devices capabilities.\n\n**Option 4**: Adapt these steps to other socketcan devices\n"
  },
  {
    "path": "canopen/sphinx/software-tests/proxy-driver-test.rst",
    "content": "Lifecycle Proxy Driver Test\n===========================\n\n.. csv-table:: Testdetails\n    :header: \"Detail\", \"Information\"\n    :delim: ;\n\n    Package; canopen_tests\n    Test file; launch_tests/test_lifecycle_proxy_driver.py\n    Description; Tests nmt, sdo and lifecycle of lifecycle proxy driver\n    Prerequisites; vcan0 must be available\n\nProxy Driver Test\n===========================\n\n.. csv-table:: Testdetails\n    :header: \"Detail\", \"Information\"\n    :delim: ;\n\n    Package; canopen_tests\n    Test file; launch_tests/test_proxy_driver.py\n    Description; Tests nmt, sdo and lifecycle of proxy driver\n    Prerequisites; vcan0 must be available\n"
  },
  {
    "path": "canopen/sphinx/software-tests/ros2_control_system-test.rst",
    "content": "ros2_control SystemInterface test\n=================================\n\nTest details\n------------\n\n.. csv-table:: Tests\n    :header: \"Detail\", \"Information\"\n    :delim: ;\n\n    Package; canopen_tests\n    Test file; launch/canopen_system.launch.py\n    Description; Create an exemplary ros2_control SystemInterface with CAN master and communicates to a slave node.\n    Prerequisites; vcan0 must be available\n\nTo bring up vcan0:\n\n   .. code-block:: bash\n\n      sudo modprobe vcan\n      sudo ip link add dev vcan0 type vcan\n      sudo ip link set vcan0 txqueuelen 1000\n      sudo ip link set up vcan0\n\n\nExplanation of the test\n------------------------\n\nThe test starts generic system interface and generic proxy controller for CanOpen devices.\nGeneric system interface enables integration of values from the CAN Bus into ros2_control framework and the controller enables you to send and receive data from the CAN bus through ros2_control to ROS2.\n\nThe next few lines show you some command to have exemplary usage of the ros2_control integration:\n\n1. After the test is started check ``/dynamic_joint_states`` to show internal data from CAN nodes in ros2_control system.\n\n   .. code-block:: bash\n\n      ros2 topic echo /dynamic_joint_states\n\n\n2. Open a new terminal and echo data from the topic ``/node_1_controller/rpdo``.\n\n   .. code-block:: bash\n\n      ros2 topic echo /node_1_controller/rpdo\n\n\n3. Open a new terminal reset the state of nmt.\n\n   .. code-block:: bash\n\n      ros2 service call /node_1_controller/nmt_reset_node std_srvs/srv/Trigger {}\n\n   You will expect changes in the ``/dynamic_joint_states`` topic.\n\n\n4. In a new terminal publish some data to the controller to write them to the CAN bus:\n\n   .. code-block:: bash\n\n      ros2 topic pub --once /node_1_controller/tpdo canopen_interfaces/msg/COData \"\n      index: 0x4000\n      subindex: 0\n      data: 0x1122\"\n\n   Now watch how data in the topic ``/node_1_controller/rpdo`` are changing. There is a mirror of the data on 0x4001.\n   That is, the slave node will mirror the data on 0x4001 via its tpdo and the proxy device will get the data via its rpdo.\n   You should see this\n\n   .. code-block:: bash\n\n      index: 16385  # This is 0x4001\n      subindex: 0\n      data: 4386\n      ---\n"
  },
  {
    "path": "canopen/sphinx/user-guide/cia402-driver.rst",
    "content": "Cia402 Driver\n========================\n\nThe Cia402 Driver implements the CIA402 profile for motion controllers and enables setting\nthe drive status, operation mode and sending target values to the motion controller.\n\n.. csv-table:: CIA402 Drivers\n   :header: Type, Package, Name\n   :widths: 30, 20, 50\n\n   lifecycle, canopen_402_driver, ros2_canopen::LifecycleCia402Driver\n   simple, canopen_402_driver, ros2_canopen::Cia402Driver\n\nServices\n--------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n  :align: left\n\n  * - Services\n    - Type\n    - Description\n  * - ~/nmt_reset_node\n    - Trigger\n    - Resets CANopen Device the Proxy Device Node manages.\n  * - ~/sdo_read\n    - CORead\n    - Reads an SDO object from the specified index, subindex and datatype of the remote device.\n  * - ~/sdo_write\n    - COWrite\n    - Writes data to an SDO object on the specified index, subindex and datatype of the remote device.\n  * - ~/init\n    - Trigger\n    - Initialises motion controller including referencing\n  * - ~/recover\n    - Trigger\n    - Recovers motion controller\n  * - ~/halt\n    - Trigger\n    - Stops motion controller\n  * - ~/position_mode\n    - Trigger\n    - Switches to profiled position mode\n  * - ~/velocity_mode\n    - Trigger\n    - Switches to profiled velocity mode\n  * - ~/torque_mode\n    - Trigger\n    - Switches to profiled torque mode\n  * - ~/cyclic_position_mode\n    - Trigger\n    - Switches to cyclic position mode\n  * - ~/cyclic_velocity_mode\n    - Trigger\n    - Switches to cyclic velocity mode\n  * - ~/cyclic_torque_mode\n    - Trigger\n    - Switches to cyclic torque mode\n  * - ~/interpolated_position_mode\n    - Trigger\n    - Switches to interpolated position mode, only linear mode with fixed time is supported\n  * - ~/target\n    - CODouble\n    - Sets the target value. Only accepted when an operation mode is set.\n\nPublishers\n----------\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n  :align: left\n\n  * - Publishers\n    - Type\n    - Description\n  * - ~/joint_states\n    - sensor_msgs/msg/JointState\n    - Joint states of the drive\n  * - ~/nmt_state\n    - String\n    - Publishes NMT state on change\n  * - ~/rpdo\n    - COData\n    - Publishes received PDO objects on reception\n\n\nSubscribers\n-----------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n\n  * - Topic\n    - Type\n    - Description\n  * - ~/target\n    - COTargetDouble\n    - Sets target value.\n  * - ~/tpdo\n    - COData\n    - Writes received data to remote device if the specified object is RPDO mapped on remote device.\n\nBus Configuration Parameters\n----------------------------\nAdditional parameters that can be used in bus.yml for this driver.\n\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n\n  * - Parameter\n    - Type\n    - Description\n  * - polling\n    - bool\n    - Enables polling of the drive status. Default: true. If false, period will be used to run a ros2 timer as update loop. If true, the update loop will be triggered by the sync signal and directly executed in the canopen realtime loop. This requires all data processed in the update loop to be PDO, otherwise the loop will get stuck. This can speed reduce processor load significantly though.\n  * - period\n    - Milliseconds\n    - Refresh period for 402 state machine. Should be similar to sync period of master.\n  * - switching_state\n    - see below\n    - The state to switch the operation mode in.\n  * - scale_pos_to_dev\n    - double\n    - Scaling factor to convert from SI units to device units for position.\n  * - offset_pos_to_dev\n    - double\n    - Offset in device units added to scaled position commands sent to the device.\n  * - scale_vel_to_dev\n    - double\n    - Scaling factor to convert from SI units to device units for velocity.\n  * - scale_pos_from_dev\n    - double\n    - Scaling factor to convert from device units to SI units for position.\n  * - offset_pos_from_dev\n    - double\n    - Offset in SI units to added to scaled position reports from the device.\n  * - scale_vel_from_dev\n    - double\n    - Scaling factor to convert from device units to SI units for velocity.\n  * - position_mode\n    - int\n    - The drives operation mode to use for the position interface\n  * - velocity_mode\n    - int\n    - The drives operation mode to use for the velocity interface\n  * - torque_mode\n    - int\n    - The drives operation mode to use for the torque interface\n"
  },
  {
    "path": "canopen/sphinx/user-guide/configuration.rst",
    "content": "Configuration Package\n=====================\n\nA configuration package contains one or more configurations for the CANopen\nstack. The configuration package needs to hold the EDS/DCF files for each device,\nthe bus configuration and the launch files for the different configurations.\n\nConsequently, the structure of the configuration package should look as follows:\n\n    ::\n\n          {package_name}\n          ├── config\n          │   ├── {bus_config_name_1}\n          │   |   ├── bus.yml\n          │   |   ├── {device1}.eds\n          │   |   ├── {device...}.eds\n          │   |   └── {slave_n}.eds\n          │   └── {bus_config_name_2}\n          │       ├── bus.yml\n          │       ├── {device1}.eds\n          │       ├── {device...}.eds\n          │       └── {slave_n}.eds\n          ├── launch\n          │   ├── {bus_config_name_1}.launch.py\n          |   └── {bus_config_name_1}.launch.py\n          ├── CMakeLists.txt\n          └── package.xml\n\n\n\nBus Configuration File\n============================\n\nThe ros2_canopen stack relies on a YAML configuration file that is used\nfor configuring the bus topology and specifying configurations for\neach device. The file details which devices connected to the bus, which\nEDS/DCF file applies to them, which parameters of the EDS/DCF files should be\noverwritten and which drivers should be used to control the devices.\n\nStructure\n---------\n\nThe YAML configuration file has the following sections:\n\n.. code-block:: yaml\n\n  options: # General options especially dcf_path\n    [configuration item]: [value]\n\n  master: # The configuration of the master\n    [configuration item]: [value]\n    [...]\n\n  defaults: # Defaults that apply to all slave nodes\n    [configuration item]: [value]\n    []\n\n  nodes: # Configurations for all slave nodes\n    - [device_name]:\n        [configuration item]: [value]\n        [...]\n\n\nOptions Section\n---------------\nThe options section holds general options. Right now these are only the following.\n\n.. csv-table:: Options Configuration\n  :header-rows: 1\n  :class: longtable\n  :delim: ;\n  :widths: 1 1\n\n  configuration item; description\n  dcf_path;\tThe directory in which the generated .bin file will be available at runtime. You can set this to \"@BUS_CONFIG_PATH@\" and it will be auto-generated by cmake.\n\n\nMaster Section\n--------------\nThe master section has a number of configuration options. These are not unique to ros2_canopen\nbut come from the lely core library. Below you find a list of possible configuration items.\n\n.. csv-table:: Master Configuration\n  :header-rows: 1\n  :class: longtable\n  :delim: ;\n  :widths: 1 1\n\n  configuration item; description\n  node_id; The node-ID (default: 255)\n  driver; The fully qualified class name of the master to use.\n  package; The ros2 package name in which the master class can be found.\n  namespace; The namespace in which the master will be created (default: \"/\").\n  baudrate; The baudrate in kbit/s (default: 1000)\n  vendor_id;The vendor-ID (default: 0x00000000)\n  product_code;The product code (default: 0x00000000)\n  revision_number;\t The revision number (default: 0x00000000).\n  serial_number; \tThe serial number (default: 0x00000000).\n  heartbeat_multiplier;\tThe multiplication factor used to obtain the slave heartbeat consumer time from the master heartbeat producer time (default: see options section).\n  heartbeat_consumer;\tSpecifies whether the master should monitor the heartbeats of the slaves (default: true).\n  heartbeat_producer;\tThe heartbeat producer time in ms (default: 0).\n  emcy_inhibit_time;\tThe EMCY inhibit time in multiples of 100 μs (default: 0, see object 1015).\n  sync_period;\tThe SYNC interval in μs (default: 0).\n  sync_window;\tThe SYNC window length in μs (default: 0, see object 1007).\n  sync_overflow;\tThe SYNC counter overflow value (default: 0, see object 1019).\n  error_behavior;\tA dictionary of error behaviors for different classes or errors (default: {1: 0x00}, see object 1029).\n  nmt_inhibit_time;\tThe NMT inhibit time in multiples of 100 μs (default: 0, see object 102A).\n  start;\tSpecifies whether the master shall switch into the NMT operational state by itself (default: true, see bit 2 in object 1F80).\n  start_nodes;\tSpecifies whether the master shall start the slaves (default: true, see bit 3 in object 1F80).\n  start_all_nodes;\tSpecifies whether the master shall start all nodes simultaneously (default: false, see bit 1 in object 1F80).\n  reset_all_nodes;\tSpecifies whether all slaves shall be reset in case of an error event on a mandatory slave (default: false, see bit 4 in object 1F80).\n  stop_all_nodes;\tSpecifies whether all slaves shall be stopped in case of an error event on a mandatory slave (default: false, see bit 6 in object 1F80).\n  boot_time;\tThe timeout for booting mandatory slaves in ms (default: 0, see object 1F89).\n  boot_timeout;\tThe timeout for booting all slaves in ms (default: 2000ms).\n\nDevice Section\n--------------\nThe device configuration enables configuring the characteristics of the connected CANopen\ndevice.\n\n.. note::\n  It is important to note, that you choose the operation (simple nodes or managed nodes) by choosing\n  either only lifecycle drivers or only simple drivers.\n\n  **Mixing them will not work!**\n\n.. csv-table:: Device Configuration\n  :header-rows: 1\n  :class: longtable\n  :delim: ;\n  :widths: 1 1\n\n  configuration item; description\n  driver; The fully qualified class name of the driver to use.\n  package; The ros2 package name in which the driver class can be found.\n  namespace; The namespace in which the driver will be created (default: \"/\").\n  enable_lazy_load; A flag that states whether the driver is loaded on start-up.\n  dcf;\tThe filename of the EDS/DCF describing the slave (mandatory).\n  dcf_path;\tThe directory in which the generated .bin file will be available at runtime (default: see options section).\n  node_id;\tThe node-ID (default: 255, can be omitted if specified in the DCF).\n  revision_number;\tThe revision number (default: 0x00000000, can be omitted if specified in the DCF).\n  serial_number;\tThe serial number (default: 0x00000000, can be omitted if specified in the DCF).\n  heartbeat_multiplier;\tThe multiplication factor used to obtain master heartbeat consumer time from the slave heartbeat producer time (default: see options section).\n  heartbeat_consumer;\tSpecifies whether the slave should monitor the heartbeat of the master (default: false).\n  heartbeat_producer;\tThe heartbeat producer time in ms (default: 0).\n  error_behavior;\tA dictionary of error behaviors for different classes or errors (default: {}, see object 1029).\n  rpdo;\tThe Receive-PDO configuration (see below).\n  tpdo;\tThe Transmit-PDO configuration (see below).\n  boot;\tSpecifies whether the slave will be configured and booted by the master (default: true, see bit 2 in object 1F81).\n  mandatory;\tSpecifies whether the slave is mandatory (default: false, see bit 3 in object 1F81).\n  reset_communication;\tSpecifies whether the NMT reset communication command may be sent to the slave (default: true, see bit 4 in object 1F81).\n  software_file;\tThe name of the file containing the firmware (default: \"\", see object 1F58).\n  software_version;\tThe expected software version (default: 0x00000000, see object 1F55).\n  configuration_file;\tThe name of the file containing the configuration (default: \"<dcf_path>/<name>.bin\" (where <name> is the section name), see object 1F22).\n  restore_configuration;\tThe sub-index of object 1011 to be used when restoring the configuration (default: 0x00).\n  sdo_timeout_ms; The timeout to use for SDO reads/writes to this device. (default: 20ms)\n  sdo;\tAdditional SDO requests to be sent during configuration (see below).\n\n\nFurther references\n------------------\nThe dcfgen documentation gives more details on the usage of the dcfgen tool for generating DCF: https://opensource.lely.com/canopen/docs/dcf-tools/\n\nVariables\n---------\n\n``@BUS_CONFIG_PATH@:`` Automatic config path definition if configuration package structure is followed.\n\n\n\n\nConfiguration Package CMake\n===========================\n\nIn order to build the configuration package and generate the necessary runtime artifacts from the\nbus configuration file and eds/dcf files, the lely_core_libraries package contains an extra\nCMAKE macro.\n\n**cogen_dcf(target)**\n\nTarget: the name of the configuration (e.g. for config/{bus_config_name_1} is bus_config_name_1)\n\n.. code-block::\n\n  cogen_dcf(bus_config)\n"
  },
  {
    "path": "canopen/sphinx/user-guide/how-to-create-a-cia301-system.rst",
    "content": "How to create a cia301 system with ros2_control\n=================================================\n\nThe CiA 301 profile, also known as the CANopen application layer,\nis the foundation of the CANopen protocol. It defines the basic principles,\ncommunication services, and object dictionary used for device communication\nand network management in a CANopen system.\n\nThe CiA 301 profile defines several communication services that allow devices\nto exchange data and perform actions. These services include\nthe SDO (Service Data Object) service for transferring object data between devices,\nthe PDO (Process Data Object) service for real-time data exchange,\nand the NMT (Network Management) service for network initialization,\ndevice state control, and error handling.\n\nTo bring up the CiA301 interface using ROS2, it includes three steps:\n\n- preparing the configuration for bus and ``ros2_control``\n- preparing the state and command interfaces,\n- and finally preparing the launch file.\n\n\nPreparing the configuration\n--------------------------------------------------------\nTo use the control system interface for CiA301 profile, we should prepare the following\n\n- bus_conf\n- master_dcf\n- master_bin\n- can_interface, (default: vcan0)\n\nDefine the bus configuration parameters\n\n.. code-block:: yaml\n\n    master:\n        node_id: 1\n        driver: \"ros2_canopen::MasterDriver\"\n        package: \"canopen_master_driver\"\n        baudrate: 250\n    options:\n        dcf_path: \"@BUS_CONFIG_PATH@\"\n    joint_1:\n        node_id: 0x00\n        dcf: \"joint.eds\"\n        driver: \"ros2_canopen::ProxyDriver\"\n        package: \"canopen_proxy_driver\"\n        reset_communication: false\n    joint_2:\n        node_id: 0x01\n        dcf: \"joint.eds\"\n        driver: \"ros2_canopen::ProxyDriver\"\n        package: \"canopen_proxy_driver\"\n        reset_communication: false\n\nDefine the ``ros2_control`` parameters\n\n.. code-block:: yaml\n\n    controller_manager:\n        ros__parameters:\n            update_rate: 100  # Hz\n\n            joint_state_broadcaster:\n                type: joint_state_broadcaster/JointStateBroadcaster\n\n            joint_1_controller:\n                type: canopen_ros2_controllers/CanopenProxyController\n\n            joint_2_controller:\n                type: canopen_ros2_controllers/CanopenProxyController\n\n        joint_1_controller:\n            ros__parameters:\n                joint: joint_1\n\n\n       joint_2_controller:\n            ros__parameters:\n                joint: joint_2\n\nThe example of master_dcf see https://github.com/ros-industrial/ros2_canopen/blob/master/canopen_tests/config/simple/simple.eds\n\n\nUse RPDO to access the current state\n--------------------------------------------------------\nDefining the Joint and CANopen Data Structure\n The first step is to define a structure that will hold information about your joints and the associated CANopen data. This structure serves as the foundation for  your CANopen network, ensuring that all the relevant data is stored and accessible when needed.\n\nPDO Index and Subindex\n Each Process Data Object (PDO) has an index and a subindex. The index acts as a unique identifier for each PDO, differentiating it from other PDOs in the system. The subindex is used to access individual data fields within each PDO as a PDO can contain multiple data fields.\n\nNetwork Management (NMT)\n Network Management (NMT) is a fundamental service in the CANopen protocol suite. It offers basic device control commands such as start, stop, and reset, and manages the state of devices within the network.\n\n For RPDOs, the data are defined using:\n\n - \"rpdo/index\"\n - \"rpdo/subindex\"\n - \"rpdo/type\"\n - \"rpdo/data\"\n\n For NMT, we can read the states via:\n\n - \"nmt/state\"\n\n\nUse TPDO to send commands\n----------------------------\nIn order to send commands to hardware devices in a CANopen network, we first need to export the appropriate hardware interfaces. This is a critical step that enables us to effectively control each joint within our network.\n\nRegistering Transmit Process Data Objects (TPDOs)\n Similar to how we handle state interfaces, we must register Transmit Process Data Objects (TPDOs) for each joint. These TPDOs are related to the following commands:\n\n- \"tpdo/index\"\n- \"tpdo/subindex\"\n- \"tpdo/type\"\n- \"tpdo/data\"\n- \"tpdo/owns\"\n\nNetwork Management (NMT) Commands\n Beyond this, we have the ability to register commands associated with Network Management (NMT) to control the state of devices within our network. This is important for the smooth operation and control of our devices. The NMT related commands include:\n\n- \"nmt/reset\"\n- \"nmt/reset_fbk\"\n- \"nmt/start\"\n- \"nmt/start_fbk\"\n\nThese NMT commands not only help in managing the state of devices but also in providing feedback (indicated by \"fbk\") from the device to the control system after the execution of a command. This feedback mechanism is crucial for ensuring the successful execution of commands and managing the overall health of the network.\n\n\nHow to launch the nodes\n----------------------------\nFinally, we prepare the launch file for the interface. An example see: https://github.com/ros-industrial/ros2_canopen/blob/master/canopen_ros2_control/launch/canopen_system.launch.py\n\nFor testing, please refer to following section.\n"
  },
  {
    "path": "canopen/sphinx/user-guide/how-to-create-a-configuration.rst",
    "content": "How to create a configuration package\n========================================\nIn order to use the ros2_canopen stack for your robot, you need to\ncreate a configuration package, that holds the configuration of the\nbus as well as you launch script. The following sections detail the\nsteps to create such a package.\n\n\nPackage creation\n----------------\nWhen you create your package, you have to first make some decisions.\nYou will need to choose a package name, decide which bus configurations\nyou need to have (usually one per CAN interface) and which slaves you have.\n\n| **package_name**: Name of the package\n| **bus_config_name**: Name of the the bus configuration (you can have multiple)\n\nYou can use ``ros2 pkg create`` command to create your package.\n\n.. code-block:: console\n\n  $ ros2 pkg create --dependencies canopen lely_core_libraries --build-type ament_cmake {package_name}\n  $ cd {package_name}\n  $ rm -rf src\n  $ rm -rf include\n  $ mkdir -p launch\n  $ mkdir -p config\n\nNow your package directory should look like this.\n\n::\n\n      {package_name}\n      ├── config\n      ├── launch\n      ├── CMakeLists.txt\n      └── package.xml\n\n\n\nBus configuration creation\n------------------------------\n\n#. **Bus configuration decisions**\n    Decide how many bus configurations you need. Add one subfolder for each\n    bus configuration in your `config`-folder.\n\n    .. code-block:: bash\n\n      $ mkdir -p {bus_config_name}\n\n#. **Add device information to bus configurations**\n    Once you created the folders for your bus configurations add the .eds files\n    for the devices that are in the bus configuration to the respective folder.\n\n    Now your package directory should now look like this.\n\n    ::\n\n          {package_name}\n          ├── config\n          │   ├── {bus_config_name_1}\n          │   |   ├── {device1}.eds\n          │   |   ├── {device...}.eds\n          │   |   └── {slave_n}.eds\n          │   └── {bus_config_name_2}\n          │       ├── {device1}.eds\n          │       ├── {device...}.eds\n          │       └── {slave_n}.eds\n          ├── CMakeLists.txt\n          └── package.xml\n\n#. **Create the bus configuration specifications**\n    To specify the bus configuration ros2_canopen uses the a YAML-file called\n    bus.yml. Create the file in the respective bus configuration folder.\n\n    .. code-block:: console\n\n      $ touch bus.yml\n\n    ::\n\n          {package_name}\n          ├── config\n          │   ├── {bus_config_name_1}\n          │   |   ├── bus.yml\n          │   |   ├── {device1}.eds\n          │   |   ├── {device...}.eds\n          │   |   └── {slave_n}.eds\n          │   └── {bus_config_name_2}\n          │       ├── bus.yml\n          │       ├── {device1}.eds\n          │       ├── {device...}.eds\n          │       └── {slave_n}.eds\n          ├── CMakeLists.txt\n          └── package.xml\n\n#. **Edit the bus configuration specifications**\n    You need to modify each bus.yml file according to your needs.\n    First you need to define where these files and generated files will be\n    found at runtime. This is usually the following if you use colcon to\n    build from source.\n\n    .. code-block:: yaml\n\n      options:\n        dcf_path: install/{package_name}/share/{package_name}/config/{bus_config_name}\n\n    Then you need to define your master.\n\n    .. code-block:: yaml\n\n      master:\n        node_id: [node id]\n        package: [ros2 package where to find the master driver (usually canopen_core)]\n        driver: [component type of the driver (ros2_canopen::MasterDriver or ros2_canopen::LifecycleMasterDriver)]\n\n    Make sure, that you specify a lifecycle master if you use the lifecycled version of ros2_canopen.\n    And add other configuration data as necessary. A documentation of configuration options\n    available can be found in the :doc:`configuration` documentation.\n\n    Once you have defined the configuration of your master, add your slaves. The following\n    describes the mandatory data per slave. Further configuration options can be found in the :doc:`configuration` documentation.\n    The slave name is the node name that will be assigned to the driver.\n\n    .. code-block:: yaml\n\n      nodes:\n        - [unique slave name]:\n          node_id: [node id]\n          package: [ros2 package where to find the driver]\n          driver: [qualified name of the driver]\n\n    Make sure you use a lifecycle slave if you use the lifecycled version of ros2_canopen.\n\n\nLaunch configuration creation\n-----------------------------\n\nCreate a launch folder in your package directory and a launch file.\n\n.. code-block:: console\n\n  mkdir launch\n  touch {...}.launch.py\n\nAdd the following code:\n\n.. code-block:: python\n\n  def generate_launch_description():\n        \"\"\"Generate launch description with multiple components.\"\"\"\n        path_file = os.path.dirname(__file__)\n\n        ld = launch.LaunchDescription()\n\n\n        device_container = IncludeLaunchDescription(\n            PythonLaunchDescriptionSource(\n                [\n                    os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                    \"/canopen.launch.py\",\n                ]\n            ),\n            launch_arguments={\n                \"master_config\": os.path.join(\n                    get_package_share_directory(\"{package_name}\"),\n                    \"config\",\n                    \"{bus_config_name}\",\n                    \"master.dcf\",\n                ),\n                \"master_bin\": os.path.join(\n                    get_package_share_directory(\"{package_name}\"),\n                    \"config\",\n                    \"{bus_config_name}\",\n                    \"master.bin\",\n                ),\n                \"bus_config\": os.path.join(\n                    get_package_share_directory(\"{package_name}\"),\n                    \"config\",\n                    \"{bus_config_name}\",\n                    \"bus.yml\",\n                ),\n                \"can_interface_name\": \"{can_interface_name i.e. can0}\",\n            }.items(),\n\n        )\n\n        ld.add_action(device_container)\n\n        return ld\n\n\nCMAKE Configuration creation\n-----------------------------\nFinally we need to adjust the CMakeLists.txt file to pick everything up correctly.\n\n.. code-block:: cmake\n\n  cmake_minimum_required(VERSION 3.8)\n  project({package_name})\n\n  if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n    add_compile_options(-Wall -Wextra -Wpedantic)\n  endif()\n\n  # find dependencies\n  find_package(ament_cmake REQUIRED)\n  find_package(canopen_core REQUIRED)\n  find_package(canopen_interfaces REQUIRED)\n  find_package(canopen_base_driver REQUIRED)\n  find_package(canopen_proxy_driver REQUIRED)\n  find_package(lely_core_libraries REQUIRED)\n\n\n  cogen_dcf({bus_config_name})\n\n  install(DIRECTORY\n    launch/\n    DESTINATION share/${PROJECT_NAME}/launch/\n  )\n\n  install(DIRECTORY\n    launch_tests/\n    DESTINATION share/${PROJECT_NAME}/launch_tests/\n  )\n\n\n  if(BUILD_TESTING)\n    find_package(ament_lint_auto REQUIRED)\n    # the following line skips the linter which checks for copyrights\n    # comment the line when a copyright and license is added to all source files\n    set(ament_cmake_copyright_FOUND TRUE)\n    # the following line skips cpplint (only works in a git repo)\n    # comment the line when this package is in a git repo and when\n    # a copyright and license is added to all source files\n    set(ament_cmake_cpplint_FOUND TRUE)\n    ament_lint_auto_find_test_dependencies()\n  endif()\n\n  ament_package()\n"
  },
  {
    "path": "canopen/sphinx/user-guide/how-to-create-a-robot-system.rst",
    "content": "How to create a robot system with ros2_control\n==============================================\nThis guide describes how to create a simple robot using the robot system hardware interface\nleveragin ros2_control.\n\n1. Create a new configuration package with the name ``canopen_robot_control_example``.\n\n  .. code-block:: console\n\n    $ ros2 pkg create --dependencies canopen lely_core_libraries --build-type ament_cmake {package_name}\n    $ cd {package_name}\n    $ rm -rf src\n    $ rm -rf include\n    $ mkdir -p launch\n    $ mkdir -p config\n\n2. Create a new bus configuration folder with the name ``robot_control``.\n\n  .. code-block:: console\n\n    $ mkdir -p config/robot_control\n\n3. Create a new bus configuration file with the name ``bus.yml``.\n\n  .. code-block:: console\n\n    $ touch config/robot_control/bus.yml\n\n4. Add the following content to the ``bus.yml`` file.\n\n.. code-block:: yaml\n\n  options:\n    dcf_path: \"@BUS_CONFIG_PATH@\"\n\n  master:\n    node_id: 1\n    driver: \"ros2_canopen::MasterDriver\"\n    package: \"canopen_master_driver\"\n    sync_period: 10000\n\n  defaults:\n    dcf: \"cia402_slave.eds\"\n    driver: \"ros2_canopen::Cia402Driver\"\n    package: \"canopen_402_driver\"\n    period: 10\n    position_mode: 1\n    revision_number: 0\n    sdo:\n      - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n      - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n      - {index: 0x6081, sub_index: 0, value: 1000}\n      - {index: 0x6083, sub_index: 0, value: 2000}\n      - {index: 0x6060, sub_index: 0, value: 7}\n    tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n      1:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6041, sub_index: 0} # status word\n          - {index: 0x6061, sub_index: 0} # mode of operation display\n      2:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6064, sub_index: 0} # position actual value\n          - {index: 0x606c, sub_index: 0} # velocity actual position\n    rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n      1:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n        - {index: 0x6040, sub_index: 0} # controlword\n        - {index: 0x6060, sub_index: 0} # mode of operation\n      2:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n        - {index: 0x607A, sub_index: 0} # target position\n\n  nodes:\n    joint_1:\n      node_id: 2\n    joint_2:\n      node_id: 3\n\n5. Copy the ``cia402_slave.eds`` file from the ``canopen_tests/config/robot_control`` package to the ``config/robot_control`` folder.\n\n6. Create a ros2_controllers.yaml and add the following content.\n\n.. code-block:: yaml\n\n  controller_manager:\n    ros__parameters:\n      update_rate: 100  # Hz\n      joint_state_broadcaster:\n        type: joint_state_broadcaster/JointStateBroadcaster\n\n      forward_position_controller:\n        type: forward_command_controller/ForwardCommandController\n\n  forward_position_controller:\n    ros__parameters:\n      joints:\n        - joint1\n        - joint2\n      interface_name: position\n\n7. Create a launch file with the name ``robot_control.launch.py`` in the launch directory of your package and add the following content.\n\n.. code-block:: python\n\n  from launch import LaunchDescription\n  from launch.actions import DeclareLaunchArgument\n  from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\n  from launch_ros.actions import Node\n  from launch_ros.substitutions import FindPackageShare\n  from launch.actions import IncludeLaunchDescription\n  from launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\n  def generate_launch_description():\n      robot_description_content = Command(\n          [\n              PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n              \" \",\n              PathJoinSubstitution(\n                  [\n                      FindPackageShare(\"canopen_tests\"),\n                      \"urdf\",\n                      \"robot_controller\",\n                      \"robot_controller.urdf.xacro\",\n                  ]\n              ),\n          ]\n      )\n      robot_description = {\"robot_description\": robot_description_content}\n      robot_control_config = PathJoinSubstitution(\n          [FindPackageShare(\"canopen_tests\"), \"config/robot_control\", \"ros2_controllers.yaml\"]\n      )\n\n      control_node = Node(\n          package=\"controller_manager\",\n          executable=\"ros2_control_node\",\n          parameters=[robot_description, robot_control_config],\n          output=\"screen\",\n      )\n\n      joint_state_broadcaster_spawner = Node(\n          package=\"controller_manager\",\n          executable=\"spawner\",\n          arguments=[\"joint_state_broadcaster\", \"--controller-manager\", \"/controller_manager\"],\n      )\n\n      forward_position_controller_spawner = Node(\n          package=\"controller_manager\",\n          executable=\"spawner\",\n          arguments=[\"forward_position_controller\", \"--controller-manager\", \"/controller_manager\"],\n      )\n\n      robot_state_publisher_node = Node(\n          package=\"robot_state_publisher\",\n          executable=\"robot_state_publisher\",\n          output=\"both\",\n          parameters=[robot_description],\n      )\n\n      slave_config = PathJoinSubstitution(\n          [FindPackageShare(\"canopen_tests\"), \"config/robot_control\", \"cia402_slave.eds\"]\n      )\n\n      slave_launch = PathJoinSubstitution(\n          [FindPackageShare(\"canopen_fake_slaves\"), \"launch\", \"cia402_slave.launch.py\"]\n      )\n      slave_node_1 = IncludeLaunchDescription(\n          PythonLaunchDescriptionSource(slave_launch),\n          launch_arguments={\n              \"node_id\": \"2\",\n              \"node_name\": \"slave_node_1\",\n              \"slave_config\": slave_config,\n          }.items(),\n      )\n\n      slave_node_2 = IncludeLaunchDescription(\n          PythonLaunchDescriptionSource(slave_launch),\n          launch_arguments={\n              \"node_id\": \"3\",\n              \"node_name\": \"slave_node_2\",\n              \"slave_config\": slave_config,\n          }.items(),\n      )\n\n      nodes_to_start = [\n          control_node,\n          joint_state_broadcaster_spawner,\n          forward_position_controller_spawner,\n          robot_state_publisher_node,\n          slave_node_1,\n          slave_node_2\n      ]\n\n      return LaunchDescription(nodes_to_start)\n\n8. Create a urdf folder add all files from the ``canopen_tests/urdf/robot_controller`` package to the urdf folder of your package.\n\n9. Edit the CMakeLists.txt file of your package and add the following lines after the find_package section.\n\n.. code-block:: cmake\n\n  cogen_dcf(robot_control)\n\n  install(DIRECTORY\n  launch urdf\n  DESTINATION share/${PROJECT_NAME})\n\n10. Build your package and source the setup.bash file.\n11. Start your launch file\n12. You can now control the robot with the forward_command_controller. You can as well visualize the robot in\n    rviz by adding a tf or a robot model and setting the fixed frame to ``base_link``. You can move the robot with the\n    following command.\n\n.. code-block:: bash\n\n  ros2 topic pub /joint1/forward_position_controller/command std_msgs/msg/Float64 \"data: [1.0, 1.0]\"\n"
  },
  {
    "path": "canopen/sphinx/user-guide/master.rst",
    "content": "Master Driver\n=============\n\nThe master driver handles the creation of the necessary can interface and sets up a canopen event loop which drivers can hook onto.\nIn addition, the node offers services for communicating with nodes via nmt and sdo.\n\n.. csv-table:: Master Drivers\n   :header: Type, Package, Name\n   :widths: 30, 20, 50\n\n   lifecycle, canopen_master_driver, ros2_canopen::LifecycleMasterDriver\n   simple, canopen_master_driver, ros2_canopen::MasterDriver\n\n\nServices\n--------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n\n  * - Services\n    - Type\n    - Description\n  * - ~/read_sdo\n    - COReadID\n    - Reads an SDO object specified by Index, Subindex and Datatype of the device with the specified nodeid.\n  * - ~/write_sdo\n    - COWriteID\n    - Writes Data to an SDO object specified by Index, Subindex and Datatype on the device with the specified nodeid.\n  * - ~/set_nmt\n    - CONmtID\n    - Sends the NMT command to the device with the specified nodeid\n"
  },
  {
    "path": "canopen/sphinx/user-guide/operation/managed-service-interface.rst",
    "content": "Managed Service Interface\n============================\n\n\nDevice Container with managed nodes\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe device container implements ROS2 component manager. The load and unload services are disabled.\nDevices are loaded based on the Bus Configuration File (bus.yml). The device container provides\nthe list service, which can be used with ros2cli to check which components have been loaded.\n\n.. figure:: ../../images/device-manager.png\n    :alt: Device Manager Concept\n\n    device manager concept\n\nThe device container uses the bus description file to identify the correct drivers for each devices.\nOn launch it will load the CANopen master node and driver nodes and pass the appropriate configuration\ndata to the nodes. The nodes are now in unconfigured state.\n\nWhen using the default launch files in canopen_core the lifecycle manager node will automatically\nbe launched. The lifecycle manager takes care of sequencing the lifecycle of the different nodes in the\ndevice container. By bringing the lifecycle_manager to active lifecycle state, all master and driver nodes\nwill be activated in correct sequence.\n\nIf you choose to write your own lifecycle_manager, you'll need to remember, that the master needs\nto be configured and activated before any driver node can be configured or activated.\n\n\nBus Configuration\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe bus configuration for the managed service interface needs to use the driver classes that are marked as\nlifecycle drivers. The master driver indicates whether the bus.yml will be treated as managed or un-managed\nservice interface.\n\n.. csv-table:: Available Driver Components\n   :header: \"Package\", \"Component\"\n\n    canopen_master_driver, ros2_canopen::LifecycleMasterDriver\n    canopen_proxy_driver, ros2_canopen::LifecycleProxyDriver\n    canopen_402_driver, ros2_canopen::LifecycleCia402Driver\n\nLaunching\n\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe device manager has the following configuration parameters.\n\n.. csv-table:: Parameters\n   :header: \"Parameter\", \"Type\", \"Description\"\n\n    bus_conf, string, (Mandatory) Path to the bus configuration YAML-file\n    master_dcf, string, (Mandatory) Path to the DCF file to be used by the master node. Usually generated by dcfgen as master.dcf.\n    master_bin, string, (Optional) Path to the concise DCF (.bin) file to be used to configure the master. Usually generated by dcfgen as master.bin. (default: \"\")\n    can_interface_name, string, (Mandatory) Name of the CAN interface to be used. (default: vcan0)\n"
  },
  {
    "path": "canopen/sphinx/user-guide/operation/ros2-control-interface.rst",
    "content": "Hardware Interface\n------------------\nThis package provides multiple hardware interfaces for testing. Mainly the following:\n\n- canopen_ros2_control/CanopenSystem: A system interface for ProxyDrivers\n- canopen_ros2_control/Cia402System: A system interface for Cia402Drivers\n- canopen_ros2_control/Cia402RobotSystem: A system interface for Cia402Drivers in a robot configuration (under development)\n\n\nRobot System Interface\n''''''''''''''''''''''\n\nThe robot system interface takes a number of inputs from the robot description (urdf).\nIt will make the Cia402Drivers available via the ros2_control hardware interface.\nThe bus has to still be defined in the bus.yml file. In the urdf you can the choose the\nCANopen nodes that have a Cia402Driver attached to them.\n\nThe ros2_control interface only works with non-lifecycle drivers right now.\nFor each joint in your urdf you can choose the attached CANopen device by using the\n``node_id`` parameter. The ``node_id`` parameter is the CANopen node id of the device.\n\n.. code-block:: xml\n\n    <ros2_control name=\"${name}\" type=\"system\">\n        <hardware>\n            <plugin>canopen_ros2_control/Cia402RobotSystem</plugin>\n            <param name=\"bus_config\">[path to bus.yml]</param>\n            <param name=\"master_config\">[path to master.dcf]</param>\n            <param name=\"can_interface_name\">[can interface to be used]</param>\n            <param name=\"master_bin\">[master.bin if it exists]</param>\n        </hardware>\n        <joint name=\"joint1\">\n            <param name=\"node_id\">3</param>\n            ...\n        </joint>\n        <joint name=\"joint2\">\n            <param name=\"node_id\">3</param>\n            ...\n        </joint>\n    </ros2_control>\n\n.. note::\n\n    You can find an example for the configuration in the ``canopen_tests`` package under robot_control.\n\n\nROS2 Controllers\n----------------\nThis package provides multiple controllers for testing. Mainly the following:\n\n- canopen_ros2_controllers/Cia402RobotController: Works with Robot System Interface\n- canopen_ros2_controllers/Cia402DeviceController: Works with Cia402System\n- canopen_ros2_controllers/CanopenProxyController: Works with CanopenSystem and Cia402System\n\nRobot Controller\n''''''''''''''''\n\nThe robot controller enables bringing up the different joints of the robot automatically\nby using the ros2_controller lifecycle. There is no need for further action, once the\ncontroller is activated, the drives are ready to be used.\n\nThe robot controller can be configured in the ros2_controllers.yaml with the following\nparameters:\n\n.. code-block:: yaml\n\n    robot_controller:\n        ros__parameters:\n            joints:  # joints that are controlled by the controller\n            - joint1\n            - joint2\n            operation_mode: 1 # operation mode of the controller\n            command_poll_freq: 5 # frequency with which the controller polls for command feedback\n"
  },
  {
    "path": "canopen/sphinx/user-guide/operation/service-interface.rst",
    "content": "Service Interface\n==================\n\n\nDevice Container\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe device container implements ROS2 component manager. The load and unload services are disabled.\nDevices are loaded based on the Bus Configuration File (bus.yml). It provides the list service though.\n\n.. figure:: ../../images/device-manager.png\n    :alt: Device Manager Concept\n\n    device manager concept\n\nThe device manager uses the bus description file to identify the correct drivers for each devices.\nOn launch it will load the CANopen master node and pass the generated DCF files to configure the CANopen master\ncorrectly for you bus configuration. It will the enable the master. Once the master is enabled it will\nsequentially load and enable all drivers in the bus configuration.\n\nOnce a CANopen Node comes online (i.e. sends the boot indication) the CANopen master\nwill configure the node with the parameters and commands specified in the bus configuration for that device.\nWhen the configuration of the device is done, all data send by the device is forwarded\nto the appropriate driver.\n\nAll loaded nodes are added to the device manager's executor.\n\n.. figure:: ../../images/device-manager-usage.png\n    :alt: Device Manager Usage\n\n    device manager usage\n\nBus Configuration\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe bus configuration for the needs to use the driver classes that are marked as\nnon lifecycle drivers.\n\n.. csv-table:: Available Driver Components\n   :header: \"Package\", \"Component\"\n\n    canopen_core, ros2_canopen::MasterDriver\n    canopen_proxy_driver, ros2_canopen::ProxyDriver\n    canopen_402_driver, ros2_canopen::Cia402Driver\n\nLaunching\n\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe device manager has the following configuration parameters.\n\n.. csv-table:: Parameters\n   :header: \"Parameter\", \"Type\", \"Description\"\n\n    bus_conf, string, (Mandatory) Path to the bus configuration YAML-file\n    master_dcf, string, (Mandatory) Path to the DCF file to be used by the master node. Usually generated by dcfgen as master.dcf.\n    master_bin, string, (Optional) Path to the concise DCF (.bin) file to be used to configure the master. Usually generated by dcfgen as master.bin. (default: \"\")\n    can_interface_name, string, (Mandatory) Name of the CAN interface to be used. (default: vcan0)\n"
  },
  {
    "path": "canopen/sphinx/user-guide/operation.rst",
    "content": "Operation\n=========\n\nThe ros2_canopen stack can be used in three different ways:\n\n* standard nodes container\n* managed nodes container\n* ros2_control system interface with standard nodes\n\n\nSimple nodes container\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe standard node container mode bundles the master and all slave driver nodes in one specialised\ncontainer called device container. All nodes are simple ROS 2 nodes and expose a publish and subscribe\nas well as a service interfaces. Once the device container is started, all nodes are brought up\nand ready to be used.\n\n**Purpose**:\nThe simple nodes container is thought for applications where the user needs a simple and\neasy to launch interface and does not need any realtime control capabilities as provided by\nros2_control.\n\nManaged nodes container\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe managed nodes container has the same properties as the standard nodes container.\nThe exception is, that all nodes are lifecycle nodes and there is a special node called\nlifecycle manager. The user can use the lifecycle manager to control the lifecycle of\nall nodes in the container.\n\n**Purpose**:\nThe managed nodes container is thought for applications where the user wants to have\nmore runtime recovery options than killing and restarting the container.\n\n\nROS 2 control system interface\n\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\"\nThe ros2_control interface is currently build on top of the simple nodes container. In\naddition to the standard nodes container the ros2_control system interface provides a\nhardware interface that can be used to control the devices on the bus. Currently, three\ndifferent system interfaces are provided:\n\n* canopen_ros2_control/CANopenSystem\n* canopen_ros2_control/CIA402System\n* canopen_ros2_control/RobotSystem\n\n**Purpose**:\nThe ROS 2 control system interfaces are thought for control applications that require\nlow latencies.\n"
  },
  {
    "path": "canopen/sphinx/user-guide/proxy-driver.rst",
    "content": "Proxy Driver\n===================\nA proxy driver which simply forwards CANopen functionality for a specific device via ROS2 services and messages.\n\n.. csv-table:: Proxy Drivers\n   :header: Type, Package, Name\n   :widths: 30, 20, 50\n\n   lifecycle, canopen_proxy_driver, ros2_canopen::LifecycleProxyDriver\n   simple, canopen_proxy_driver, ros2_canopen::ProxyDriver\n\nServices\n--------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n  :align: left\n\n  * - Services\n    - Type\n    - Description\n  * - ~/nmt_reset_node\n    - Trigger\n    - Resets CANopen Device the Proxy Device Node manages.\n  * - ~/sdo_read\n    - CORead\n    - Reads an SDO object from the specified index, subindex and datatype of the remote device.\n  * - ~/sdo_write\n    - COWrite\n    - Writes data to an SDO object on the specified index, subindex and datatype of the remote device.\n\n\nPublishers\n----------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n  :align: left\n\n  * - Topic\n    - Type\n    - Description\n  * - ~/nmt_state\n    - String\n    - Publishes NMT state on change\n  * - ~/rpdo\n    - COData\n    - Publishes received PDO objects on reception\n\nSubscribers\n-----------\n\n.. list-table::\n  :widths: 30 20 50\n  :header-rows: 1\n\n  * - Topic\n    - Type\n    - Description\n  * - ~/tpdo\n    - COData\n    - Writes received data to remote device if the specified object is RPDO mapped on remote device.\n"
  },
  {
    "path": "canopen_402_driver/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_402_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* Fix configuration parsing and logging\n* add pdo 6077 torque actual value to the joint state interface as effort (`#316 <https://github.com/ros-industrial/ros2_canopen/issues/316>`_)\n* Contributors: ipa-vsp, synsi23b\n\n0.3.1 (2025-06-23)\n------------------\n* Homing timeout\n* Add services to disable/enable motor so that brake is usable.\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.3.0 (2024-12-12)\n------------------\n* Reformat using pre-commit\n* Implement position offsets\n* pre-commit fix\n* impl operation mode\n* Add cyclic torque mode to cia402 driver and robot system controller (`#293 <https://github.com/ros-industrial/ros2_canopen/issues/293>`_)\n  * Add base functions for switching to cyclic torque mode\n  * Add cyclic torque mode as effort interface to robot_system controller\n  * Add documentation about cyclic torque mode.\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Merge pull request `#267 <https://github.com/ros-industrial/ros2_canopen/issues/267>`_ from clalancette/clalancette/update-lely-core-hash\n  Update the lely_core_libraries hash to the latest.\n* fix ci build error\n* Contributors: Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.9 (2024-04-16)\n------------------\n* Update the lely_core_libraries hash to the latest.\n* fix ci build error\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix maintainer naming\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix boost/std placeholders ambiguity in older boost versions\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Borong Yuan, Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, G.A. vd. Hoorn, Lovro, Vishnuprasad Prachandabhanu, livanov93\n"
  },
  {
    "path": "canopen_402_driver/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_402_driver)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_ros REQUIRED)\nfind_package(canopen_base_driver REQUIRED)\nfind_package(canopen_core REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(canopen_proxy_driver REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\nfind_package(sensor_msgs REQUIRED)\n\nadd_library(lely_motion_controller_bridge\n  src/motor.cpp\n  src/command.cpp\n  src/state.cpp\n  src/default_homing_mode.cpp\n)\ntarget_compile_features(lely_motion_controller_bridge PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lely_motion_controller_bridge PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lely_motion_controller_bridge PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\ntarget_link_libraries(lely_motion_controller_bridge PUBLIC\n  canopen_base_driver::node_canopen_base_driver\n  rclcpp::rclcpp\n)\n\n\nadd_library(node_canopen_cia402_driver\n  src/node_interfaces/node_canopen_402_driver.cpp\n)\ntarget_compile_features(node_canopen_cia402_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_cia402_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_cia402_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(node_canopen_cia402_driver PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${sensor_msgs_TARGETS}\n  canopen_proxy_driver::node_canopen_proxy_driver\n  lely_motion_controller_bridge\n)\n\nadd_library(lifecycle_cia402_driver\n  src/lifecycle_cia402_driver.cpp\n)\ntarget_compile_features(lifecycle_cia402_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lifecycle_cia402_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lifecycle_cia402_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\ntarget_link_libraries(lifecycle_cia402_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_cia402_driver\n  rclcpp_components::component\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(lifecycle_cia402_driver PRIVATE \"CANOPEN_402_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(lifecycle_cia402_driver \"ros2_canopen::LifecycleCia402Driver\")\nset(node_plugins \"${node_plugins}ros2_canopen::LifecycleCia402Driver;$<TARGET_FILE:lifecycle_cia402_driver>\\n\")\n\n\n\n\nadd_library(cia402_driver\n  src/cia402_driver.cpp\n)\ntarget_compile_features(cia402_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(cia402_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(cia402_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(cia402_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_cia402_driver\n  rclcpp_components::component\n)\n\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(cia402_driver PRIVATE \"CANOPEN_cia402_driver_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(cia402_driver \"ros2_canopen::Cia402Driver\")\nset(node_plugins \"${node_plugins}ros2_canopen::Cia402Driver;$<TARGET_FILE:cia402_driver>\\n\")\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\ninstall(\n  TARGETS lifecycle_cia402_driver cia402_driver node_canopen_cia402_driver lely_motion_controller_bridge\n  EXPORT export_${PROJECT_NAME}\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  RUNTIME DESTINATION bin\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_gtest REQUIRED)\n  add_subdirectory(test)\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  lifecycle_cia402_driver\n  cia402_driver\n  node_canopen_cia402_driver\n  lely_motion_controller_bridge\n)\nament_export_targets(\n  export_${PROJECT_NAME}\n)\nament_export_dependencies(\n  canopen_base_driver\n  canopen_core\n  canopen_interfaces\n  canopen_proxy_driver\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n  sensor_msgs\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_402_driver/LICENSE",
    "content": "GNU LESSER GENERAL PUBLIC LICENSE\n                       Version 3, 29 June 2007\n\n Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n\n  This version of the GNU Lesser General Public License incorporates\nthe terms and conditions of version 3 of the GNU General Public\nLicense, supplemented by the additional permissions listed below.\n\n  0. Additional Definitions.\n\n  As used herein, \"this License\" refers to version 3 of the GNU Lesser\nGeneral Public License, and the \"GNU GPL\" refers to version 3 of the GNU\nGeneral Public License.\n\n  \"The Library\" refers to a covered work governed by this License,\nother than an Application or a Combined Work as defined below.\n\n  An \"Application\" is any work that makes use of an interface provided\nby the Library, but which is not otherwise based on the Library.\nDefining a subclass of a class defined by the Library is deemed a mode\nof using an interface provided by the Library.\n\n  A \"Combined Work\" is a work produced by combining or linking an\nApplication with the Library.  The particular version of the Library\nwith which the Combined Work was made is also called the \"Linked\nVersion\".\n\n  The \"Minimal Corresponding Source\" for a Combined Work means the\nCorresponding Source for the Combined Work, excluding any source code\nfor portions of the Combined Work that, considered in isolation, are\nbased on the Application, and not on the Linked Version.\n\n  The \"Corresponding Application Code\" for a Combined Work means the\nobject code and/or source code for the Application, including any data\nand utility programs needed for reproducing the Combined Work from the\nApplication, but excluding the System Libraries of the Combined Work.\n\n  1. Exception to Section 3 of the GNU GPL.\n\n  You may convey a covered work under sections 3 and 4 of this License\nwithout being bound by section 3 of the GNU GPL.\n\n  2. Conveying Modified Versions.\n\n  If you modify a copy of the Library, and, in your modifications, a\nfacility refers to a function or data to be supplied by an Application\nthat uses the facility (other than as an argument passed when the\nfacility is invoked), then you may convey a copy of the modified\nversion:\n\n   a) under this License, provided that you make a good faith effort to\n   ensure that, in the event an Application does not supply the\n   function or data, the facility still operates, and performs\n   whatever part of its purpose remains meaningful, or\n\n   b) under the GNU GPL, with none of the additional permissions of\n   this License applicable to that copy.\n\n  3. Object Code Incorporating Material from Library Header Files.\n\n  The object code form of an Application may incorporate material from\na header file that is part of the Library.  You may convey such object\ncode under terms of your choice, provided that, if the incorporated\nmaterial is not limited to numerical parameters, data structure\nlayouts and accessors, or small macros, inline functions and templates\n(ten or fewer lines in length), you do both of the following:\n\n   a) Give prominent notice with each copy of the object code that the\n   Library is used in it and that the Library and its use are\n   covered by this License.\n\n   b) Accompany the object code with a copy of the GNU GPL and this license\n   document.\n\n  4. Combined Works.\n\n  You may convey a Combined Work under terms of your choice that,\ntaken together, effectively do not restrict modification of the\nportions of the Library contained in the Combined Work and reverse\nengineering for debugging such modifications, if you also do each of\nthe following:\n\n   a) Give prominent notice with each copy of the Combined Work that\n   the Library is used in it and that the Library and its use are\n   covered by this License.\n\n   b) Accompany the Combined Work with a copy of the GNU GPL and this license\n   document.\n\n   c) For a Combined Work that displays copyright notices during\n   execution, include the copyright notice for the Library among\n   these notices, as well as a reference directing the user to the\n   copies of the GNU GPL and this license document.\n\n   d) Do one of the following:\n\n       0) Convey the Minimal Corresponding Source under the terms of this\n       License, and the Corresponding Application Code in a form\n       suitable for, and under terms that permit, the user to\n       recombine or relink the Application with a modified version of\n       the Linked Version to produce a modified Combined Work, in the\n       manner specified by section 6 of the GNU GPL for conveying\n       Corresponding Source.\n\n       1) Use a suitable shared library mechanism for linking with the\n       Library.  A suitable mechanism is one that (a) uses at run time\n       a copy of the Library already present on the user's computer\n       system, and (b) will operate properly with a modified version\n       of the Library that is interface-compatible with the Linked\n       Version.\n\n   e) Provide Installation Information, but only if you would otherwise\n   be required to provide such information under section 6 of the\n   GNU GPL, and only to the extent that such information is\n   necessary to install and execute a modified version of the\n   Combined Work produced by recombining or relinking the\n   Application with a modified version of the Linked Version. (If\n   you use option 4d0, the Installation Information must accompany\n   the Minimal Corresponding Source and Corresponding Application\n   Code. If you use option 4d1, you must provide the Installation\n   Information in the manner specified by section 6 of the GNU GPL\n   for conveying Corresponding Source.)\n\n  5. Combined Libraries.\n\n  You may place library facilities that are a work based on the\nLibrary side by side in a single library together with other library\nfacilities that are not Applications and are not covered by this\nLicense, and convey such a combined library under terms of your\nchoice, if you do both of the following:\n\n   a) Accompany the combined library with a copy of the same work based\n   on the Library, uncombined with any other library facilities,\n   conveyed under the terms of this License.\n\n   b) Give prominent notice with the combined library that part of it\n   is a work based on the Library, and explaining where to find the\n   accompanying uncombined form of the same work.\n\n  6. Revised Versions of the GNU Lesser General Public License.\n\n  The Free Software Foundation may publish revised and/or new versions\nof the GNU Lesser General Public License from time to time. Such new\nversions will be similar in spirit to the present version, but may\ndiffer in detail to address new problems or concerns.\n\n  Each version is given a distinguishing version number. If the\nLibrary as you received it specifies that a certain numbered version\nof the GNU Lesser General Public License \"or any later version\"\napplies to it, you have the option of following the terms and\nconditions either of that published version or of any later version\npublished by the Free Software Foundation. If the Library as you\nreceived it does not specify a version number of the GNU Lesser\nGeneral Public License, you may choose any version of the GNU Lesser\nGeneral Public License ever published by the Free Software Foundation.\n\n  If the Library as you received it specifies that a proxy can decide\nwhether future versions of the GNU Lesser General Public License shall\napply, that proxy's public statement of acceptance of any version is\npermanent authorization for you to choose that version for the\nLibrary.\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/base.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#ifndef CANOPEN_402_BASE_H\n#define CANOPEN_402_BASE_H\n#include <string>\n\n#include \"lely/coapp/driver.hpp\"\n#include \"lely/coapp/master.hpp\"\n\nnamespace ros2_canopen\n{\n\n/**\n * @brief Motor Base Class\n *\n */\nclass MotorBase\n{\nprotected:\n  MotorBase() {}\n\npublic:\n  enum OperationMode\n  {\n    No_Mode = 0,\n    Profiled_Position = 1,\n    Velocity = 2,\n    Profiled_Velocity = 3,\n    Profiled_Torque = 4,\n    Reserved = 5,\n    Homing = 6,\n    Interpolated_Position = 7,\n    Cyclic_Synchronous_Position = 8,\n    Cyclic_Synchronous_Velocity = 9,\n    Cyclic_Synchronous_Torque = 10,\n  };\n\n  /**\n   * @brief Set target\n   *\n   * @param [in] val      Target value\n   * @return true\n   * @return false\n   */\n  virtual bool setTarget(double val) = 0;\n\n  /**\n   * @brief Enter Operation Mode\n   *\n   * @param [in] mode     Target Mode\n   * @return true\n   * @return false\n   */\n  virtual bool enterModeAndWait(uint16_t mode) = 0;\n\n  /**\n   * @brief Check if Operation Mode is supported\n   *\n   * @param [in] mode     Operation Mode to be checked\n   * @return true\n   * @return false\n   */\n  virtual bool isModeSupported(uint16_t mode) = 0;\n\n  /**\n   * @brief Get current Mode\n   *\n   * @return uint16_t\n   */\n  virtual uint16_t getMode() = 0;\n\n  /**\n   * @brief Register default Operation Modes\n   *\n   */\n  virtual void registerDefaultModes() {}\n\n  typedef std::shared_ptr<MotorBase> MotorBaseSharedPtr;\n};\ntypedef MotorBase::MotorBaseSharedPtr MotorBaseSharedPtr;\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/cia402_driver.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef CANOPEN_402_DRIVER__402_DRIVER_HPP_\n#define CANOPEN_402_DRIVER__402_DRIVER_HPP_\n#include <cstdint>\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp\"\n#include \"canopen_core/driver_node.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Abstract Class for a CANopen Device Node\n *\n * This class provides the base functionality for creating a\n * CANopen device node. It provides callbacks for nmt and rpdo.\n */\nclass Cia402Driver : public ros2_canopen::CanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp::Node>> node_canopen_402_driver_;\n\npublic:\n  Cia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n\n  virtual bool reset_node_nmt_command()\n  {\n    return node_canopen_402_driver_->reset_node_nmt_command();\n  }\n\n  virtual bool start_node_nmt_command()\n  {\n    return node_canopen_402_driver_->start_node_nmt_command();\n  }\n\n  virtual bool tpdo_transmit(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->tpdo_transmit(data);\n  }\n\n  virtual bool sdo_write(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->sdo_write(data);\n  }\n\n  virtual bool sdo_read(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->sdo_read(data);\n  }\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);\n  }\n\n  double get_effort(uint8_t channel = 0) { return node_canopen_402_driver_->get_effort(channel); }\n\n  double get_speed(uint8_t channel = 0) { return node_canopen_402_driver_->get_speed(channel); }\n\n  double get_position(uint8_t channel = 0)\n  {\n    return node_canopen_402_driver_->get_position(channel);\n  }\n\n  bool set_target(double target, uint8_t channel = 0)\n  {\n    return node_canopen_402_driver_->set_target(target, channel);\n  }\n\n  bool init_motor(uint8_t channel = 0) { return node_canopen_402_driver_->init_motor(channel); }\n\n  bool recover_motor(uint8_t channel = 0)\n  {\n    return node_canopen_402_driver_->recover_motor(channel);\n  }\n\n  bool halt_motor(uint8_t channel = 0) { return node_canopen_402_driver_->halt_motor(channel); }\n\n  uint16_t get_mode(uint8_t channel = 0) { return node_canopen_402_driver_->get_mode(channel); }\n\n  bool set_operation_mode(uint16_t mode, uint8_t channel = 0)\n  {\n    return node_canopen_402_driver_->set_operation_mode(mode, channel);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_402_DRIVER__CANOPEN_402_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/command.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef CANOPEN_402_DRIVER_COMMAND_HPP\n#define CANOPEN_402_DRIVER_COMMAND_HPP\n\n#include <boost/container/flat_map.hpp>\n#include <cstdint>\n#include <utility>\n#include \"state.hpp\"\n\nnamespace ros2_canopen\n{\nclass Command402\n{\n  struct Op\n  {\n    uint16_t to_set_;\n    uint16_t to_reset_;\n    Op(uint16_t to_set, uint16_t to_reset) : to_set_(to_set), to_reset_(to_reset) {}\n    void operator()(uint16_t & val) const { val = (val & ~to_reset_) | to_set_; }\n  };\n  class TransitionTable\n  {\n    boost::container::flat_map<std::pair<State402::InternalState, State402::InternalState>, Op>\n      transitions_;\n    void add(const State402::InternalState & from, const State402::InternalState & to, Op op)\n    {\n      transitions_.insert(std::make_pair(std::make_pair(from, to), op));\n    }\n\n  public:\n    TransitionTable();\n    const Op & get(const State402::InternalState & from, const State402::InternalState & to) const\n    {\n      return transitions_.at(std::make_pair(from, to));\n    }\n  };\n  static const TransitionTable transitions_;\n  static State402::InternalState nextStateForEnabling(State402::InternalState state);\n  Command402();\n\npublic:\n  enum ControlWord\n  {\n    CW_Switch_On = 0,\n    CW_Enable_Voltage = 1,\n    CW_Quick_Stop = 2,\n    CW_Enable_Operation = 3,\n    CW_Operation_mode_specific0 = 4,\n    CW_Operation_mode_specific1 = 5,\n    CW_Operation_mode_specific2 = 6,\n    CW_Fault_Reset = 7,\n    CW_Halt = 8,\n    CW_Operation_mode_specific3 = 9,\n    // CW_Reserved1=10,\n    CW_Manufacturer_specific0 = 11,\n    CW_Manufacturer_specific1 = 12,\n    CW_Manufacturer_specific2 = 13,\n    CW_Manufacturer_specific3 = 14,\n    CW_Manufacturer_specific4 = 15,\n  };\n  static bool setTransition(\n    uint16_t & cw, const State402::InternalState & from, const State402::InternalState & to,\n    State402::InternalState * next);\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_402_DRIVER_COMMAND_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/default_homing_mode.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef DEFAULT_HOMING_MODE_HPP\n#define DEFAULT_HOMING_MODE_HPP\n#include <mutex>\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include \"homing_mode.hpp\"\n\nnamespace ros2_canopen\n{\n\nclass DefaultHomingMode : public HomingMode\n{\n  const uint16_t base_index = 0x6098;\n  uint16_t channel_offset_;  // Channel offset for multi-axis support (CiA 402-2)\n  std::shared_ptr<LelyDriverBridge> driver;\n\n  std::atomic<bool> execute_;\n\n  std::mutex mutex_;\n  std::condition_variable cond_;\n  uint16_t status_;\n\n  const int homing_timeout_seconds_;\n\n  enum SW_masks\n  {\n    MASK_Reached = (1 << State402::SW_Target_reached),\n    MASK_Attained = (1 << SW_Attained),\n    MASK_Error = (1 << SW_Error),\n  };\n  bool error(const std::string & msg)\n  {\n    execute_ = false;\n    std::cout << msg << std::endl;\n    return false;\n  }\n\npublic:\n  DefaultHomingMode(\n    std::shared_ptr<LelyDriverBridge> driver, int homing_timeout_seconds,\n    uint16_t channel_offset = 0)\n  : homing_timeout_seconds_(homing_timeout_seconds), channel_offset_(channel_offset)\n  {\n    this->driver = driver;\n  }\n  virtual bool start();\n  virtual bool read(const uint16_t & sw);\n  virtual bool write(OpModeAccesser & cw);\n\n  virtual bool executeHoming();\n};\n}  // namespace ros2_canopen\n#endif  // DEFAULT_HOMING_MODE_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/homing_mode.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef HOMING_MODE_HPP\n#define HOMING_MODE_HPP\n#include \"base.hpp\"\n#include \"mode.hpp\"\n\nnamespace ros2_canopen\n{\nclass HomingMode : public Mode\n{\nprotected:\n  enum SW_bits\n  {\n    SW_Attained = State402::SW_Operation_mode_specific0,\n    SW_Error = State402::SW_Operation_mode_specific1,\n  };\n  enum CW_bits\n  {\n    CW_StartHoming = Command402::CW_Operation_mode_specific0,\n  };\n\npublic:\n  HomingMode() : Mode(MotorBase::Homing) {}\n  virtual bool executeHoming() = 0;\n};\n}  // namespace ros2_canopen\n\n#endif  // HOMING_MODE_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/lifecycle_cia402_driver.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_\n#define CANOPEN_402_DRIVER__CANOPEN_LIFECYCLE_402_DRIVER_HPP_\n\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp\"\n#include \"canopen_core/driver_node.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle 402 Driver\n *\n * A very basic driver without any functionality.\n *\n */\nclass LifecycleCia402Driver : public ros2_canopen::LifecycleCanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>>\n    node_canopen_402_driver_;\n\npublic:\n  LifecycleCia402Driver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n\n  virtual bool reset_node_nmt_command()\n  {\n    return node_canopen_402_driver_->reset_node_nmt_command();\n  }\n\n  virtual bool start_node_nmt_command()\n  {\n    return node_canopen_402_driver_->start_node_nmt_command();\n  }\n\n  virtual bool tpdo_transmit(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->tpdo_transmit(data);\n  }\n\n  virtual bool sdo_write(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->sdo_write(data);\n  }\n\n  virtual bool sdo_read(ros2_canopen::COData & data)\n  {\n    return node_canopen_402_driver_->sdo_read(data);\n  }\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_402_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_402_driver_->register_rpdo_cb(rpdo_cb);\n  }\n\n  double get_speed() { return node_canopen_402_driver_->get_speed(); }\n\n  double get_position() { return node_canopen_402_driver_->get_position(); }\n\n  bool set_target(double target) { return node_canopen_402_driver_->set_target(target); }\n\n  bool init_motor() { return node_canopen_402_driver_->init_motor(); }\n\n  bool recover_motor() { return node_canopen_402_driver_->recover_motor(); }\n\n  bool halt_motor() { return node_canopen_402_driver_->halt_motor(); }\n\n  uint16_t get_mode() { return node_canopen_402_driver_->get_mode(); }\n\n  bool set_operation_mode(uint16_t mode)\n  {\n    return node_canopen_402_driver_->set_operation_mode(mode);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_402_DRIVER__CANOPEN_402_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/mode.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef CANOPEN_402_DRIVER_MODE_HPP\n#define CANOPEN_402_DRIVER_MODE_HPP\n\n#include <cstdint>\n#include <memory>\n#include \"command.hpp\"\n#include \"state.hpp\"\n#include \"word_accessor.hpp\"\n\nnamespace ros2_canopen\n{\nclass Mode\n{\npublic:\n  const uint16_t mode_id_;\n  Mode(uint16_t id) : mode_id_(id) {}\n  typedef WordAccessor<\n    (1 << Command402::CW_Operation_mode_specific0) |\n    (1 << Command402::CW_Operation_mode_specific1) |\n    (1 << Command402::CW_Operation_mode_specific2) | (1 << Command402::CW_Operation_mode_specific3)>\n    OpModeAccesser;\n  virtual bool start() = 0;\n  virtual bool read(const uint16_t & sw) = 0;\n  virtual bool write(OpModeAccesser & cw) = 0;\n  virtual bool setTarget(const double & val) { return false; }\n  virtual ~Mode() {}\n};\ntypedef std::shared_ptr<Mode> ModeSharedPtr;\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_402_DRIVER_MODE_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/mode_forward_helper.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef MODE_FORWARD_HELPER_HPP\n#define MODE_FORWARD_HELPER_HPP\n\n#include <cstdint>\n#include <memory>\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include \"mode_target_helper.hpp\"\n\nnamespace ros2_canopen\n{\n\ntemplate <uint16_t ID, typename TYPE, uint16_t OBJ, uint8_t SUB, uint16_t CW_MASK>\nclass ModeForwardHelper : public ModeTargetHelper<TYPE>\n{\n  std::shared_ptr<LelyDriverBridge> driver;\n  uint16_t channel_offset_;  // Channel offset for multi-axis support (CiA 402-2)\n\npublic:\n  ModeForwardHelper(std::shared_ptr<LelyDriverBridge> driver, uint16_t channel_offset = 0)\n  : ModeTargetHelper<TYPE>(ID), channel_offset_(channel_offset)\n  {\n    this->driver = driver;\n  }\n  virtual bool read(const uint16_t & sw) { return true; }\n  virtual bool write(Mode::OpModeAccesser & cw)\n  {\n    if (this->hasTarget())\n    {\n      cw = cw.get() | CW_MASK;\n\n      // Apply channel offset to object dictionary index\n      driver->universal_set_value<TYPE>(OBJ + channel_offset_, SUB, this->getTarget());\n      return true;\n    }\n    else\n    {\n      cw = cw.get() & ~CW_MASK;\n      return false;\n    }\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // MODE_FORWARD_HELPER_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/mode_target_helper.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef MODE_TARGET_HELPER_HPP\n#define MODE_TARGET_HELPER_HPP\n\n#include <atomic>\n#include <boost/numeric/conversion/cast.hpp>\n#include <cmath>\n#include <iostream>\n#include <limits>\n#include <memory>\n#include <string>\n#include <vector>\n\n#include \"canopen_402_driver/mode.hpp\"\n\nnamespace ros2_canopen\n{\n\ntemplate <typename T>\nclass ModeTargetHelper : public Mode\n{\n  T target_;\n  std::atomic<bool> has_target_;\n\npublic:\n  ModeTargetHelper(uint16_t mode) : Mode(mode) {}\n  bool hasTarget() { return has_target_; }\n  T getTarget() { return target_; }\n  virtual bool setTarget(const double & val)\n  {\n    if (std::isnan(val))\n    {\n      // std::cout << \"canopen_402 target command is not a number\" << std::endl;\n      RCLCPP_DEBUG(rclcpp::get_logger(\"canopen_402_target\"), \"Target command is not a number\");\n      return false;\n    }\n\n    using boost::numeric_cast;\n    using boost::numeric::negative_overflow;\n    using boost::numeric::positive_overflow;\n\n    try\n    {\n      target_ = numeric_cast<T>(val);\n    }\n    catch (negative_overflow &)\n    {\n      std::cout << \"canopen_402 Command \" << val\n                << \" does not fit into target, clamping to min limit\" << std::endl;\n      target_ = std::numeric_limits<T>::min();\n    }\n    catch (positive_overflow &)\n    {\n      std::cout << \"canopen_402 Command \" << val\n                << \" does not fit into target, clamping to max limit\" << std::endl;\n      target_ = std::numeric_limits<T>::max();\n    }\n    catch (...)\n    {\n      std::cout << \"canopen_402 Was not able to cast command \" << val << std::endl;\n      return false;\n    }\n\n    has_target_ = true;\n    return true;\n  }\n  virtual bool start()\n  {\n    has_target_ = false;\n    return true;\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // MODE_TARGET_HELPER_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/motor.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef MOTOR_HPP\n#define MOTOR_HPP\n\n#include <algorithm>\n#include <atomic>\n#include <bitset>\n#include <condition_variable>\n#include <functional>\n#include <iostream>\n#include <limits>\n#include <mutex>\n#include <thread>\n#include \"rclcpp/rclcpp.hpp\"\n\n#include \"canopen_402_driver/default_homing_mode.hpp\"\n#include \"canopen_402_driver/mode_forward_helper.hpp\"\n#include \"canopen_402_driver/profiled_position_mode.hpp\"\n#include \"canopen_base_driver/diagnostic_collector.hpp\"\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n\nnamespace ros2_canopen\n{\n\ntypedef ModeForwardHelper<MotorBase::Profiled_Velocity, int32_t, 0x60FF, 0, 0> ProfiledVelocityMode;\ntypedef ModeForwardHelper<MotorBase::Profiled_Torque, int16_t, 0x6071, 0, 0> ProfiledTorqueMode;\ntypedef ModeForwardHelper<MotorBase::Cyclic_Synchronous_Position, int32_t, 0x607A, 0, 0>\n  CyclicSynchronousPositionMode;\ntypedef ModeForwardHelper<MotorBase::Cyclic_Synchronous_Velocity, int32_t, 0x60FF, 0, 0>\n  CyclicSynchronousVelocityMode;\ntypedef ModeForwardHelper<MotorBase::Cyclic_Synchronous_Torque, int16_t, 0x6071, 0, 0>\n  CyclicSynchronousTorqueMode;\ntypedef ModeForwardHelper<\n  MotorBase::Velocity, int16_t, 0x6042, 0,\n  (1 << Command402::CW_Operation_mode_specific0) | (1 << Command402::CW_Operation_mode_specific1) |\n    (1 << Command402::CW_Operation_mode_specific2)>\n  VelocityMode;\ntypedef ModeForwardHelper<\n  MotorBase::Interpolated_Position, int32_t, 0x60C1, 0x01,\n  (1 << Command402::CW_Operation_mode_specific0)>\n  InterpolatedPositionMode;\n\nclass Motor402 : public MotorBase\n{\npublic:\n  Motor402(\n    std::shared_ptr<LelyDriverBridge> driver, ros2_canopen::State402::InternalState switching_state,\n    int homing_timeout_seconds, uint8_t channel = 0)\n  : MotorBase(),\n    switching_state_(switching_state),\n    monitor_mode_(true),\n    state_switch_timeout_(5),\n    homing_timeout_seconds_(homing_timeout_seconds),\n    channel_(channel),\n    effort_support_state_(-1)\n  {\n    this->driver = driver;\n    // Calculate channel offset according to CiA 402-2: base_index + (channel * 0x800)\n    channel_offset_ = channel * 0x800;\n  }\n\n  /**\n   * @brief Get channel-specific object dictionary index\n   *\n   * According to CiA 402-2, multi-axis devices use offset indices:\n   * - Channel 0: 0x6000-0x67FF (standard, no offset)\n   * - Channel 1: 0x6800-0x6FFF (offset +0x800)\n   * - Channel 2: 0x7000-0x77FF (offset +0x1000)\n   * - etc.\n   *\n   * @param base_index The base object dictionary index\n   * @return The channel-specific index\n   */\n  uint16_t get_channel_index(uint16_t base_index) const { return base_index + channel_offset_; }\n\n  uint8_t get_channel() const { return channel_; }\n\n  virtual bool setTarget(double val);\n  virtual bool enterModeAndWait(uint16_t mode);\n  virtual bool isModeSupported(uint16_t mode);\n  virtual uint16_t getMode();\n  bool readState();\n\n  /**\n   * @brief Updates the device diagnostic information\n   *\n   * This function updates the diagnostic information of the device by updating the diagnostic\n   * status message\n   * @ref diagnostic_status_ and publishing it.\n   */\n  void handleDiag();\n  /**\n   * @brief Initialise the drive\n   *\n   * This function initialises the drive. This means, it first\n   * attempts to bring the device to operational state (CIA402)\n   * and then executes the chosen homing method.\n   *\n   */\n  bool handleInit();\n  /**\n   * @brief Read objects of the drive\n   *\n   * This function should be called regularly. It reads the status word\n   * from the device and translates it into the devices state.\n   *\n   */\n  void handleRead();\n  /**\n   * @brief Writes objects to the drive\n   *\n   * This function should be called regularly. It writes the new command\n   * word to the drive\n   *\n   */\n  void handleWrite();\n  /**\n   * @brief Shutdowns the drive\n   *\n   * This function shuts down the drive by bringing it into\n   * SwitchOn disabled state.\n   *\n   */\n  bool handleShutdown();\n  /**\n   * @brief Executes a quickstop\n   *\n   * The function executes a quickstop.\n   *\n   */\n  bool handleHalt();\n\n  /**\n   * @brief Recovers the device from fault\n   *\n   * This function tries to reset faults and\n   * put the device back to operational state.\n   *\n   */\n  bool handleRecover();\n\n  /**\n   * @brief Enable the drive\n   *\n   * This function enables the drive. This means it attempts\n   * to bring the device to operational state (CIA402), and does nothing else.\n   *\n   */\n  bool handleEnable();\n  /**\n   * @brief Disable the drive\n   *\n   * This function disables the drive. This means it attempts to bring the\n   * device to switched on disabled state (CIA402).\n   *\n   */\n  bool handleDisable();\n\n  /**\n   * @brief Register a new operation mode for the drive\n   *\n   * This function will register an operation mode for the drive.\n   * It will check if the mode is supported by the drive by reading\n   * 0x6508 object.\n   *\n   * @tparam T\n   * @tparam Args\n   * @param mode\n   * @param args\n   * @return true\n   * @return false\n   */\n  template <typename T, typename... Args>\n  bool registerMode(uint16_t mode, Args &&... args)\n  {\n    return mode_allocators_\n      .insert(std::make_pair(\n        mode,\n        [args..., mode, this]()\n        {\n          if (isModeSupportedByDevice(mode)) registerMode(mode, ModeSharedPtr(new T(args...)));\n        }))\n      .second;\n  }\n\n  /**\n   * @brief Tries to register the standard operation modes defined in cia402\n   *\n   */\n  virtual void registerDefaultModes()\n  {\n    // Pass channel_offset_ to all mode constructors for multi-axis support\n    registerMode<ProfiledPositionMode>(MotorBase::Profiled_Position, driver, channel_offset_);\n    registerMode<VelocityMode>(MotorBase::Velocity, driver, channel_offset_);\n    registerMode<ProfiledVelocityMode>(MotorBase::Profiled_Velocity, driver, channel_offset_);\n    registerMode<ProfiledTorqueMode>(MotorBase::Profiled_Torque, driver, channel_offset_);\n    registerMode<DefaultHomingMode>(\n      MotorBase::Homing, driver, homing_timeout_seconds_, channel_offset_);\n    registerMode<InterpolatedPositionMode>(\n      MotorBase::Interpolated_Position, driver, channel_offset_);\n    registerMode<CyclicSynchronousPositionMode>(\n      MotorBase::Cyclic_Synchronous_Position, driver, channel_offset_);\n    registerMode<CyclicSynchronousVelocityMode>(\n      MotorBase::Cyclic_Synchronous_Velocity, driver, channel_offset_);\n    registerMode<CyclicSynchronousTorqueMode>(\n      MotorBase::Cyclic_Synchronous_Torque, driver, channel_offset_);\n  }\n\n  double get_effort() const\n  {\n    auto idx = get_channel_index(0x6077);\n    auto state = effort_support_state_.load();\n    if (state <= 0)\n    {\n      if (state == 0)\n      {\n        return 0.0;\n      }\n      bool has_object = this->driver->has_object(idx, 0);\n      effort_support_state_.store(has_object ? 1 : 0);\n      if (!has_object)\n      {\n        RCLCPP_WARN(\n          rclcpp::get_logger(\"canopen_402_driver\"),\n          \"Effort interface disabled: object 0x6077:00 not found in EDS/OD.\");\n        return 0.0;\n      }\n    }\n    return (double)this->driver->universal_get_value<int16_t>(idx, 0);\n  }\n  double get_speed() const\n  {\n    return (double)this->driver->universal_get_value<int32_t>(get_channel_index(0x606C), 0);\n  }\n\n  double get_position() const\n  {\n    return (double)this->driver->universal_get_value<int32_t>(get_channel_index(0x6064), 0);\n  }\n\n  void set_diagnostic_status_msgs(std::shared_ptr<DiagnosticsCollector> status, bool enable)\n  {\n    this->enable_diagnostics_.store(enable);\n    this->diag_collector_ = status;\n  }\n\nprivate:\n  virtual bool isModeSupportedByDevice(uint16_t mode);\n  void registerMode(uint16_t id, const ModeSharedPtr & m);\n\n  ModeSharedPtr allocMode(uint16_t mode);\n\n  bool switchMode(uint16_t mode);\n  bool switchState(const State402::InternalState & target);\n\n  std::atomic<uint16_t> status_word_;\n  uint16_t control_word_;\n  std::mutex cw_mutex_;\n  std::atomic<bool> start_fault_reset_;\n  std::atomic<State402::InternalState> target_state_;\n\n  State402 state_handler_;\n\n  std::mutex map_mutex_;\n  std::unordered_map<uint16_t, ModeSharedPtr> modes_;\n  typedef std::function<void()> AllocFuncType;\n  std::unordered_map<uint16_t, AllocFuncType> mode_allocators_;\n\n  ModeSharedPtr selected_mode_;\n  uint16_t mode_id_;\n  std::condition_variable mode_cond_;\n  std::mutex mode_mutex_;\n  const State402::InternalState switching_state_;\n  const bool monitor_mode_;\n  const std::chrono::seconds state_switch_timeout_;\n  const int homing_timeout_seconds_;\n\n  std::shared_ptr<LelyDriverBridge> driver;\n\n  // Channel support for multi-axis devices (CiA 402-2)\n  const uint8_t channel_;\n  uint16_t channel_offset_;\n\n  // Base object dictionary indices (will be offset by channel_offset_)\n  const uint16_t status_word_entry_index = 0x6041;\n  const uint16_t control_word_entry_index = 0x6040;\n  const uint16_t op_mode_display_index = 0x6061;\n  const uint16_t op_mode_index = 0x6060;\n  const uint16_t supported_drive_modes_index = 0x6502;\n\n  // Diagnostic components\n  std::atomic<bool> enable_diagnostics_;\n  std::shared_ptr<DiagnosticsCollector> diag_collector_;\n\n  // -1 unknown, 0 missing, 1 present\n  mutable std::atomic<int> effort_support_state_;\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//                          Vishnuprasad Prachandabhanu\n//                          Lovro Ivanov\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef NODE_CANOPEN_402_DRIVER\n#define NODE_CANOPEN_402_DRIVER\n\n#include <cstdint>\n#include <memory>\n#include <string>\n#include <type_traits>\n#include <vector>\n\n#include \"canopen_402_driver/motor.hpp\"\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include \"canopen_interfaces/srv/co_target_double.hpp\"\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n#include \"sensor_msgs/msg/joint_state.hpp\"\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n\ntemplate <class NODETYPE>\nclass NodeCanopen402Driver : public NodeCanopenProxyDriver<NODETYPE>\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  struct ChannelContext\n  {\n    std::shared_ptr<Motor402> motor;\n\n    // Resolved (effective) per-channel scale/offset values\n    double scale_pos_to_dev{1000.0};\n    double scale_pos_from_dev{0.001};\n    double scale_vel_to_dev{1000.0};\n    double scale_vel_from_dev{0.001};\n    double scale_eff_from_dev{0.001};\n    double offset_pos_to_dev{0.0};\n    double offset_pos_from_dev{0.0};\n\n    // Per-channel service handles (kept alive by owning SharedPtr)\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_init;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_enable;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_disable;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_halt;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_recover;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_position;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_torque;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_velocity;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_velocity;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_position;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_torque;\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_interpolated_position;\n    rclcpp::Service<canopen_interfaces::srv::COTargetDouble>::SharedPtr handle_set_target;\n  };\n\n  std::vector<ChannelContext> channels_;\n  uint8_t num_channels_;\n  std::vector<std::string> channel_names_;\n\n  rclcpp::TimerBase::SharedPtr timer_;\n\n  rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr publish_joint_state;\n\n  // Global scale/offset (used as defaults)\n  double scale_pos_to_dev_;\n  double scale_pos_from_dev_;\n  double scale_vel_to_dev_;\n  double scale_vel_from_dev_;\n  double scale_eff_from_dev_;\n  double offset_pos_to_dev_;\n  double offset_pos_from_dev_;\n\n  ros2_canopen::State402::InternalState switching_state_;\n  int homing_timeout_seconds_;\n\n  void publish();\n  virtual void poll_timer_callback() override;\n  void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat) override;\n\n  // Shared configure logic for both rclcpp::Node and rclcpp_lifecycle::LifecycleNode\n  void configure_common();\n\n  // Helper to create per-channel services after configure\n  void create_per_channel_services();\n\npublic:\n  NodeCanopen402Driver(NODETYPE * node);\n\n  virtual void init(bool called_from_base) override;\n  virtual void configure(bool called_from_base) override;\n  virtual void activate(bool called_from_base) override;\n  virtual void deactivate(bool called_from_base) override;\n  virtual void add_to_master() override;\n\n  virtual double get_effort(uint8_t channel = 0)\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor) return 0.0;\n    return channels_[channel].motor->get_effort() * channels_[channel].scale_eff_from_dev;\n  }\n\n  virtual double get_speed(uint8_t channel = 0)\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor) return 0.0;\n    return channels_[channel].motor->get_speed() * channels_[channel].scale_vel_from_dev;\n  }\n\n  virtual double get_position(uint8_t channel = 0)\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor) return 0.0;\n    return channels_[channel].motor->get_position() * channels_[channel].scale_pos_from_dev +\n           channels_[channel].offset_pos_from_dev;\n  }\n\n  virtual uint16_t get_mode(uint8_t channel = 0)\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor) return 0;\n    return channels_[channel].motor->getMode();\n  }\n\n  /**\n   * @brief Service Callback to initialise device\n   *\n   * Calls Motor402::handleInit function. Brings motor to enabled\n   * state and homes it.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_init(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to enable device\n   *\n   * Calls Motor402::handleEnable function. Brings motor to enabled\n   * state.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_enable(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to disable device\n   *\n   * Calls Motor402::handleDisable function. Brings motor to switched on\n   * disabled state.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_disable(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Method to initialise device\n   *\n   * Calls Motor402::handleInit function. Brings motor to enabled\n   * state and homes it.\n   *\n   * @param [in] void\n   *\n   * @return  bool\n   * Indicates initialisation procedure result\n   */\n  bool init_motor(uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to recover device\n   *\n   * Calls Motor402::handleRecover function. Resets faults and brings\n   * motor to enabled state.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_recover(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Method to recover device\n   *\n   * Calls Motor402::handleRecover function. Resets faults and brings\n   * motor to enabled state.\n   *\n   * @param [in] void\n   *\n   * @return bool\n   */\n  bool recover_motor(uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to halt device\n   *\n   * Calls Motor402::handleHalt function. Calls Quickstop. Resulting\n   * Motor state depends on devices configuration specifically object\n   * 0x605A.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_halt(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Method to halt device\n   *\n   * Calls Motor402::handleHalt function. Calls Quickstop. Resulting\n   * Motor state depends on devices configuration specifically object\n   * 0x605A.\n   *\n   * @param [in] void\n   *\n   * @return bool\n   */\n  bool halt_motor(uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set operation mode\n   *\n   * Calls Motor402::enterModeAndWait with requested Operation Mode.\n   *\n   * @param [in] request Requested Operation Mode as MotorBase::Profiled_Position or\n   * MotorBase::Profiled_Velocity or MotorBase::Profiled_Torque or MotorBase::Cyclic_Position or\n   * MotorBase::Cyclic_Velocity or MotorBase::Cyclic_Torque or MotorBase::Interpolated_Position\n   * @param [out] response\n   */\n  bool set_operation_mode(uint16_t mode, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set profiled position mode\n   *\n   * Calls Motor402::enterModeAndWait with Profiled Position Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Profiled Position Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_position(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set profiled velocity mode\n   *\n   * Calls Motor402::enterModeAndWait with Profiled Velocity Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Profiled Velocity Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_velocity(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set cyclic position mode\n   *\n   * Calls Motor402::enterModeAndWait with Cyclic Position Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Cyclic Position Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_cyclic_position(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set interpolated position mode\n   *\n   * Calls Motor402::enterModeAndWait with Interpolated Position Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Interpolated Position Mode. This only supports linear mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_interpolated_position(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set cyclic velocity mode\n   *\n   * Calls Motor402::enterModeAndWait with Cyclic Velocity Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Cyclic Velocity Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_cyclic_velocity(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set profiled torque mode\n   *\n   * Calls Motor402::enterModeAndWait with Profiled Torque Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Profiled Torque Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_torque(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set cyclic torque mode\n   *\n   * Calls Motor402::enterModeAndWait with Cyclic Torque Mode as\n   * Target Operation Mode. If successful, the motor was transitioned\n   * to Cyclic Torque Mode.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_mode_cyclic_torque(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response, uint8_t channel = 0);\n\n  /**\n   * @brief Service Callback to set target\n   *\n   * Calls Motor402::setTarget and sets the requested target value. Note\n   * that the resulting movement is dependent on the Operation Mode and the\n   * drives state.\n   *\n   * @param [in] request\n   * @param [out] response\n   */\n  void handle_set_target(\n    const canopen_interfaces::srv::COTargetDouble::Request::SharedPtr request,\n    canopen_interfaces::srv::COTargetDouble::Response::SharedPtr response,\n    const uint8_t channel = 0);\n\n  /**\n   * @brief Method to set target\n   *\n   * Calls Motor402::setTarget and sets the requested target value. Note\n   * that the resulting movement is dependent on the Operation Mode and the\n   * drives state.\n   *\n   * @param [in] double target value\n   * @param [in] uint8_t channel (default 0 for backward compatibility)\n   *\n   * @return bool\n   */\n  bool set_target(double target, uint8_t channel = 0);\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//                          Vishnuprasad Prachandabhanu\n//                          Lovro Ivanov\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef NODE_CANOPEN_402_DRIVER_IMPL_HPP_\n#define NODE_CANOPEN_402_DRIVER_IMPL_HPP_\n\n#include <sys/types.h>\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp\"\n#include \"canopen_core/driver_error.hpp\"\n\n#include <optional>\n\nusing namespace ros2_canopen::node_interfaces;\nusing namespace std::placeholders;\n\ntemplate <class NODETYPE>\nNodeCanopen402Driver<NODETYPE>::NodeCanopen402Driver(NODETYPE * node)\n: ros2_canopen::node_interfaces::NodeCanopenProxyDriver<NODETYPE>(node)\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::init(bool called_from_base)\n{\n  RCLCPP_ERROR(this->node_->get_logger(), \"Not init implemented.\");\n}\n\ntemplate <>\nvoid NodeCanopen402Driver<rclcpp::Node>::init(bool called_from_base)\n{\n  NodeCanopenProxyDriver<rclcpp::Node>::init(false);\n  publish_joint_state =\n    this->node_->create_publisher<sensor_msgs::msg::JointState>(\"~/joint_states\", 1);\n  // Per-channel services will be created in configure() after num_channels_ is known\n}\n\ntemplate <>\nvoid NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>::init(bool called_from_base)\n{\n  NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::init(false);\n  publish_joint_state =\n    this->node_->create_publisher<sensor_msgs::msg::JointState>(\"~/joint_states\", 10);\n  // Per-channel services will be created in configure() after num_channels_ is known\n}\n\n// Helper method to create per-channel services (called from configure)\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::create_per_channel_services()\n{\n  // Ensure per-channel storage exists\n  channels_.resize(num_channels_);\n\n  // Create services for each channel\n  for (uint8_t ch = 0; ch < num_channels_; ++ch)\n  {\n    // Service naming:\n    // - Single-channel (num_channels_ == 1): Use legacy names like \"init\", \"target\", etc.\n    // - Multi-channel: Use channel_name as prefix like \"channel_name/init\"\n    std::string service_prefix;\n    if (num_channels_ == 1)\n    {\n      // Single-channel: legacy behavior\n      service_prefix = std::string(this->node_->get_name()) + \"/\";\n    }\n    else\n    {\n      // Multi-channel: use channel_name as prefix\n      if (ch < channel_names_.size())\n      {\n        service_prefix = channel_names_[ch] + \"/\";\n      }\n      else\n      {\n        // Fallback if channel_names not configured\n        service_prefix = \"ch\" + std::to_string(ch) + \"/\";\n      }\n    }\n\n    // Init service\n    channels_[ch].handle_init = this->node_->template create_service<std_srvs::srv::Trigger>(\n      service_prefix + \"init\", [this, ch](\n                                 const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                 std_srvs::srv::Trigger::Response::SharedPtr response)\n      { this->handle_init(request, response, ch); });\n\n    // Enable service\n    channels_[ch].handle_enable = this->node_->template create_service<std_srvs::srv::Trigger>(\n      service_prefix + \"enable\", [this, ch](\n                                   const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                   std_srvs::srv::Trigger::Response::SharedPtr response)\n      { this->handle_enable(request, response, ch); });\n\n    // Disable service\n    channels_[ch].handle_disable = this->node_->template create_service<std_srvs::srv::Trigger>(\n      service_prefix + \"disable\", [this, ch](\n                                    const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                    std_srvs::srv::Trigger::Response::SharedPtr response)\n      { this->handle_disable(request, response, ch); });\n\n    // Halt service\n    channels_[ch].handle_halt = this->node_->template create_service<std_srvs::srv::Trigger>(\n      service_prefix + \"halt\", [this, ch](\n                                 const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                 std_srvs::srv::Trigger::Response::SharedPtr response)\n      { this->handle_halt(request, response, ch); });\n\n    // Recover service\n    channels_[ch].handle_recover = this->node_->template create_service<std_srvs::srv::Trigger>(\n      service_prefix + \"recover\", [this, ch](\n                                    const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                    std_srvs::srv::Trigger::Response::SharedPtr response)\n      { this->handle_recover(request, response, ch); });\n\n    // Position mode service\n    channels_[ch].handle_set_mode_position =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"position_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_position(request, response, ch); });\n\n    // Velocity mode service\n    channels_[ch].handle_set_mode_velocity =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"velocity_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_velocity(request, response, ch); });\n\n    // Torque mode service\n    channels_[ch].handle_set_mode_torque =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"torque_mode\", [this, ch](\n                                          const std_srvs::srv::Trigger::Request::SharedPtr request,\n                                          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_torque(request, response, ch); });\n\n    // Cyclic velocity mode service\n    channels_[ch].handle_set_mode_cyclic_velocity =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"cyclic_velocity_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_cyclic_velocity(request, response, ch); });\n\n    // Cyclic position mode service\n    channels_[ch].handle_set_mode_cyclic_position =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"cyclic_position_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_cyclic_position(request, response, ch); });\n\n    // Cyclic torque mode service\n    channels_[ch].handle_set_mode_cyclic_torque =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"cyclic_torque_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_cyclic_torque(request, response, ch); });\n\n    // Interpolated position mode service\n    channels_[ch].handle_set_mode_interpolated_position =\n      this->node_->template create_service<std_srvs::srv::Trigger>(\n        service_prefix + \"interpolated_position_mode\",\n        [this, ch](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        { this->handle_set_mode_interpolated_position(request, response, ch); });\n\n    // Target service (uses COTargetDouble without channel field, since channel is in service name)\n    channels_[ch].handle_set_target =\n      this->node_->template create_service<canopen_interfaces::srv::COTargetDouble>(\n        service_prefix + \"target\",\n        [this, ch](\n          const canopen_interfaces::srv::COTargetDouble::Request::SharedPtr request,\n          canopen_interfaces::srv::COTargetDouble::Response::SharedPtr response)\n        { response->success = this->set_target(request->target, ch); });\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::configure_common()\n{\n  NodeCanopenProxyDriver<NODETYPE>::configure(false);\n  std::optional<double> scale_pos_to_dev;\n  std::optional<double> scale_pos_from_dev;\n  std::optional<double> scale_vel_to_dev;\n  std::optional<double> scale_vel_from_dev;\n  std::optional<double> scale_eff_from_dev;\n  std::optional<double> offset_pos_to_dev;\n  std::optional<double> offset_pos_from_dev;\n  std::optional<int> switching_state;\n  std::optional<int> homing_timeout_seconds;\n  try\n  {\n    scale_pos_to_dev = std::optional(this->config_[\"scale_pos_to_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    scale_pos_from_dev = std::optional(this->config_[\"scale_pos_from_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    scale_vel_to_dev = std::optional(this->config_[\"scale_vel_to_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    scale_vel_from_dev = std::optional(this->config_[\"scale_vel_from_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    scale_eff_from_dev = std::optional(this->config_[\"scale_eff_from_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    offset_pos_to_dev = std::optional(this->config_[\"offset_pos_to_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    offset_pos_from_dev = std::optional(this->config_[\"offset_pos_from_dev\"].template as<double>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    switching_state = std::optional(this->config_[\"switching_state\"].template as<int>());\n  }\n  catch (...)\n  {\n  }\n  try\n  {\n    homing_timeout_seconds =\n      std::optional(this->config_[\"homing_timeout_seconds\"].template as<int>());\n  }\n  catch (...)\n  {\n  }\n\n  scale_pos_to_dev_ = scale_pos_to_dev.value_or(1000.0);\n  scale_pos_from_dev_ = scale_pos_from_dev.value_or(0.001);\n  scale_vel_to_dev_ = scale_vel_to_dev.value_or(1000.0);\n  scale_vel_from_dev_ = scale_vel_from_dev.value_or(0.001);\n  scale_eff_from_dev_ = scale_eff_from_dev.value_or(0.001);\n  offset_pos_to_dev_ = offset_pos_to_dev.value_or(0.0);\n  offset_pos_from_dev_ = offset_pos_from_dev.value_or(0.0);\n  switching_state_ = (ros2_canopen::State402::InternalState)switching_state.value_or(\n    (int)ros2_canopen::State402::InternalState::Operation_Enable);\n  homing_timeout_seconds_ = homing_timeout_seconds.value_or(10);\n\n  // Multi-channel configuration\n  num_channels_ = 1;\n  try\n  {\n    num_channels_ = this->config_[\"num_channels\"].template as<uint8_t>();\n  }\n  catch (...)\n  {\n  }\n\n  // Parse channel names\n  channel_names_.clear();\n  try\n  {\n    auto names_node = this->config_[\"channel_names\"];\n    if (names_node.IsDefined() && names_node.IsSequence())\n    {\n      for (size_t i = 0; i < names_node.size(); ++i)\n      {\n        channel_names_.push_back(names_node[i].template as<std::string>());\n      }\n    }\n  }\n  catch (...)\n  {\n  }\n\n  // Generate default names if not provided\n  if (channel_names_.empty())\n  {\n    for (uint8_t i = 0; i < num_channels_; ++i)\n    {\n      channel_names_.push_back(std::string(this->node_->get_name()) + \"/\" + std::to_string(i));\n    }\n  }\n\n  // Resolve per-channel scales/offsets into per-channel contexts\n  channels_.clear();\n  channels_.resize(num_channels_);\n  for (uint8_t i = 0; i < num_channels_; ++i)\n  {\n    channels_[i].scale_pos_to_dev = scale_pos_to_dev_;\n    channels_[i].scale_pos_from_dev = scale_pos_from_dev_;\n    channels_[i].scale_vel_to_dev = scale_vel_to_dev_;\n    channels_[i].scale_vel_from_dev = scale_vel_from_dev_;\n    channels_[i].scale_eff_from_dev = scale_eff_from_dev_;\n    channels_[i].offset_pos_to_dev = offset_pos_to_dev_;\n    channels_[i].offset_pos_from_dev = offset_pos_from_dev_;\n  }\n\n  try\n  {\n    auto channels_node = this->config_[\"channels\"];\n    if (channels_node.IsDefined() && channels_node.IsSequence())\n    {\n      for (size_t i = 0; i < channels_node.size() && i < num_channels_; ++i)\n      {\n        auto ch = channels_node[i];\n        try\n        {\n          channels_[i].scale_pos_to_dev = ch[\"scale_pos_to_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].scale_pos_from_dev = ch[\"scale_pos_from_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].scale_vel_to_dev = ch[\"scale_vel_to_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].scale_vel_from_dev = ch[\"scale_vel_from_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].scale_eff_from_dev = ch[\"scale_eff_from_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].offset_pos_to_dev = ch[\"offset_pos_to_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n        try\n        {\n          channels_[i].offset_pos_from_dev = ch[\"offset_pos_from_dev\"].template as<double>();\n        }\n        catch (...)\n        {\n        }\n      }\n    }\n  }\n  catch (...)\n  {\n  }\n\n  RCLCPP_INFO(\n    this->node_->get_logger(),\n    \"num_channels: %u\\nscale_pos_to_dev_ %f\\nscale_pos_from_dev_ %f\\nscale_vel_to_dev_ \"\n    \"%f\\nscale_vel_from_dev_ \"\n    \"%f\\nscale_eff_from_dev_ %f\\noffset_pos_to_dev_ %f\\noffset_pos_from_dev_ \"\n    \"%f\\nhoming_timeout_seconds_ %i\\n\",\n    num_channels_, scale_pos_to_dev_, scale_pos_from_dev_, scale_vel_to_dev_, scale_vel_from_dev_,\n    scale_eff_from_dev_, offset_pos_to_dev_, offset_pos_from_dev_, homing_timeout_seconds_);\n\n  // Create per-channel services\n  create_per_channel_services();\n}\n\ntemplate <>\nvoid NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>::configure(bool called_from_base)\n{\n  this->configure_common();\n}\n\ntemplate <>\nvoid NodeCanopen402Driver<rclcpp::Node>::configure(bool called_from_base)\n{\n  this->configure_common();\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::activate(bool called_from_base)\n{\n  NodeCanopenProxyDriver<NODETYPE>::activate(false);\n  // Register default modes for all motor instances\n  for (auto & ch : channels_)\n  {\n    if (!ch.motor) continue;\n    ch.motor->registerDefaultModes();\n    ch.motor->set_diagnostic_status_msgs(this->diagnostic_collector_, this->diagnostic_enabled_);\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::deactivate(bool called_from_base)\n{\n  NodeCanopenProxyDriver<NODETYPE>::deactivate(false);\n  timer_->cancel();\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::poll_timer_callback()\n{\n  NodeCanopenProxyDriver<NODETYPE>::poll_timer_callback();\n  // Handle read/write for all motors\n  for (auto & ch : channels_)\n  {\n    if (!ch.motor) continue;\n    ch.motor->handleRead();\n    ch.motor->handleWrite();\n  }\n  publish();\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::publish()\n{\n  sensor_msgs::msg::JointState js_msg;\n  // Publish joint state for all channels\n  for (size_t ch = 0; ch < channels_.size(); ++ch)\n  {\n    std::string name;\n    if (num_channels_ == 1)\n    {\n      // Single-channel: use node name (legacy behavior)\n      name = std::string(this->node_->get_name());\n    }\n    else\n    {\n      // Multi-channel: use channel_name\n      if (ch < channel_names_.size())\n      {\n        name = channel_names_[ch];\n      }\n      else\n      {\n        // Fallback if channel_names not configured\n        name = std::string(this->node_->get_name()) + \"/ch\" + std::to_string(ch);\n      }\n    }\n\n    js_msg.name.push_back(name);\n    if (!channels_[ch].motor)\n    {\n      js_msg.position.push_back(0.0);\n      js_msg.velocity.push_back(0.0);\n      js_msg.effort.push_back(0.0);\n      continue;\n    }\n\n    js_msg.position.push_back(\n      channels_[ch].motor->get_position() * channels_[ch].scale_pos_from_dev +\n      channels_[ch].offset_pos_from_dev);\n    js_msg.velocity.push_back(channels_[ch].motor->get_speed() * channels_[ch].scale_vel_from_dev);\n    js_msg.effort.push_back(channels_[ch].motor->get_effort() * channels_[ch].scale_eff_from_dev);\n  }\n  publish_joint_state->publish(js_msg);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::add_to_master()\n{\n  NodeCanopenProxyDriver<NODETYPE>::add_to_master();\n  // Create separate Motor402 instance for each channel\n  channels_.resize(num_channels_);\n  for (uint8_t ch = 0; ch < num_channels_; ++ch)\n  {\n    channels_[ch].motor =\n      std::make_shared<Motor402>(this->lely_driver_, switching_state_, homing_timeout_seconds_, ch);\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_init(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = this->init_motor(channel);\n}\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_recover(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = this->recover_motor(channel);\n}\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_halt(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = this->halt_motor(channel);\n}\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_position(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Profiled_Position, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_velocity(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Profiled_Velocity, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_cyclic_position(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Cyclic_Synchronous_Position, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_interpolated_position(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Interpolated_Position, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_cyclic_velocity(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Cyclic_Synchronous_Velocity, channel);\n}\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_torque(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Profiled_Torque, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_mode_cyclic_torque(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_operation_mode(MotorBase::Cyclic_Synchronous_Torque, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_set_target(\n  const canopen_interfaces::srv::COTargetDouble::Request::SharedPtr request,\n  canopen_interfaces::srv::COTargetDouble::Response::SharedPtr response, const uint8_t channel)\n{\n  response->success = set_target(request->target, channel);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_disable(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor)\n    {\n      response->success = false;\n      return;\n    }\n    response->success = channels_[channel].motor->handleDisable();\n  }\n  else\n  {\n    response->success = false;\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::handle_enable(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response, const uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size() || !channels_[channel].motor)\n    {\n      response->success = false;\n      return;\n    }\n    response->success = channels_[channel].motor->handleEnable();\n  }\n  else\n  {\n    response->success = false;\n  }\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopen402Driver<NODETYPE>::init_motor(uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size())\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(), \"Invalid channel %u (max %lu)\", channel, channels_.size() - 1);\n      return false;\n    }\n    if (!channels_[channel].motor) return false;\n    return channels_[channel].motor->handleInit();\n  }\n  else\n  {\n    RCLCPP_INFO(this->node_->get_logger(), \"Initialisation failed.\");\n    return false;\n  }\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopen402Driver<NODETYPE>::recover_motor(uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size())\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(), \"Invalid channel %u (max %lu)\", channel, channels_.size() - 1);\n      return false;\n    }\n    if (!channels_[channel].motor) return false;\n    return channels_[channel].motor->handleRecover();\n  }\n  else\n  {\n    return false;\n  }\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopen402Driver<NODETYPE>::halt_motor(uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size())\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(), \"Invalid channel %u (max %lu)\", channel, channels_.size() - 1);\n      return false;\n    }\n    if (!channels_[channel].motor) return false;\n    return channels_[channel].motor->handleHalt();\n  }\n  else\n  {\n    return false;\n  }\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopen402Driver<NODETYPE>::set_operation_mode(uint16_t mode, uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size())\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(), \"Invalid channel %u (max %lu)\", channel, channels_.size() - 1);\n      return false;\n    }\n\n    if (!channels_[channel].motor) return false;\n\n    if (channels_[channel].motor->getMode() != mode)\n    {\n      return channels_[channel].motor->enterModeAndWait(mode);\n    }\n    else\n    {\n      return false;\n    }\n  }\n  return false;\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopen402Driver<NODETYPE>::set_target(double target, uint8_t channel)\n{\n  if (this->activated_.load())\n  {\n    if (channel >= channels_.size())\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(), \"Invalid channel %u (max %lu)\", channel, channels_.size() - 1);\n      return false;\n    }\n\n    if (!channels_[channel].motor) return false;\n\n    auto mode = channels_[channel].motor->getMode();\n\n    const double scale_pos_to_dev = channels_[channel].scale_pos_to_dev;\n    const double offset_pos_to_dev = channels_[channel].offset_pos_to_dev;\n    const double scale_vel_to_dev = channels_[channel].scale_vel_to_dev;\n\n    double scaled_target;\n    if (\n      (mode == MotorBase::Profiled_Position) or (mode == MotorBase::Cyclic_Synchronous_Position) or\n      (mode == MotorBase::Interpolated_Position))\n    {\n      scaled_target = target * scale_pos_to_dev + offset_pos_to_dev;\n    }\n    else if (\n      (mode == MotorBase::Velocity) or (mode == MotorBase::Profiled_Velocity) or\n      (mode == MotorBase::Cyclic_Synchronous_Velocity))\n    {\n      scaled_target = target * scale_vel_to_dev;\n    }\n    else\n    {\n      scaled_target = target;\n    }\n\n    return channels_[channel].motor->setTarget(scaled_target);\n  }\n  else\n  {\n    return false;\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopen402Driver<NODETYPE>::diagnostic_callback(\n  diagnostic_updater::DiagnosticStatusWrapper & stat)\n{\n  // Handle diagnostics for all motors\n  for (size_t ch = 0; ch < channels_.size(); ++ch)\n  {\n    if (!channels_[ch].motor) continue;\n    channels_[ch].motor->handleDiag();\n  }\n\n  stat.summary(this->diagnostic_collector_->getLevel(), this->diagnostic_collector_->getMessage());\n  stat.add(\"device_state\", this->diagnostic_collector_->getValue(\"DEVICE\"));\n  stat.add(\"nmt_state\", this->diagnostic_collector_->getValue(\"NMT\"));\n  stat.add(\"emcy_state\", this->diagnostic_collector_->getValue(\"EMCY\"));\n  stat.add(\"cia402_mode\", this->diagnostic_collector_->getValue(\"cia402_mode\"));\n  stat.add(\"cia402_state\", this->diagnostic_collector_->getValue(\"cia402_state\"));\n\n  // Add per-channel diagnostic info\n  for (size_t ch = 0; ch < channels_.size(); ++ch)\n  {\n    std::string ch_prefix = \"ch\" + std::to_string(ch) + \"_\";\n    stat.add(\n      ch_prefix + \"mode\",\n      this->diagnostic_collector_->getValue((ch_prefix + \"cia402_mode\").c_str()));\n    stat.add(\n      ch_prefix + \"state\",\n      this->diagnostic_collector_->getValue((ch_prefix + \"cia402_state\").c_str()));\n  }\n}\n\n#endif\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/profiled_position_mode.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef PROFILED_POSITION_MODE_HPP\n#define PROFILED_POSITION_MODE_HPP\n\n#include <cstdint>\n#include <memory>\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include \"mode_target_helper.hpp\"\n\nnamespace ros2_canopen\n{\nclass ProfiledPositionMode : public ModeTargetHelper<int32_t>\n{\n  const uint16_t base_index = 0x607A;\n  uint16_t channel_offset_;  // Channel offset for multi-axis support (CiA 402-2)\n  std::shared_ptr<LelyDriverBridge> driver;\n\n  double last_target_;\n  uint16_t sw_;\n\npublic:\n  enum SW_masks\n  {\n    MASK_Reached = (1 << State402::SW_Target_reached),\n    MASK_Acknowledged = (1 << State402::SW_Operation_mode_specific0),\n    MASK_Error = (1 << State402::SW_Operation_mode_specific1),\n  };\n  enum CW_bits\n  {\n    CW_NewPoint = Command402::CW_Operation_mode_specific0,\n    CW_Immediate = Command402::CW_Operation_mode_specific1,\n    CW_Blending = Command402::CW_Operation_mode_specific3,\n  };\n  ProfiledPositionMode(std::shared_ptr<LelyDriverBridge> driver, uint16_t channel_offset = 0)\n  : ModeTargetHelper(MotorBase::Profiled_Position), channel_offset_(channel_offset)\n  {\n    this->driver = driver;\n  }\n\n  virtual bool start()\n  {\n    sw_ = 0;\n    last_target_ = std::numeric_limits<double>::quiet_NaN();\n    return ModeTargetHelper::start();\n  }\n  virtual bool read(const uint16_t & sw)\n  {\n    sw_ = sw;\n    return (sw & MASK_Error) == 0;\n  }\n  virtual bool write(OpModeAccesser & cw)\n  {\n    cw.set(CW_Immediate);\n    if (hasTarget())\n    {\n      int32_t target = getTarget();\n      if ((sw_ & MASK_Acknowledged) == 0 && target != last_target_)\n      {\n        if (cw.get(CW_NewPoint))\n        {\n          cw.reset(CW_NewPoint);  // reset if needed\n        }\n        else\n        {\n          // Apply channel offset to object dictionary index\n          driver->universal_set_value(base_index + channel_offset_, 0x0, target);\n          cw.set(CW_NewPoint);\n          last_target_ = target;\n        }\n      }\n      else if (sw_ & MASK_Acknowledged)\n      {\n        cw.reset(CW_NewPoint);\n      }\n      return true;\n    }\n    return false;\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // PROFILED_POSITION_MODE_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/state.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef CANOPEN_402_DRIVER_STATE_HPP\n#define CANOPEN_402_DRIVER_STATE_HPP\n\n#include <chrono>\n#include <condition_variable>\n#include <mutex>\n\nnamespace ros2_canopen\n{\nclass State402\n{\npublic:\n  enum StatusWord\n  {\n    SW_Ready_To_Switch_On = 0,\n    SW_Switched_On = 1,\n    SW_Operation_enabled = 2,\n    SW_Fault = 3,\n    SW_Voltage_enabled = 4,\n    SW_Quick_stop = 5,\n    SW_Switch_on_disabled = 6,\n    SW_Warning = 7,\n    SW_Manufacturer_specific0 = 8,\n    SW_Remote = 9,\n    SW_Target_reached = 10,\n    SW_Internal_limit = 11,\n    SW_Operation_mode_specific0 = 12,\n    SW_Operation_mode_specific1 = 13,\n    SW_Manufacturer_specific1 = 14,\n    SW_Manufacturer_specific2 = 15\n  };\n  enum InternalState\n  {\n    Unknown = 0,\n    Start = 0,\n    Not_Ready_To_Switch_On = 1,\n    Switch_On_Disabled = 2,\n    Ready_To_Switch_On = 3,\n    Switched_On = 4,\n    Operation_Enable = 5,\n    Quick_Stop_Active = 6,\n    Fault_Reaction_Active = 7,\n    Fault = 8,\n  };\n  InternalState getState();\n  InternalState read(uint16_t sw);\n  bool waitForNewState(\n    const std::chrono::steady_clock::time_point & abstime, InternalState & state);\n  State402() : state_(Unknown) {}\n\nprivate:\n  std::condition_variable cond_;\n  std::mutex mutex_;\n  InternalState state_;\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_402_DRIVER_STATE_HPP\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/visibility_control.h",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#ifndef CANOPEN_402_DRIVER__VISIBILITY_CONTROL_H_\n#define CANOPEN_402_DRIVER__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_402_DRIVER_EXPORT __attribute__((dllexport))\n#define CANOPEN_402_DRIVER_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_402_DRIVER_EXPORT __declspec(dllexport)\n#define CANOPEN_402_DRIVER_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_402_DRIVER_BUILDING_LIBRARY\n#define CANOPEN_402_DRIVER_PUBLIC CANOPEN_402_DRIVER_EXPORT\n#else\n#define CANOPEN_402_DRIVER_PUBLIC CANOPEN_402_DRIVER_IMPORT\n#endif\n#define CANOPEN_402_DRIVER_PUBLIC_TYPE CANOPEN_402_DRIVER_PUBLIC\n#define CANOPEN_402_DRIVER_LOCAL\n#else\n#define CANOPEN_402_DRIVER_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_402_DRIVER_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_402_DRIVER_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_402_DRIVER_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_402_DRIVER_PUBLIC\n#define CANOPEN_402_DRIVER_LOCAL\n#endif\n#define CANOPEN_402_DRIVER_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_402_DRIVER__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_402_driver/include/canopen_402_driver/word_accessor.hpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#ifndef WORD_ACCESSOR_HPP\n#define WORD_ACCESSOR_HPP\n\n#include <cstdint>\n\nnamespace ros2_canopen\n{\ntemplate <uint16_t MASK>\nclass WordAccessor\n{\n  uint16_t & word_;\n\npublic:\n  WordAccessor(uint16_t & word) : word_(word) {}\n  bool set(uint8_t bit)\n  {\n    uint16_t val = MASK & (1 << bit);\n    word_ |= val;\n    return val;\n  }\n  bool reset(uint8_t bit)\n  {\n    uint16_t val = MASK & (1 << bit);\n    word_ &= ~val;\n    return val;\n  }\n  bool get(uint8_t bit) const { return word_ & (1 << bit); }\n  uint16_t get() const { return word_ & MASK; }\n  WordAccessor & operator=(const uint16_t & val)\n  {\n    word_ = (word_ & ~MASK) | (val & MASK);\n    return *this;\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // WORD_ACCESSOR_HPP\n"
  },
  {
    "path": "canopen_402_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_402_driver</name>\n  <version>0.3.2</version>\n  <description>Driver for devices implementing CIA402 profile</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>LGPL-v3</license>\n\n  <buildtool_depend>ament_cmake_ros</buildtool_depend>\n\n  <depend>boost</depend>\n  <depend>canopen_base_driver</depend>\n  <depend>canopen_core</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>canopen_proxy_driver</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n  <depend>sensor_msgs</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_402_driver/src/cia402_driver.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#include \"canopen_402_driver/cia402_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nCia402Driver::Cia402Driver(rclcpp::NodeOptions node_options) : CanopenDriver(node_options)\n{\n  node_canopen_402_driver_ =\n    std::make_shared<node_interfaces::NodeCanopen402Driver<rclcpp::Node>>(this);\n  node_canopen_driver_ =\n    std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(node_canopen_402_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::Cia402Driver)\n"
  },
  {
    "path": "canopen_402_driver/src/command.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#include \"canopen_402_driver/command.hpp\"\n#include <stdexcept>\nusing namespace ros2_canopen;\n\nconst Command402::TransitionTable Command402::transitions_;\n\nCommand402::TransitionTable::TransitionTable()\n{\n  typedef State402 s;\n\n  transitions_.reserve(32);\n\n  Op disable_voltage(0, (1 << CW_Fault_Reset) | (1 << CW_Enable_Voltage));\n  /* 7*/ add(s::Ready_To_Switch_On, s::Switch_On_Disabled, disable_voltage);\n  /* 9*/ add(s::Operation_Enable, s::Switch_On_Disabled, disable_voltage);\n  /*10*/ add(s::Switched_On, s::Switch_On_Disabled, disable_voltage);\n  /*12*/ add(s::Quick_Stop_Active, s::Switch_On_Disabled, disable_voltage);\n\n  Op automatic(0, 0);\n  /* 0*/ add(s::Start, s::Not_Ready_To_Switch_On, automatic);\n  /* 1*/ add(s::Not_Ready_To_Switch_On, s::Switch_On_Disabled, automatic);\n  /*14*/ add(s::Fault_Reaction_Active, s::Fault, automatic);\n\n  Op shutdown(\n    (1 << CW_Quick_Stop) | (1 << CW_Enable_Voltage), (1 << CW_Fault_Reset) | (1 << CW_Switch_On));\n  /* 2*/ add(s::Switch_On_Disabled, s::Ready_To_Switch_On, shutdown);\n  /* 6*/ add(s::Switched_On, s::Ready_To_Switch_On, shutdown);\n  /* 8*/ add(s::Operation_Enable, s::Ready_To_Switch_On, shutdown);\n\n  Op switch_on(\n    (1 << CW_Quick_Stop) | (1 << CW_Enable_Voltage) | (1 << CW_Switch_On),\n    (1 << CW_Fault_Reset) | (1 << CW_Enable_Operation));\n  /* 3*/ add(s::Ready_To_Switch_On, s::Switched_On, switch_on);\n  /* 5*/ add(s::Operation_Enable, s::Switched_On, switch_on);\n\n  Op enable_operation(\n    (1 << CW_Quick_Stop) | (1 << CW_Enable_Voltage) | (1 << CW_Switch_On) |\n      (1 << CW_Enable_Operation),\n    (1 << CW_Fault_Reset));\n  /* 4*/ add(s::Switched_On, s::Operation_Enable, enable_operation);\n  /*16*/ add(s::Quick_Stop_Active, s::Operation_Enable, enable_operation);\n\n  Op quickstop((1 << CW_Enable_Voltage), (1 << CW_Fault_Reset) | (1 << CW_Quick_Stop));\n  /* 7*/ add(\n    s::Ready_To_Switch_On, s::Quick_Stop_Active, quickstop);    // transit to Switch_On_Disabled\n  /*10*/ add(s::Switched_On, s::Quick_Stop_Active, quickstop);  // transit to Switch_On_Disabled\n  /*11*/ add(s::Operation_Enable, s::Quick_Stop_Active, quickstop);\n\n  // fault reset\n  /*15*/ add(s::Fault, s::Switch_On_Disabled, Op((1 << CW_Fault_Reset), 0));\n}\nState402::InternalState Command402::nextStateForEnabling(State402::InternalState state)\n{\n  switch (state)\n  {\n    case State402::Start:\n      return State402::Not_Ready_To_Switch_On;\n\n    case State402::Fault:\n    case State402::Not_Ready_To_Switch_On:\n      return State402::Switch_On_Disabled;\n\n    case State402::Switch_On_Disabled:\n      return State402::Ready_To_Switch_On;\n\n    case State402::Ready_To_Switch_On:\n      return State402::Switched_On;\n\n    case State402::Switched_On:\n    case State402::Quick_Stop_Active:\n    case State402::Operation_Enable:\n      return State402::Operation_Enable;\n\n    case State402::Fault_Reaction_Active:\n      return State402::Fault;\n  }\n  throw std::out_of_range(\"state value is illegal\");\n}\n\nbool Command402::setTransition(\n  uint16_t & cw, const State402::InternalState & from, const State402::InternalState & to,\n  State402::InternalState * next)\n{\n  try\n  {\n    if (from != to)\n    {\n      State402::InternalState hop = to;\n      if (next)\n      {\n        if (to == State402::Operation_Enable) hop = nextStateForEnabling(from);\n        *next = hop;\n      }\n      transitions_.get(from, hop)(cw);\n    }\n    return true;\n  }\n  catch (...)\n  {\n    /// @todo Print error here.\n  }\n  return false;\n}\n"
  },
  {
    "path": "canopen_402_driver/src/default_homing_mode.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#include \"canopen_402_driver/default_homing_mode.hpp\"\nusing namespace ros2_canopen;\n\ntemplate <uint16_t mask, uint16_t not_equal>\nstruct masked_status_not_equal\n{\n  uint16_t & status_;\n  masked_status_not_equal(uint16_t & status) : status_(status) {}\n  bool operator()() const { return (status_ & mask) != not_equal; }\n};\nbool DefaultHomingMode::start()\n{\n  execute_ = false;\n  return read(0);\n}\nbool DefaultHomingMode::read(const uint16_t & sw)\n{\n  std::scoped_lock lock(mutex_);\n  uint16_t old = status_;\n  status_ = sw & (MASK_Reached | MASK_Attained | MASK_Error);\n  if (old != status_)\n  {\n    cond_.notify_all();\n  }\n  return true;\n}\nbool DefaultHomingMode::write(Mode::OpModeAccesser & cw)\n{\n  cw = 0;\n  if (execute_)\n  {\n    cw.set(CW_StartHoming);\n    return true;\n  }\n  return false;\n}\n\nbool DefaultHomingMode::executeHoming()\n{\n  // Apply channel offset to object dictionary index\n  int hmode = driver->universal_get_value<int8_t>(base_index + channel_offset_, 0x0);\n  if (hmode == 0)\n  {\n    return true;\n  }\n  /// @ get abs time from canopen_master\n  std::chrono::steady_clock::time_point prepare_time =\n    std::chrono::steady_clock::now() + std::chrono::seconds(1);\n  // ensure homing is not running\n  std::unique_lock lock(mutex_);\n  if (!cond_.wait_until(\n        lock, prepare_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0>(status_)))\n  {\n    return error(\"could not prepare homing\");\n  }\n  if (status_ & MASK_Error)\n  {\n    return error(\"homing error before start\");\n  }\n\n  execute_ = true;\n\n  // ensure start\n  if (!cond_.wait_until(\n        lock, prepare_time,\n        masked_status_not_equal<MASK_Error | MASK_Attained | MASK_Reached, MASK_Reached>(status_)))\n  {\n    return error(\"homing did not start\");\n  }\n  if (status_ & MASK_Error)\n  {\n    return error(\"homing error at start\");\n  }\n\n  //  std::chrono::steady_clock::time_point finish_time =\n  //    std::chrono::steady_clock::now() + std::chrono::seconds(10);  //\n  //\n  std::chrono::steady_clock::time_point finish_time =\n    std::chrono::steady_clock::now() + std::chrono::seconds(homing_timeout_seconds_);  //\n\n  // wait for attained\n  if (!cond_.wait_until(\n        lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Attained, 0>(status_)))\n  {\n    return error(\"homing not attained\");\n  }\n  if (status_ & MASK_Error)\n  {\n    return error(\"homing error during process\");\n  }\n\n  // wait for motion stop\n  if (!cond_.wait_until(\n        lock, finish_time, masked_status_not_equal<MASK_Error | MASK_Reached, 0>(status_)))\n  {\n    return error(\"homing did not stop\");\n  }\n  if (status_ & MASK_Error)\n  {\n    return error(\"homing error during stop\");\n  }\n\n  if ((status_ & MASK_Reached) && (status_ & MASK_Attained))\n  {\n    execute_ = false;\n    return true;\n  }\n\n  return error(\"something went wrong while homing\");\n}\n"
  },
  {
    "path": "canopen_402_driver/src/lifecycle_cia402_driver.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#include \"canopen_402_driver/lifecycle_cia402_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nLifecycleCia402Driver::LifecycleCia402Driver(rclcpp::NodeOptions node_options)\n: LifecycleCanopenDriver(node_options)\n{\n  node_canopen_402_driver_ =\n    std::make_shared<node_interfaces::NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>>(this);\n  node_canopen_driver_ =\n    std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(node_canopen_402_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleCia402Driver)\n"
  },
  {
    "path": "canopen_402_driver/src/motor.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2023 Vishnuprasad Prachandabhanu\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#include \"canopen_402_driver/motor.hpp\"\nusing namespace ros2_canopen;\n\nbool Motor402::setTarget(double val)\n{\n  if (state_handler_.getState() == State402::Operation_Enable)\n  {\n    std::scoped_lock lock(mode_mutex_);\n    return selected_mode_ && selected_mode_->setTarget(val);\n  }\n  return false;\n}\nbool Motor402::isModeSupported(uint16_t mode)\n{\n  return mode != MotorBase::Homing && allocMode(mode);\n}\n\nbool Motor402::enterModeAndWait(uint16_t mode)\n{\n  bool okay = mode != MotorBase::Homing && switchMode(mode);\n  return okay;\n}\n\nuint16_t Motor402::getMode()\n{\n  std::scoped_lock lock(mode_mutex_);\n  return selected_mode_ ? selected_mode_->mode_id_ : (uint16_t)MotorBase::No_Mode;\n}\n\nbool Motor402::isModeSupportedByDevice(uint16_t mode)\n{\n  uint32_t supported_modes =\n    driver->universal_get_value<uint32_t>(get_channel_index(supported_drive_modes_index), 0x0);\n  bool supported = supported_modes & (1 << (mode - 1));\n  bool below_max = mode <= 32;\n  bool above_min = mode > 0;\n  return below_max && above_min && supported;\n}\nvoid Motor402::registerMode(uint16_t id, const ModeSharedPtr & m)\n{\n  std::scoped_lock map_lock(map_mutex_);\n  if (m && m->mode_id_ == id) modes_.insert(std::make_pair(id, m));\n}\n\nModeSharedPtr Motor402::allocMode(uint16_t mode)\n{\n  ModeSharedPtr res;\n  if (isModeSupportedByDevice(mode))\n  {\n    std::scoped_lock map_lock(map_mutex_);\n    std::unordered_map<uint16_t, ModeSharedPtr>::iterator it = modes_.find(mode);\n    if (it != modes_.end())\n    {\n      res = it->second;\n    }\n  }\n  return res;\n}\n\nbool Motor402::switchMode(uint16_t mode)\n{\n  if (mode == MotorBase::No_Mode)\n  {\n    std::scoped_lock lock(mode_mutex_);\n    selected_mode_.reset();\n    try\n    {  // try to set mode (use channel-specific index)\n      driver->universal_set_value<int8_t>(get_channel_index(op_mode_index), 0x0, mode);\n    }\n    catch (...)\n    {\n    }\n    if (enable_diagnostics_.load())\n    {\n      this->diag_collector_->addf(\n        \"cia402_mode\", \"No mode selected: %d (channel %u)\", mode, channel_);\n    }\n    return true;\n  }\n\n  ModeSharedPtr next_mode = allocMode(mode);\n  if (!next_mode)\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Mode is not supported.\");\n    return false;\n  }\n\n  if (!next_mode->start())\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Could not  start mode.\");\n    return false;\n  }\n\n  {  // disable mode handler\n    std::scoped_lock lock(mode_mutex_);\n\n    if (mode_id_ == mode && selected_mode_ && selected_mode_->mode_id_ == mode)\n    {\n      // nothing to do\n      return true;\n    }\n\n    selected_mode_.reset();\n  }\n\n  if (!switchState(switching_state_)) return false;\n\n  driver->universal_set_value<int8_t>(get_channel_index(op_mode_index), 0x0, mode);\n\n  bool okay = false;\n\n  {  // wait for switch\n    std::unique_lock lock(mode_mutex_);\n\n    std::chrono::steady_clock::time_point abstime =\n      std::chrono::steady_clock::now() + std::chrono::seconds(5);\n    if (monitor_mode_)\n    {\n      while (mode_id_ != mode && mode_cond_.wait_until(lock, abstime) == std::cv_status::no_timeout)\n      {\n      }\n    }\n    else\n    {\n      while (mode_id_ != mode && std::chrono::steady_clock::now() < abstime)\n      {\n        lock.unlock();  // unlock inside loop\n        driver->universal_get_value<int8_t>(get_channel_index(op_mode_display_index), 0x0);  // poll\n        std::this_thread::sleep_for(std::chrono::milliseconds(20));  // wait some time\n        lock.lock();\n      }\n    }\n\n    if (mode_id_ == mode)\n    {\n      selected_mode_ = next_mode;\n      okay = true;\n      if (enable_diagnostics_.load())\n      {\n        this->diag_collector_->addf(\n          \"cia402_mode\", \"Mode switched to: %d (channel %u)\", mode, channel_);\n      }\n    }\n    else\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Mode switch timed out.\");\n      driver->universal_set_value<int8_t>(get_channel_index(op_mode_index), 0x0, mode_id_);\n      if (enable_diagnostics_.load())\n      {\n        this->diag_collector_->addf(\n          \"cia402_mode\", \"Mode switch timed out: %d (channel %u)\", mode, channel_);\n      }\n    }\n  }\n\n  if (!switchState(State402::Operation_Enable)) return false;\n\n  return okay;\n}\n\nbool Motor402::switchState(const State402::InternalState & target)\n{\n  std::chrono::steady_clock::time_point abstime =\n    std::chrono::steady_clock::now() + state_switch_timeout_;\n  State402::InternalState state = state_handler_.getState();\n  target_state_ = target;\n  while (state != target_state_)\n  {\n    std::unique_lock lock(cw_mutex_);\n    State402::InternalState next = State402::Unknown;\n    bool success = Command402::setTransition(control_word_, state, target_state_, &next);\n    if (!success)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Could not set transition.\");\n      return false;\n    }\n    else if (enable_diagnostics_.load() && success)\n    {\n      this->diag_collector_->addf(\"cia402_state\", \"State switched to: %d\", next);\n    }\n    lock.unlock();\n    if (state != next && !state_handler_.waitForNewState(abstime, state))\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Transition timed out.\");\n      if (enable_diagnostics_.load())\n      {\n        this->diag_collector_->addf(\n          \"cia402_state\", \"State transition timed out: %d -> %d\", state, next);\n      }\n      return false;\n    }\n  }\n  return state == target;\n}\n\nbool Motor402::readState()\n{\n  uint16_t old_sw,\n    sw = driver->universal_get_value<uint16_t>(\n      get_channel_index(status_word_entry_index), 0x0);  // TODO: added error handling\n  old_sw = status_word_.exchange(sw);\n\n  state_handler_.read(sw);\n\n  std::unique_lock lock(mode_mutex_);\n  uint16_t new_mode;\n  new_mode = driver->universal_get_value<int8_t>(get_channel_index(op_mode_display_index), 0x0);\n  // RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Mode %hhi\",new_mode);\n\n  if (selected_mode_ && selected_mode_->mode_id_ == new_mode)\n  {\n    if (!selected_mode_->read(sw))\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Mode handler has error.\");\n    }\n  }\n  if (new_mode != mode_id_)\n  {\n    mode_id_ = new_mode;\n    mode_cond_.notify_all();\n  }\n  if (selected_mode_ && selected_mode_->mode_id_ != new_mode)\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Mode does not match.\");\n  }\n  if (sw & (1 << State402::SW_Internal_limit))\n  {\n    if (old_sw & (1 << State402::SW_Internal_limit))\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Internal limit active\");\n    }\n    else\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Internal limit active\");\n    }\n  }\n\n  return true;\n}\nvoid Motor402::handleRead() { readState(); }\nvoid Motor402::handleWrite()\n{\n  std::scoped_lock lock(cw_mutex_);\n  control_word_ |= (1 << Command402::CW_Halt);\n  if (state_handler_.getState() == State402::Operation_Enable)\n  {\n    std::scoped_lock lock(mode_mutex_);\n    Mode::OpModeAccesser cwa(control_word_);\n    bool okay = false;\n    if (selected_mode_ && selected_mode_->mode_id_ == mode_id_)\n    {\n      okay = selected_mode_->write(cwa);\n    }\n    else\n    {\n      cwa = 0;\n    }\n    if (okay)\n    {\n      control_word_ &= ~(1 << Command402::CW_Halt);\n    }\n  }\n  if (start_fault_reset_.exchange(false))\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Fault reset (channel %u)\", channel_);\n    this->driver->universal_set_value<uint16_t>(\n      get_channel_index(control_word_entry_index), 0x0,\n      control_word_ & ~(1 << Command402::CW_Fault_Reset));\n  }\n  else\n  {\n    // RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Control Word %s\",\n    // std::bitset<16>{control_word_}.to_string());\n    this->driver->universal_set_value<uint16_t>(\n      get_channel_index(control_word_entry_index), 0x0, control_word_);\n  }\n}\nvoid Motor402::handleDiag()\n{\n  uint16_t sw = status_word_;\n  State402::InternalState state = state_handler_.getState();\n\n  switch (state)\n  {\n    case State402::Not_Ready_To_Switch_On:\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::WARN, \"Not ready to switch on\");\n      break;\n    case State402::Switch_On_Disabled:\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::WARN, \"Switch on disabled\");\n      break;\n    case State402::Ready_To_Switch_On:\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::OK, \"Ready to switch on\");\n      break;\n    case State402::Switched_On:\n      // std::cout << \"Motor operation is not enabled\" << std::endl;\n      this->diag_collector_->summary(diagnostic_msgs::msg::DiagnosticStatus::OK, \"Switched on\");\n      break;\n    case State402::Operation_Enable:\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::OK, \"Operation enabled\");\n      break;\n    case State402::Quick_Stop_Active:\n      // std::cout << \"Quick stop is active\" << std::endl;\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::WARN, \"Quick stop active\");\n      break;\n    case State402::Fault:\n      this->diag_collector_->summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"Fault\");\n      break;\n    case State402::Fault_Reaction_Active:\n      // std::cout << \"Motor has fault\" << std::endl;\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"Fault reaction active\");\n      break;\n    case State402::Unknown:\n      // std::cout << \"State is unknown\" << std::endl;\n      this->diag_collector_->summary(\n        diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"Unknown state\");\n      break;\n  }\n\n  if (sw & (1 << State402::SW_Warning))\n  {\n    // std::cout << \"Warning bit is set\" << std::endl;\n    this->diag_collector_->summary(\n      diagnostic_msgs::msg::DiagnosticStatus::WARN, \"Warning bit is set\");\n  }\n  if (sw & (1 << State402::SW_Internal_limit))\n  {\n    // std::cout << \"Internal limit active\" << std::endl;\n    this->diag_collector_->summary(\n      diagnostic_msgs::msg::DiagnosticStatus::WARN, \"Internal limit active\");\n  }\n}\n\nbool Motor402::handleInit()\n{\n  for (std::unordered_map<uint16_t, AllocFuncType>::iterator it = mode_allocators_.begin();\n       it != mode_allocators_.end(); ++it)\n  {\n    (it->second)();\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Init: Read State\");\n  if (!readState())\n  {\n    std::cout << \"Could not read motor state\" << std::endl;\n    return false;\n  }\n  {\n    std::scoped_lock lock(cw_mutex_);\n    control_word_ = 0;\n    start_fault_reset_ = true;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Init: Enable\");\n  if (!switchState(State402::Operation_Enable))\n  {\n    std::cout << \"Could not enable motor\" << std::endl;\n    return false;\n  }\n\n  ModeSharedPtr m = allocMode(MotorBase::Homing);\n  if (!m)\n  {\n    std::cout << \"Homeing mode not supported\" << std::endl;\n    return true;  // homing not supported\n  }\n\n  HomingMode * homing = dynamic_cast<HomingMode *>(m.get());\n\n  if (!homing)\n  {\n    std::cout << \"Homing mode has incorrect handler\" << std::endl;\n    return false;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Init: Switch to homing\");\n  if (!switchMode(MotorBase::Homing))\n  {\n    std::cout << \"Could not enter homing mode\" << std::endl;\n    return false;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Init: Execute homing\");\n  if (!homing->executeHoming())\n  {\n    std::cout << \"Homing failed\" << std::endl;\n    return false;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Init: Switch no mode\");\n  if (!switchMode(MotorBase::No_Mode))\n  {\n    std::cout << \"Could not enter no mode\" << std::endl;\n    return false;\n  }\n  return true;\n}\nbool Motor402::handleShutdown()\n{\n  switchMode(MotorBase::No_Mode);\n  return switchState(State402::Switch_On_Disabled);\n}\nbool Motor402::handleHalt()\n{\n  State402::InternalState state = state_handler_.getState();\n  std::scoped_lock lock(cw_mutex_);\n\n  // do not demand quickstop in case of fault\n  if (state == State402::Fault_Reaction_Active || state == State402::Fault) return false;\n\n  if (state != State402::Operation_Enable)\n  {\n    target_state_ = state;\n  }\n  else\n  {\n    target_state_ = State402::Quick_Stop_Active;\n    if (!Command402::setTransition(control_word_, state, State402::Quick_Stop_Active, 0))\n    {\n      std::cout << \"Could not quick stop\" << std::endl;\n      return false;\n    }\n  }\n  return true;\n}\nbool Motor402::handleRecover()\n{\n  start_fault_reset_ = true;\n  {\n    std::scoped_lock lock(mode_mutex_);\n    if (selected_mode_ && !selected_mode_->start())\n    {\n      std::cout << \"Could not restart mode.\" << std::endl;\n      return false;\n    }\n  }\n  if (!switchState(State402::Operation_Enable))\n  {\n    std::cout << \"Could not enable motor\" << std::endl;\n    return false;\n  }\n  return true;\n}\nbool Motor402::handleEnable()\n{\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Enable: Read State\");\n  if (!readState())\n  {\n    std::cout << \"Could not read motor state\" << std::endl;\n    return false;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Enable\");\n  if (!switchState(State402::Operation_Enable))\n  {\n    std::cout << \"Could not enable motor\" << std::endl;\n    return false;\n  }\n  return true;\n}\n\nbool Motor402::handleDisable()\n{\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Disable: Read State\");\n  if (!readState())\n  {\n    std::cout << \"Could not read motor state\" << std::endl;\n    return false;\n  }\n  RCLCPP_INFO(rclcpp::get_logger(\"canopen_402_driver\"), \"Disable\");\n  if (!switchState(State402::Switched_On))\n  {\n    std::cout << \"Could not disable motor\" << std::endl;\n    return false;\n  }\n  return true;\n}\n"
  },
  {
    "path": "canopen_402_driver/src/node_interfaces/node_canopen_402_driver.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp\"\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver_impl.hpp\"\n#include \"canopen_core/driver_error.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopen402Driver<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopen402Driver<rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_402_driver/src/state.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//    Copyright 2014-2022 Authors of ros_canopen\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#include \"canopen_402_driver/state.hpp\"\n#include <mutex>\nusing namespace ros2_canopen;\n\nState402::InternalState State402::getState()\n{\n  std::scoped_lock lock(mutex_);\n  return state_;\n}\n\nState402::InternalState State402::read(uint16_t sw)\n{\n  static const uint16_t r = (1 << SW_Ready_To_Switch_On);\n  static const uint16_t s = (1 << SW_Switched_On);\n  static const uint16_t o = (1 << SW_Operation_enabled);\n  static const uint16_t f = (1 << SW_Fault);\n  static const uint16_t q = (1 << SW_Quick_stop);\n  static const uint16_t d = (1 << SW_Switch_on_disabled);\n\n  InternalState new_state = Unknown;\n\n  uint16_t state = sw & (d | q | f | o | s | r);\n  switch (state)\n  {\n    //   ( d | q | f | o | s | r ):\n    case (0 | 0 | 0 | 0 | 0 | 0):\n    case (0 | q | 0 | 0 | 0 | 0):\n      // std::cout << \"Not_Ready_To_Switch_On\" << std::endl;\n      new_state = Not_Ready_To_Switch_On;\n      break;\n\n    case (d | 0 | 0 | 0 | 0 | 0):\n    case (d | q | 0 | 0 | 0 | 0):\n      // std::cout << \"Switch_On_Disabled\" << std::endl;\n      new_state = Switch_On_Disabled;\n      break;\n\n    case (0 | q | 0 | 0 | 0 | r):\n      // std::cout << \"Ready_To_Switch_On\" << std::endl;\n      new_state = Ready_To_Switch_On;\n      break;\n\n    case (0 | q | 0 | 0 | s | r):\n      new_state = Switched_On;\n      break;\n\n    case (0 | q | 0 | o | s | r):\n      new_state = Operation_Enable;\n      break;\n\n    case (0 | 0 | 0 | o | s | r):\n      new_state = Quick_Stop_Active;\n      break;\n\n    case (0 | 0 | f | o | s | r):\n    case (0 | q | f | o | s | r):\n      new_state = Fault_Reaction_Active;\n      break;\n\n    case (0 | 0 | f | 0 | 0 | 0):\n    case (0 | q | f | 0 | 0 | 0):\n      new_state = Fault;\n      break;\n\n    default:\n      /// @todo Throw error here.\n      break;\n  }\n  std::scoped_lock lock(mutex_);\n  if (new_state != state_)\n  {\n    state_ = new_state;\n    cond_.notify_all();\n  }\n  return state_;\n}\nbool State402::waitForNewState(\n  const std::chrono::steady_clock::time_point & abstime, State402::InternalState & state)\n{\n  std::unique_lock lock(mutex_);\n  while (state_ == state && cond_.wait_until(lock, abstime) == std::cv_status::no_timeout)\n  {\n  }\n  bool res = state != state_;\n  state = state_;\n  return res;\n}\n"
  },
  {
    "path": "canopen_402_driver/test/CMakeLists.txt",
    "content": "ament_add_gtest(test_driver_component\ntest_driver_component.cpp\n)\ntarget_include_directories(test_driver_component PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_driver_component\n  ${canopen_interfaces_TARGETS}\n  ${sensor_msgs_TARGETS}\n  canopen_base_driver::base_driver\n  canopen_base_driver::lely_driver_bridge\n  canopen_base_driver::lifecycle_base_driver\n  canopen_base_driver::node_canopen_base_driver\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  canopen_proxy_driver::lifecycle_proxy_driver\n  canopen_proxy_driver::node_canopen_proxy_driver\n  canopen_proxy_driver::proxy_driver\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n  sensor_msgs::sensor_msgs_library\n)\n"
  },
  {
    "path": "canopen_402_driver/test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=2\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=32\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1A00\n20=0x1A01\n21=0x1F25\n22=0x1F55\n23=0x1F80\n24=0x1F81\n25=0x1F82\n26=0x1F84\n27=0x1F85\n28=0x1F86\n29=0x1F87\n30=0x1F88\n31=0x1F89\n32=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=12\n1=0x2000\n2=0x2001\n3=0x2200\n4=0x2201\n5=0x5800\n6=0x5801\n7=0x5A00\n8=0x5A01\n9=0x5C00\n10=0x5C01\n11=0x5E00\n12=0x5E01\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=2\n2=0x00000082\n3=0x00000083\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=2\n2=0x00000005\n3=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=2\n2=0x00000360\n3=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=proxy_device_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=proxy_device_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=proxy_device_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=proxy_device_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_402_driver/test/test_driver_component.cpp",
    "content": "//    Copyright 2023 Christoph Hellmann Santos\n//\n// This program is free software: you can redistribute it and/or modify\n// it under the terms of the GNU General Public License as published by\n// the Free Software Foundation, either version 3 of the License, or\n// (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU General Public License\n// along with this program.  If not, see <https://www.gnu.org/licenses/>.\n//\n#include <rclcpp/executors.hpp>\n#include <rclcpp_components/component_manager.hpp>\n#include <rclcpp_components/node_factory.hpp>\n#include <rclcpp_components/node_instance_wrapper.hpp>\n#include <thread>\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"gtest/gtest.h\"\nusing namespace rclcpp_components;\n\nTEST(ComponentLoad, test_load_component_1)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_402_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[0]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n\nTEST(ComponentLoad, test_load_component_2)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_402_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[1]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_base_driver/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_base_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.2.9 (2024-04-16)\n------------------\n* Add timeouts\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.3.2 (2025-12-05)\n------------------\n* `#379 <https://github.com/ros-industrial/ros2_canopen/issues/379>`_: Fix data conversion in the Lely Bridge to enable more data types and proper handling of Emcy in ros2_control\n* Fixed types handling in canopen_ros2_control.\n* `#376 <https://github.com/ros-industrial/ros2_canopen/issues/376>`_: increase boot timout\n* Contributors: Dr. Denis Stogl, Vishnuprasad Prachandabhanu\n\n0.3.1 (2025-06-23)\n------------------\n* Add boot timeout and retry\n* Include driver exception when boot failed\n* Boot Timeout: Add parameter to base driver to pass to wait as timeout\n* Contributors: Gerry Salinas, Luis Camero, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* Merge pull request `#280 <https://github.com/ros-industrial/ros2_canopen/issues/280>`_ from ipa-vsp/fix/yaml-build-error\n  Fix undefined reference to yaml library\n* pre-commit update\n* Merge pull request `#261 <https://github.com/ros-industrial/ros2_canopen/issues/261>`_ from gsalinas/configurable-sdo-timeout\n  Configurable SDO timeout\n* 0.2.9\n* forthcoming\n* Merge pull request `#220 <https://github.com/ros-industrial/ros2_canopen/issues/220>`_ from ipa-vsp/feature/timeout-config\n  Add timeouts\n* Set SDO timeout from node config.\n* Replace two more hardcoded timeouts.\n* Include timeout in documentation comment for LelyDriverBridge.\n* Make 20ms a default argument of the master & driver bridges.\n* change error to warn for testing\n* remove build warings\n* non transmit time from bus.yml\n* Contributors: Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix maintainer naming\n* Update printed output in lely_driver_bridge.cpp\n* Contributors: Christoph Hellmann Santos, yos627\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix base driver lifecyle\n* Fix node polling mode in base driver\n* Contributors: Błażej Sowa, Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Lovro, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_base_driver/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_base_driver)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_ros REQUIRED)\nfind_package(Boost REQUIRED COMPONENTS thread)\nfind_package(canopen_core REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(diagnostic_updater REQUIRED)\nfind_package(lely_core_libraries REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\nfind_package(std_msgs REQUIRED)\nfind_package(std_srvs REQUIRED)\n\nadd_library(lely_driver_bridge\n  src/lely_driver_bridge.cpp\n)\ntarget_compile_features(lely_driver_bridge PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lely_driver_bridge PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lely_driver_bridge PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(lely_driver_bridge PUBLIC\n  ${lely_core_libraries_LIBRARIES}\n  canopen_core::node_canopen_driver\n  rclcpp::rclcpp\n)\n\n\nadd_library(node_canopen_base_driver\n  src/node_interfaces/node_canopen_base_driver.cpp\n)\ntarget_compile_features(node_canopen_base_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_base_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_base_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(node_canopen_base_driver PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${std_msgs_TARGETS}\n  ${std_srvs_TARGETS}\n  Boost::thread\n  canopen_core::node_canopen_driver\n  diagnostic_updater::diagnostic_updater\n  lely_driver_bridge\n)\nmessage(STATUS \"node_canopen_base_driver: ${lely_core_libraries_LIBRARIES}\")\n\nadd_library(lifecycle_base_driver\n  src/lifecycle_base_driver.cpp\n)\ntarget_compile_features(lifecycle_base_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lifecycle_base_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lifecycle_base_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(lifecycle_base_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_base_driver\n  rclcpp_components::component\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(lifecycle_base_driver PRIVATE \"CANOPEN_base_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(lifecycle_base_driver \"ros2_canopen::LifecycleBaseDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::LifecycleBaseDriver;$<TARGET_FILE:lifecycle_base_driver >\\n\")\n\n\n\n\nadd_library(base_driver\n  src/base_driver.cpp\n)\ntarget_compile_features(base_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(base_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(base_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(base_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_base_driver\n  rclcpp_components::component\n)\n\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(base_driver PRIVATE \"CANOPEN_base_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(base_driver \"ros2_canopen::BaseDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::BaseDriver;$<TARGET_FILE:base_driver >\\n\")\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\ninstall(\n  TARGETS lifecycle_base_driver base_driver node_canopen_base_driver lely_driver_bridge\n  EXPORT export_${PROJECT_NAME}\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  RUNTIME DESTINATION bin\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_gtest REQUIRED)\n  add_subdirectory(test)\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  lifecycle_base_driver\n  base_driver\n  node_canopen_base_driver\n  lely_driver_bridge\n)\nament_export_targets(\n  export_${PROJECT_NAME}\n)\nament_export_dependencies(\n  canopen_core\n  canopen_interfaces\n  diagnostic_updater\n  lely_core_libraries\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n  std_msgs\n  std_srvs\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_base_driver/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/base_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n#define CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"canopen_core/driver_node.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Abstract Class for a CANopen Device Node\n *\n * This class provides the base functionality for creating a\n * CANopen device node. It provides callbacks for nmt and rpdo.\n */\nclass BaseDriver : public ros2_canopen::CanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>> node_canopen_base_driver_;\n\npublic:\n  BaseDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_base_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_base_driver_->register_rpdo_cb(rpdo_cb);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/diagnostic_collector.hpp",
    "content": "// Copyright 2023 ROS-Industrial\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef DIAGNOSTICS_COLLECTOR_HPP_\n#define DIAGNOSTICS_COLLECTOR_HPP_\n\n#include <atomic>\n#include <mutex>\n#include <string>\n#include <unordered_map>\n#include \"diagnostic_msgs/msg/diagnostic_status.hpp\"\n#include \"diagnostic_updater/diagnostic_updater.hpp\"\n#include \"diagnostic_updater/publisher.hpp\"\n\nnamespace ros2_canopen\n{\n\n/**\n * @brief A class to collect diagnostic information\n *\n */\nclass DiagnosticsCollector\n{\npublic:\n  DiagnosticsCollector() : level_(diagnostic_msgs::msg::DiagnosticStatus::OK) {}\n\n  /**\n   * @brief Get the Level\n   * Returns the current level (OK, WARN, ERROR or STALE) of the diagnostic\n   * @return unsigned char\n   */\n  unsigned char getLevel() const\n  {\n    return static_cast<unsigned char>(level_.load(std::memory_order_relaxed));\n  }\n\n  /**\n   * @brief Get the Message object\n   * Returns the current message of the diagnostic\n   * @return std::string\n   */\n  std::string getMessage() const { return message_; }\n\n  /**\n   * @brief Get the Value object\n   * Returns the current different device state values of the diagnostic.\n   * @param key Search device state by key. Eg. \"DEVICE\", \"NMT\", \"EMCY\", \"cia402_state\",\n   * \"cia402_mode\" etc.\n   * @return std::string\n   */\n  std::string getValue(const std::string & key) const\n  {\n    std::lock_guard<std::mutex> lock(mutex_);\n    auto it = values_.find(key);\n    if (it != values_.end())\n      return it->second;\n    else\n      return \"\";  // Return an empty string if key not found\n  }\n\n  /**\n   * @brief Store current device summary\n   *\n   * @param lvl Operation level (OK, WARN, ERROR or STALE)\n   * @param message Device summary message\n   */\n  void summary(unsigned char lvl, const std::string & message)\n  {\n    std::lock_guard<std::mutex> lock(mutex_);\n    this->setLevel(lvl);\n    this->setMessage(message);\n  }\n\n  /**\n   * @brief Store current device summary\n   *\n   * @param lvl Operation level (OK, WARN, ERROR or STALE)\n   * @param format Device summary message format\n   * @param ...\n   */\n  void summaryf(unsigned char lvl, const char * format, ...)\n  {\n    va_list args;\n    va_start(args, format);\n    char buffer[1024];\n    vsnprintf(buffer, sizeof(buffer), format, args);\n    va_end(args);\n    summary(lvl, std::string(buffer));\n  }\n\n  /**\n   * @brief Add a device state value\n   *\n   * @param key Device state key. Eg. \"DEVICE\", \"NMT\", \"EMCY\", \"cia402_state\", \"cia402_mode\" etc.\n   * @param value Current device state value\n   */\n  void add(const std::string & key, const std::string & value)\n  {\n    std::lock_guard<std::mutex> lock(mutex_);\n    this->setValue(key, value);\n  }\n\n  /**\n   * @brief Add a device state value\n   *\n   * @param key Device state key. Eg. \"DEVICE\", \"NMT\", \"EMCY\", \"cia402_state\", \"cia402_mode\" etc.\n   * @param format Current device state value format\n   * @param ...\n   */\n  void addf(const std::string & key, const char * format, ...)\n  {\n    va_list args;\n    va_start(args, format);\n    char buffer[1024];\n    vsnprintf(buffer, sizeof(buffer), format, args);\n    va_end(args);\n    add(key, std::string(buffer));\n  }\n\n  /**\n   * @brief Update all diagnostic information\n   *\n   * @param lvl Operation level (OK, WARN, ERROR or STALE)\n   * @param message Device summary message\n   * @param key Device state key. Eg. \"DEVICE\", \"NMT\", \"EMCY\", \"cia402_state\", \"cia402_mode\" etc.\n   * @param value Current device state value\n   */\n  void updateAll(\n    unsigned char lvl, const std::string & message, const std::string & key,\n    const std::string & value)\n  {\n    std::lock_guard<std::mutex> lock(mutex_);\n    this->setLevel(lvl);\n    this->setMessage(message);\n    this->setValue(key, value);\n  }\n\nprivate:\n  std::atomic<unsigned char> level_;\n  std::string message_;\n  std::unordered_map<std::string, std::string> values_;\n  mutable std::mutex mutex_;\n\n  void setLevel(unsigned char lvl)\n  {\n    level_.store(static_cast<unsigned char>(lvl), std::memory_order_relaxed);\n  }\n\n  void setMessage(const std::string & message) { message_ = message; }\n\n  void setValue(const std::string & key, const std::string & value) { values_[key] = value; }\n\n  // std::unordered_map<std::string, std::string> getValues() const\n  // {\n  //     std::lock_guard<std::mutex> lock(mutex_);\n  //     return values_;\n  // }\n};\n}  // namespace ros2_canopen\n\n#endif  // DIAGNOSTICS_COLLECTOR_HPP_\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/lely_driver_bridge.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CANOPEN_BASE_DRIVER__LELY_BRIDGE_HPP_\n#define CANOPEN_BASE_DRIVER__LELY_BRIDGE_HPP_\n\n#include <sys/stat.h>\n\n#include <lely/co/dcf.hpp>\n#include <lely/co/dev.hpp>\n#include <lely/co/obj.hpp>\n#include <lely/coapp/fiber_driver.hpp>\n#include <lely/coapp/master.hpp>\n#include <lely/coapp/sdo_error.hpp>\n#include <lely/ev/co_task.hpp>\n#include <lely/ev/future.hpp>\n\n#include <atomic>\n#include <condition_variable>\n#include <future>\n#include <memory>\n#include <mutex>\n#include <rclcpp/rclcpp.hpp>\n#include <string>\n#include <system_error>\n#include <thread>\n#include <vector>\n\n#include <boost/lockfree/queue.hpp>\n#include <boost/optional.hpp>\n#include <boost/thread.hpp>\n\n#include \"canopen_core/exchange.hpp\"\n\nusing namespace std::chrono_literals;\nusing namespace lely;\n\nnamespace ros2_canopen\n{\nstruct pdo_mapping\n{\n  bool is_tpdo;\n  bool is_rpdo;\n};\n\ntypedef std::map<uint16_t, std::map<uint8_t, pdo_mapping>> PDOMap;\nclass DriverDictionary : public lely::CODev\n{\npublic:\n  DriverDictionary(std::string eds_file) : lely::CODev(eds_file.c_str()) {}\n  ~DriverDictionary()\n  {\n    // lely::CODev::~CODev();\n  }\n\n  std::shared_ptr<PDOMap> createPDOMapping()\n  {\n    std::shared_ptr<PDOMap> pdo_map = std::make_shared<PDOMap>();\n    fetchRPDO(pdo_map);\n    fetchTPDO(pdo_map);\n    return pdo_map;\n    // COObj * first = co_dev_first_obj((lely::CODev *)this);\n    // COObj * last = co_dev_last_obj((lely::CODev *)this);\n    // if (first == nullptr || last == nullptr)\n    // {\n    //   std::cout << \"No objects found in dictionary\" << std::endl;\n    //   return pdo_map;\n    // }\n    // COObj * current = first;\n    // while (current != last)\n    // {\n    //   uint16_t index = co_obj_get_idx(current);\n    //   auto subids = current->getSubidx();\n    //   bool created = false;\n    //   for (auto subid : subids)\n    //   {\n    //     bool is_rpdo = checkObjRPDO(index, subid);\n    //     bool is_tpdo = checkObjTPDO(index, subid);\n    //     std::cout << \"Found subobject: index=\" << std::hex << (int)index\n    //               << \" subindex=\" << (int)subid << (is_rpdo ? \" rpdo\" : \"\")\n    //               << (is_tpdo ? \" tpdo\" : \"\") << std::endl;\n    //     if (is_rpdo || is_tpdo)\n    //     {\n    //       pdo_mapping mapping;\n    //       mapping.is_rpdo = is_rpdo;\n    //       mapping.is_tpdo = is_tpdo;\n    //       if (!created)\n    //       {\n    //         pdo_map->emplace(index, std::map<uint8_t, pdo_mapping>());\n    //         created = true;\n    //       }\n    //       (*pdo_map)[index].emplace(subid, mapping);\n    //     }\n    //   }\n    //   current = co_obj_next(current);\n    // }\n    // return pdo_map;\n  }\n\n  void fetchRPDO(std::shared_ptr<PDOMap> map)\n  {\n    for (int index = 0; index < 256; index++)\n    {\n      for (int subindex = 1; subindex < 9; subindex++)\n      {\n        auto obj = find(0x1600 + index, subindex);\n        if (obj == nullptr)\n        {\n          continue;\n        }\n        uint32_t data;\n        {\n          data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();\n        }\n        uint8_t tmps = (data >> 8) & 0xFF;\n        uint16_t tmpi = (data >> 16) & 0xFFFF;\n        if (tmpi == 0U)\n        {\n          continue;\n        }\n        pdo_mapping mapping;\n        mapping.is_rpdo = true;\n        mapping.is_tpdo = false;\n        (*map)[tmpi][tmps] = mapping;\n        std::cout << \"Found rpdo mapped object: index=\" << std::hex << (int)tmpi\n                  << \" subindex=\" << (int)tmps << std::endl;\n      }\n    }\n  }\n  void fetchTPDO(std::shared_ptr<PDOMap> map)\n  {\n    for (int index = 0; index < 256; index++)\n    {\n      for (int subindex = 1; subindex < 9; subindex++)\n      {\n        auto obj = find(0x1A00 + index, subindex);\n        if (obj == nullptr)\n        {\n          continue;\n        }\n        uint32_t data;\n        {\n          data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();\n        }\n        uint8_t tmps = (data >> 8) & 0xFF;\n        uint16_t tmpi = (data >> 16) & 0xFFFF;\n        if (tmpi == 0U)\n        {\n          continue;\n        }\n\n        pdo_mapping mapping;\n        mapping.is_rpdo = false;\n        mapping.is_tpdo = true;\n        (*map)[tmpi][tmps] = mapping;\n        std::cout << \"Found tpdo mapped object: index=\" << std::hex << (int)tmpi\n                  << \" subindex=\" << (int)tmps << std::endl;\n      }\n    }\n  }\n\n  bool checkObjRPDO(uint16_t idx, uint8_t subidx)\n  {\n    // std::cout << \"Checking for rpo mapping of object: index=\" << std::hex << (int)idx\n    //           << \" subindex=\" << (int)subidx << std::endl;\n    for (int i = 0; i < 256; i++)\n    {\n      if (this->checkObjInPDO(i, 0x1600, idx, subidx))\n      {\n        return true;\n      }\n    }\n    return false;\n  }\n\n  bool checkObjTPDO(uint16_t idx, uint8_t subidx)\n  {\n    // std::cout << \"Checking for rpo mapping of object: index=\" << std::hex << (int)idx\n    //          << \" subindex=\" << (int)subidx << std::endl;\n    for (int i = 0; i < 256; i++)\n    {\n      if (this->checkObjInPDO(i, 0x1A00, idx, subidx))\n      {\n        return true;\n      }\n    }\n    return false;\n  }\n\n  bool checkObjInPDO(uint8_t pdo, uint16_t mapping_idx, uint16_t idx, uint8_t subindex)\n  {\n    for (int i = 1; i < 9; i++)\n    {\n      auto obj = find(mapping_idx + pdo, i);\n      if (obj == nullptr)\n      {\n        return false;\n      }\n      uint32_t data;\n      {\n        data = obj->getVal<CO_DEFTYPE_UNSIGNED32>();\n      }\n      uint8_t tmps = (data >> 8) & 0xFF;\n      uint16_t tmpi = (data >> 16) & 0xFFFF;\n\n      if (tmps == subindex && tmpi == idx)\n      {\n        std::cout << \"Found object in pdo: \" << (int)pdo << std::endl;\n        return true;\n      }\n    }\n\n    return false;\n  }\n};\n\nenum class LelyBridgeErrc\n{\n  NotListedDevice = 'A',\n  NoResponseOnDeviceType = 'B',\n  DeviceTypeDifference = 'C',\n  VendorIdDifference = 'D',\n  HeartbeatIssue = 'E',\n  NodeGuardingIssue = 'F',\n  InconsistentProgramDownload = 'G',\n  SoftwareUpdateRequired = 'H',\n  SoftwareDownloadFailed = 'I',\n  ConfigurationDownloadFailed = 'J',\n  StartErrorControlFailed = 'K',\n  NmtSlaveInitiallyOperational = 'L',\n  ProductCodeDifference = 'M',\n  RevisionCodeDifference = 'N',\n  SerialNumberDifference = 'O',\n  TimeOut = 'T'\n};\n\nstruct LelyBridgeErrCategory : std::error_category\n{\n  const char * name() const noexcept override;\n  std::string message(int ev) const override;\n};\n}  // namespace ros2_canopen\n\nnamespace std\n{\ntemplate <>\nstruct is_error_code_enum<ros2_canopen::LelyBridgeErrc> : true_type\n{\n};\nstd::error_code make_error_code(ros2_canopen::LelyBridgeErrc);\n}  // namespace std\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lely Driver Bridge\n *\n * This class provides functionalities for bridging between\n * Lelycore drivers and standard C++ functions. This means\n * it provides async and sync functions for interacting with\n * CANopen devices using synchronisation functionalities from C++ standard\n * library.\n *\n */\nclass LelyDriverBridge : public canopen::FiberDriver\n{\nprotected:\n  // Dictionary for driver based on DCF and BIN files.\n  std::unique_ptr<DriverDictionary> dictionary_;\n  std::mutex dictionary_mutex_;\n  std::shared_ptr<PDOMap> pdo_map_;\n\n  // SDO Read synchronisation items\n  std::shared_ptr<std::promise<COData>> sdo_read_data_promise;\n  std::shared_ptr<std::promise<bool>> sdo_write_data_promise;\n  std::mutex sdo_mutex;\n  bool running;\n  std::condition_variable sdo_cond;\n\n  // NMT synchronisation items\n  std::promise<canopen::NmtState> nmt_state_promise;\n  std::atomic<bool> nmt_state_is_set;\n  std::mutex nmt_mtex;\n\n  // RPDO synchronisation items\n  std::promise<COData> rpdo_promise;\n  std::atomic<bool> rpdo_is_set;\n  std::mutex pdo_mtex;\n  std::shared_ptr<SafeQueue<COData>> rpdo_queue;\n\n  // EMCY synchronisation items\n  std::promise<COEmcy> emcy_promise;\n  std::atomic<bool> emcy_is_set;\n  std::mutex emcy_mtex;\n  std::shared_ptr<SafeQueue<COEmcy>> emcy_queue;\n\n  // BOOT synchronisation items\n  std::atomic<bool> booted;\n  char boot_status;\n  std::string boot_what;\n  canopen::NmtState boot_state;\n  std::condition_variable boot_cond;\n  std::mutex boot_mtex;\n  std::chrono::milliseconds boot_timeout_;\n\n  uint8_t nodeid;\n  std::string name_;\n\n  std::chrono::milliseconds sdo_timeout;\n\n  std::function<void()> on_sync_function_;\n\n  // void set_sync_function(std::function<void()> on_sync_function)\n  // {\n  //   on_sync_function_ = on_sync_function;\n  // }\n\n  // void unset_sync_function()\n  // {\n  //   on_sync_function_ = std::function<void()>();\n  // }\n\n  void OnSync(uint8_t cnt, const time_point & t) noexcept override\n  {\n    if (on_sync_function_ != nullptr)\n    {\n      try\n      {\n        on_sync_function_();\n      }\n      catch (...)\n      {\n      }\n    }\n  }\n\n  /**\n   * @brief OnState Callback\n   *\n   * This callback function is called when an Nmt state\n   * change is detected on the connected device.\n   *\n   * @param [in] state    NMT State\n   */\n  void OnState(canopen::NmtState state) noexcept override;\n\n  /**\n   * @brief OnBoot Callback\n   * This callback is called when the Boot process of the\n   * slave that was initiated by the master has been success\n   * fully finished.\n   *\n   * @param st\n   * @param es\n   * @param what\n   */\n  virtual void OnBoot(canopen::NmtState st, char es, const ::std::string & what) noexcept override;\n\n  /**\n   * @brief OnRpdoWrite Callback\n   *\n   * This callback function is called when an RPDO\n   * write request is received from the connected device.\n   * @todo This function should use a threadsafe queue not the icky implementation we have now.\n   *\n   * @param [in] idx      Object Index\n   * @param [in] subidx   Object Subindex\n   */\n  void OnRpdoWrite(uint16_t idx, uint8_t subidx) noexcept override;\n\n  /**\n   * The function invoked when an EMCY message is received from the remote node.\n   * @todo This function should use a threadsafe queue not the icky implementation we have now.\n   *\n   * @param eec  the emergency error code.\n   * @param er   the error register.\n   * @param msef the manufacturer-specific error code.\n   */\n  void OnEmcy(uint16_t eec, uint8_t er, uint8_t msef[5]) noexcept override;\n\n  // void OnConfig(::std::function<void(::std::error_code ec)> res) noexcept override;\n\npublic:\n  using FiberDriver::FiberDriver;\n\n  /**\n   * @brief Construct a new Lely Bridge object\n   *\n   * @param [in] exec     Executor to use\n   * @param [in] master   Master to use\n   * @param [in] id       NodeId to connect to\n   * @param [in] eds      EDS file\n   * @param [in] bin      BIN file (concise dcf)\n   * @param [in] timeout  Timeout in milliseconds for SDO reads/writes\n   *\n   */\n  LelyDriverBridge(\n    ev_exec_t * exec, canopen::AsyncMaster & master, uint8_t id, std::string name, std::string eds,\n    std::string bin, std::chrono::milliseconds timeout = 20ms,\n    std::chrono::milliseconds boot_timeout = 20ms)\n  : FiberDriver(exec, master, id),\n    rpdo_queue(new SafeQueue<COData>()),\n    emcy_queue(new SafeQueue<COEmcy>())\n  {\n    nodeid = id;\n    running = false;\n    name_ = name;\n    dictionary_ = std::make_unique<DriverDictionary>(eds.c_str());\n    struct stat buffer;\n    if (stat(bin.c_str(), &buffer) == 0)\n    {\n      co_unsigned16_t * a = NULL;\n      co_unsigned16_t * b = NULL;\n      dictionary_->readDCF(a, b, bin.c_str());\n    }\n    pdo_map_ = dictionary_->createPDOMapping();\n    sdo_timeout = timeout;\n    boot_timeout_ = boot_timeout;\n  }\n\n  bool has_object(uint16_t idx, uint8_t subidx)\n  {\n    std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n    return this->dictionary_->find(idx, subidx) != nullptr;\n  }\n\n  /**\n   * @brief Asynchronous SDO Write\n   *\n   * Writes the data passed to the function via SDO to\n   * the connected device.\n   *\n   * @param [in] data     Data to written.\n   *\n   * @return std::future<bool>\n   * Returns an std::future<bool> that is fulfilled\n   * when the write request was done. An error is\n   * stored when the write request was unsuccessful.\n   */\n  std::future<bool> async_sdo_write(COData data);\n\n  template <typename T>\n  std::future<bool> async_sdo_write_typed(uint16_t idx, uint8_t subidx, T value)\n  {\n    std::unique_lock<std::mutex> lck(sdo_mutex);\n    if (running)\n    {\n      sdo_cond.wait(lck);\n    }\n    running = true;\n\n    auto prom = std::make_shared<std::promise<bool>>();\n    lely::COSub * sub = this->dictionary_->find(idx, subidx);\n    if (sub == nullptr)\n    {\n      std::cout << \"async_sdo_write_typed: id=\" << (unsigned int)this->get_id() << \" index=0x\"\n                << std::hex << (unsigned int)idx << \" subindex=\" << (unsigned int)subidx\n                << \" object does not exist\" << std::endl;\n      prom->set_value(false);\n      this->running = false;\n      this->sdo_cond.notify_one();\n      return prom->get_future();\n    }\n\n    this->SubmitWrite(\n      idx, subidx, value,\n      [this, value, prom](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec) mutable\n      {\n        if (ec)\n        {\n          prom->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncDownload\"));\n        }\n        else\n        {\n          std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n          this->dictionary_->setVal<T>(idx, subidx, value);\n          prom->set_value(true);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      this->sdo_timeout);\n    return prom->get_future();\n  }\n\n  template <typename T>\n  bool sync_sdo_write_typed(\n    uint16_t idx, uint8_t subidx, T value, std::chrono::milliseconds timeout)\n  {\n    auto fut = async_sdo_write_typed(idx, subidx, value);\n    auto wait_res = fut.wait_for(timeout);\n    if (wait_res == std::future_status::timeout)\n    {\n      std::cout << \"sync_sdo_write_typed: id=\" << (unsigned int)this->get_id() << \" index=0x\"\n                << std::hex << (unsigned int)idx << \" subindex=\" << (unsigned int)subidx\n                << \" timed out.\" << std::endl;\n      return false;\n    }\n    bool res = false;\n    try\n    {\n      res = fut.get();\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(rclcpp::get_logger(name_), e.what());\n    }\n    return res;\n  }\n\n  /**\n   * @brief Aynchronous SDO Read\n   *\n   * Reads the indicated SDO object from the connected\n   * device.\n   *\n   * @param [in] data       Data to be read, the data entry is not used.\n   * @return std::future<COData>\n   * Returns an std::future<COData> that is fulfilled\n   * when the read request was done. The result of the request\n   * is stored in the future. An error is stored when the read\n   * request was unsuccessful.\n   */\n  std::future<COData> async_sdo_read(COData data);\n\n  template <typename T>\n  std::future<T> async_sdo_read_typed(uint16_t idx, uint8_t subidx)\n  {\n    std::unique_lock<std::mutex> lck(sdo_mutex);\n    if (running)\n    {\n      sdo_cond.wait(lck);\n    }\n    running = true;\n\n    auto prom = std::make_shared<std::promise<T>>();\n    lely::COSub * sub = this->dictionary_->find(idx, subidx);\n    if (sub == nullptr)\n    {\n      std::cout << \"async_sdo_read: id=\" << (unsigned int)this->get_id() << \" index=0x\" << std::hex\n                << (unsigned int)idx << \" subindex=\" << (unsigned int)subidx\n                << \" object does not exist\" << std::endl;\n      try\n      {\n        throw lely::canopen::SdoError(this->get_id(), idx, subidx, lely::canopen::SdoErrc::NO_OBJ);\n      }\n      catch (...)\n      {\n        prom->set_exception(std::current_exception());\n      }\n      this->running = false;\n      this->sdo_cond.notify_one();\n      return prom->get_future();\n    }\n    this->SubmitRead<T>(\n      idx, subidx,\n      [this, prom](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec, T value) mutable\n      {\n        if (ec)\n        {\n          prom->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncUpload\"));\n        }\n        else\n        {\n          std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n          this->dictionary_->setVal<T>(idx, subidx, value);\n          prom->set_value(value);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      this->sdo_timeout);\n    return prom->get_future();\n  }\n\n  template <typename T>\n  bool sync_sdo_read_typed(\n    uint16_t idx, uint8_t subidx, T & value, std::chrono::milliseconds timeout)\n  {\n    auto fut = async_sdo_read_typed<T>(idx, subidx);\n    auto wait_res = fut.wait_for(timeout);\n    if (wait_res == std::future_status::timeout)\n    {\n      std::cout << \"sync_sdo_read_typed: id=\" << (unsigned int)this->get_id() << \" index=0x\"\n                << std::hex << (unsigned int)idx << \" subindex=\" << (unsigned int)subidx\n                << \" timed out.\" << std::endl;\n      return false;\n    }\n    bool res = false;\n    try\n    {\n      value = fut.get();\n      res = true;\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(rclcpp::get_logger(name_), e.what());\n      res = false;\n    }\n    return res;\n  }\n\n  /**\n   * @brief Asynchronous request for NMT\n   *\n   * Waits for an NMT state change to occur. The new\n   * state is stored in the future returned by the function.\n   *\n   * @return std::future<canopen::NmtState>\n   * The returned future is set when NMT State changes.\n   */\n  std::future<canopen::NmtState> async_request_nmt();\n\n  /**\n   * @brief Asynchronous request for RPDO\n   *\n   * Waits for an RPDO write request to be received from\n   * the slave. The content of the request are stored in\n   * the returned future.\n   * @todo This function should use a threadsafe queue not the icky implementation we have now.\n   *\n   * @return std::future<COData>\n   * The returned future is set when an RPDO event is detected.\n   */\n  std::shared_ptr<SafeQueue<COData>> get_rpdo_queue();\n\n  /**\n   * @brief Asynchronous request for EMCY\n   * @todo This function should use a threadsafe queue not the icky implementation we have now.\n   *\n   * @return std::future<COEmcy>\n   * The returned future is set when an EMCY event is detected.\n   */\n  std::shared_ptr<SafeQueue<COEmcy>> get_emcy_queue();\n\n  /**\n   * @brief Executes a TPDO transmission\n   *\n   * This function executes a TPDO transmission. The{false, true}\n   * object specified in the input data is sent if it\n   * is registered as a TPDO with the master.\n   *\n   * @param [in] data       Object and data to be written\n   */\n  void tpdo_transmit(COData data);\n\n  /**\n   * @brief Executes a NMT Command\n   *\n   * This function sends the NMT command specified as\n   * parameter.\n   *\n   * @param [in] command    NMT Command to execute\n   */\n  void nmt_command(canopen::NmtCommand command);\n\n  /**\n   * @brief Get the nodeid\n   *\n   * @return uint8_t\n   */\n  uint8_t get_id();\n\n  /**\n   * @brief Wait for device to be booted\n   *\n   * @return true\n   * @return false\n   */\n  bool wait_for_boot()\n  {\n    if (booted.load()) return true;\n\n    std::unique_lock<std::mutex> lck(boot_mtex);\n    auto status = boot_cond.wait_for(lck, boot_timeout_);\n\n    if (status == std::cv_status::timeout)\n    {\n      throw std::system_error(\n        static_cast<int>(LelyBridgeErrc::TimeOut), LelyBridgeErrCategory(), \"Boot Timeout\");\n    }\n\n    if ((boot_status != 0) && (boot_status != 'L'))\n    {\n      throw std::system_error(static_cast<int>(boot_status), LelyBridgeErrCategory(), \"Boot Issue\");\n    }\n\n    booted.store(true);\n    return true;\n  }\n\n  void set_sync_function(std::function<void()> on_sync_function)\n  {\n    on_sync_function_ = on_sync_function;\n  }\n\n  void unset_sync_function() { on_sync_function_ = std::function<void()>(); }\n\n  /**\n   * @brief Request master to boot device\n   *\n   */\n  void Boot()\n  {\n    booted.store(false);\n    FiberDriver::Boot();\n  }\n\n  /**\n   * @brief Indicates if Device is booted\n   *\n   * @return true\n   * @return false\n   */\n  bool is_booted() { return booted.load(); }\n\n  template <typename T>\n  void submit_write(COData data)\n  {\n    T value = 0;\n    std::memcpy(&value, &data.data_, sizeof(value));\n\n    this->SubmitWrite(\n      data.index_, data.subindex_, value,\n      [this, value](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec) mutable\n      {\n        if (ec)\n        {\n          this->sdo_write_data_promise->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncDownload\"));\n        }\n        else\n        {\n          std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n          this->dictionary_->setVal<T>(idx, subidx, value);\n          this->sdo_write_data_promise->set_value(true);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      this->sdo_timeout);\n  }\n\n  template <typename T>\n  void submit_read(COData data)\n  {\n    this->SubmitRead<T>(\n      data.index_, data.subindex_,\n      [this](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec, T value) mutable\n      {\n        if (ec)\n        {\n          this->sdo_read_data_promise->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncUpload\"));\n        }\n        else\n        {\n          std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n          this->dictionary_->setVal<T>(idx, subidx, value);\n          COData d = {idx, subidx, 0};\n          std::memcpy(&d.data_, &value, sizeof(T));\n          this->sdo_read_data_promise->set_value(d);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      this->sdo_timeout);\n  }\n\n  template <typename T>\n  const T universal_get_value(uint16_t index, uint8_t subindex)\n  {\n    T value = 0;\n    bool is_tpdo = false;\n    if (this->pdo_map_->find(index) != this->pdo_map_->end())\n    {\n      auto object = this->pdo_map_->at(index);\n      if (object.find(subindex) != object.end())\n      {\n        auto entry = object.at(subindex);\n        is_tpdo = entry.is_tpdo;\n      }\n    }\n    if (!is_tpdo)\n    {\n      if (sync_sdo_read_typed<T>(index, subindex, value, this->sdo_timeout))\n      {\n        return value;\n      }\n    }\n\n    std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n    if (typeid(T) == typeid(uint8_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED8>(index, subindex);\n    }\n    if (typeid(T) == typeid(uint16_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED16>(index, subindex);\n    }\n    if (typeid(T) == typeid(uint32_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_UNSIGNED32>(index, subindex);\n    }\n    if (typeid(T) == typeid(int8_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER8>(index, subindex);\n    }\n    if (typeid(T) == typeid(int16_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER16>(index, subindex);\n    }\n    if (typeid(T) == typeid(int32_t))\n    {\n      value = this->dictionary_->getVal<CO_DEFTYPE_INTEGER32>(index, subindex);\n    }\n\n    return value;\n  }\n\n  template <typename T>\n  void universal_set_value(uint16_t index, uint8_t subindex, T value)\n  {\n    bool is_rpdo = false;\n    if (this->pdo_map_->find(index) != this->pdo_map_->end())\n    {\n      auto object = this->pdo_map_->at(index);\n      if (object.find(subindex) != object.end())\n      {\n        auto entry = object.at(subindex);\n        is_rpdo = entry.is_rpdo;\n      }\n    }\n    if (is_rpdo)\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      this->dictionary_->setVal<T>(index, subindex, value);\n      this->tpdo_mapped[index][subindex] = value;\n      this->tpdo_mapped[index][subindex].WriteEvent();\n    }\n    else\n    {\n      sync_sdo_write_typed(index, subindex, value, this->sdo_timeout);\n    }\n  }\n};\n\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_BASE_DRIVER__LELY_BRIDGE_HPP_\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/lifecycle_base_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n#define CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"canopen_core/driver_node.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle Base Driver\n *\n * A very basic driver without any functionality.\n *\n */\nclass LifecycleBaseDriver : public ros2_canopen::LifecycleCanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>>\n    node_canopen_base_driver_;\n\npublic:\n  LifecycleBaseDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_base_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_base_driver_->register_rpdo_cb(rpdo_cb);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_BASE_DRIVER__CANOPEN_BASE_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_BASE_DRIVER\n#define NODE_CANOPEN_BASE_DRIVER\n\n#include \"canopen_base_driver/diagnostic_collector.hpp\"\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include \"canopen_core/node_interfaces/node_canopen_driver.hpp\"\n#include \"std_msgs/msg/string.hpp\"\n#include \"std_srvs/srv/trigger.hpp\"\n\n#include \"canopen_interfaces/msg/co_data.hpp\"\n#include \"canopen_interfaces/srv/co_read.hpp\"\n#include \"canopen_interfaces/srv/co_write.hpp\"\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\ntemplate <class NODETYPE>\nclass NodeCanopenBaseDriver : public NodeCanopenDriver<NODETYPE>\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  std::thread nmt_state_publisher_thread_;\n  std::thread rpdo_publisher_thread_;\n  std::thread emcy_publisher_thread_;\n  std::mutex driver_mutex_;\n  std::shared_ptr<ros2_canopen::LelyDriverBridge> lely_driver_;\n  uint32_t period_ms_;\n  int sdo_timeout_ms_;\n  int boot_timeout_ms_;\n  bool polling_;\n\n  // nmt state callback\n  std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb_;\n  // rpdo callback\n  std::function<void(COData, uint8_t)> rpdo_cb_;\n  // emcy callback\n  std::function<void(COEmcy, uint8_t)> emcy_cb_;\n\n  std::shared_ptr<ros2_canopen::SafeQueue<ros2_canopen::COEmcy>> emcy_queue_;\n  std::shared_ptr<ros2_canopen::SafeQueue<ros2_canopen::COData>> rpdo_queue_;\n  rclcpp::TimerBase::SharedPtr poll_timer_;\n\n  // Diagnostic components\n  std::atomic<bool> diagnostic_enabled_;\n  uint32_t diagnostic_period_ms_;\n  std::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;\n  std::shared_ptr<DiagnosticsCollector> diagnostic_collector_;\n\n  virtual void poll_timer_callback();\n  void nmt_listener();\n  virtual void on_nmt(canopen::NmtState nmt_state);\n  void rdpo_listener();\n  virtual void on_rpdo(COData data);\n  void emcy_listener();\n  virtual void on_emcy(COEmcy emcy);\n  virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);\n\npublic:\n  NodeCanopenBaseDriver(NODETYPE * node);\n\n  virtual ~NodeCanopenBaseDriver()\n  {\n    if (nmt_state_publisher_thread_.joinable())\n    {\n      nmt_state_publisher_thread_.join();\n    }\n    if (rpdo_publisher_thread_.joinable())\n    {\n      rpdo_publisher_thread_.join();\n    }\n  }\n\n  virtual void init(bool called_from_base);\n\n  virtual void configure(bool called_from_base);\n\n  virtual void activate(bool called_from_base);\n\n  virtual void deactivate(bool called_from_base);\n\n  virtual void cleanup(bool called_from_base);\n\n  virtual void shutdown(bool called_from_base);\n\n  virtual void add_to_master();\n\n  virtual void remove_from_master();\n\n  /**\n   * @brief Register a callback for NMT state change\n   *\n   * @param nmt_state_cb\n   */\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    nmt_state_cb_ = std::move(nmt_state_cb);\n  }\n\n  /**\n   * @brief Register a callback for RPDO\n   *\n   * @param rpdo_cb\n   */\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    rpdo_cb_ = std::move(rpdo_cb);\n  }\n\n  /**\n   * @brief Register a callback for EMCY\n   *\n   * @param emcy_cb\n   */\n  void register_emcy_cb(std::function<void(COEmcy, uint8_t)> emcy_cb)\n  {\n    emcy_cb_ = std::move(emcy_cb);\n  }\n};\ntypedef NodeCanopenBaseDriver<rclcpp::Node> NCBDNode;\ntypedef NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode> NCBDLifecycleNode;\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/node_interfaces/node_canopen_base_driver_impl.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_BASE_DRIVER_IMPL\n#define NODE_CANOPEN_BASE_DRIVER_IMPL\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"canopen_core/driver_error.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate <class NODETYPE>\nNodeCanopenBaseDriver<NODETYPE>::NodeCanopenBaseDriver(NODETYPE * node)\n: ros2_canopen::node_interfaces::NodeCanopenDriver<NODETYPE>(node),\n  diagnostic_enabled_(false),\n  diagnostic_collector_(new DiagnosticsCollector())\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::init(bool called_from_base)\n{\n}\n\ntemplate <>\nvoid NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>::configure(bool called_from_base)\n{\n  try\n  {\n    this->non_transmit_timeout_ =\n      std::chrono::milliseconds(this->config_[\"non_transmit_timeout\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  RCLCPP_INFO_STREAM(\n    this->node_->get_logger(),\n    \"Non transmit timeout\" << static_cast<int>(this->non_transmit_timeout_.count()) << \"ms\");\n\n  try\n  {\n    polling_ = this->config_[\"polling\"].as<bool>();\n  }\n  catch (...)\n  {\n    RCLCPP_WARN(this->node_->get_logger(), \"Could not polling from config, setting to true.\");\n    polling_ = true;\n  }\n  if (polling_)\n  {\n    try\n    {\n      period_ms_ = this->config_[\"period\"].as<std::uint32_t>();\n    }\n    catch (...)\n    {\n      RCLCPP_WARN(this->node_->get_logger(), \"Could not read period from config, setting to 10ms\");\n      period_ms_ = 10;\n    }\n  }\n\n  // Diagnostic components\n  try\n  {\n    diagnostic_enabled_ = this->config_[\"diagnostics\"][\"enable\"].as<bool>();\n  }\n  catch (...)\n  {\n    RCLCPP_WARN(\n      this->node_->get_logger(),\n      \"Could not read enable diagnostics from config, setting to false.\");\n    diagnostic_enabled_ = false;\n  }\n  if (diagnostic_enabled_.load())\n  {\n    try\n    {\n      diagnostic_period_ms_ = this->config_[\"diagnostics\"][\"period\"].as<std::uint32_t>();\n    }\n    catch (...)\n    {\n      RCLCPP_ERROR(\n        this->node_->get_logger(),\n        \"Could not read diagnostics period from config, setting to 1000ms\");\n      diagnostic_period_ms_ = 1000;\n    }\n\n    diagnostic_updater_ = std::make_shared<diagnostic_updater::Updater>(this->node_);\n    diagnostic_updater_->setHardwareID(std::to_string(this->node_id_));\n  }\n\n  std::optional<int> sdo_timeout_ms;\n  try\n  {\n    sdo_timeout_ms = std::optional(this->config_[\"sdo_timeout_ms\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  sdo_timeout_ms_ = sdo_timeout_ms.value_or(20);\n\n  std::optional<int> boot_timeout_ms;\n  try\n  {\n    boot_timeout_ms = std::optional(this->config_[\"boot_timeout_ms\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  boot_timeout_ms_ = boot_timeout_ms.value_or(1000);\n}\ntemplate <>\nvoid NodeCanopenBaseDriver<rclcpp::Node>::configure(bool called_from_base)\n{\n  try\n  {\n    this->non_transmit_timeout_ =\n      std::chrono::milliseconds(this->config_[\"non_transmit_timeout\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  RCLCPP_INFO_STREAM(\n    this->node_->get_logger(),\n    \"Non transmit timeout\" << static_cast<int>(this->non_transmit_timeout_.count()) << \"ms\");\n\n  try\n  {\n    polling_ = this->config_[\"polling\"].as<bool>();\n  }\n  catch (...)\n  {\n    RCLCPP_WARN(this->node_->get_logger(), \"Could not polling from config, setting to true.\");\n    polling_ = true;\n  }\n  if (polling_)\n  {\n    try\n    {\n      period_ms_ = this->config_[\"period\"].as<std::uint32_t>();\n    }\n    catch (...)\n    {\n      RCLCPP_WARN(this->node_->get_logger(), \"Could not read period from config, setting to 10ms\");\n      period_ms_ = 10;\n    }\n  }\n\n  // Diagnostic components\n  try\n  {\n    diagnostic_enabled_ = this->config_[\"diagnostics\"][\"enable\"].as<bool>();\n  }\n  catch (...)\n  {\n    RCLCPP_WARN(\n      this->node_->get_logger(),\n      \"Could not read enable diagnostics from config, setting to false.\");\n    diagnostic_enabled_ = false;\n  }\n  if (diagnostic_enabled_.load())\n  {\n    try\n    {\n      diagnostic_period_ms_ = this->config_[\"diagnostics\"][\"period\"].as<std::uint32_t>();\n    }\n    catch (...)\n    {\n      RCLCPP_WARN(\n        this->node_->get_logger(),\n        \"Could not read diagnostics period from config, setting to 1000ms\");\n      diagnostic_period_ms_ = 1000;\n    }\n\n    diagnostic_updater_ = std::make_shared<diagnostic_updater::Updater>(this->node_);\n    diagnostic_updater_->setHardwareID(std::to_string(this->node_id_));\n  }\n\n  std::optional<int> sdo_timeout_ms;\n  try\n  {\n    sdo_timeout_ms = std::optional(this->config_[\"sdo_timeout_ms\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  sdo_timeout_ms_ = sdo_timeout_ms.value_or(20);\n\n  std::optional<int> boot_timeout_ms;\n  try\n  {\n    boot_timeout_ms = std::optional(this->config_[\"boot_timeout_ms\"].as<int>());\n  }\n  catch (...)\n  {\n  }\n  boot_timeout_ms_ = boot_timeout_ms.value_or(1000);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::activate(bool called_from_base)\n{\n  nmt_state_publisher_thread_ =\n    std::thread(std::bind(&NodeCanopenBaseDriver<NODETYPE>::nmt_listener, this));\n  emcy_queue_ = this->lely_driver_->get_emcy_queue();\n  rpdo_queue_ = this->lely_driver_->get_rpdo_queue();\n  if (polling_)\n  {\n    RCLCPP_INFO(this->node_->get_logger(), \"Starting with polling mode.\");\n    poll_timer_ = this->node_->create_wall_timer(\n      std::chrono::milliseconds(period_ms_),\n      std::bind(&NodeCanopenBaseDriver<NODETYPE>::poll_timer_callback, this), this->timer_cbg_);\n  }\n  else\n  {\n    RCLCPP_INFO(this->node_->get_logger(), \"Starting with event mode.\");\n    this->lely_driver_->set_sync_function(\n      std::bind(&NodeCanopenBaseDriver<NODETYPE>::poll_timer_callback, this));\n  }\n\n  if (diagnostic_enabled_.load())\n  {\n    RCLCPP_INFO(this->node_->get_logger(), \"Starting with diagnostics enabled.\");\n    diagnostic_updater_->add(\n      \"diagnostic updater\", this, &NodeCanopenBaseDriver<NODETYPE>::diagnostic_callback);\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::deactivate(bool called_from_base)\n{\n  nmt_state_publisher_thread_.join();\n  if (poll_timer_) {\n    poll_timer_->cancel();\n  }\n  emcy_queue_.reset();\n  rpdo_queue_.reset();\n  if (diagnostic_enabled_.load())\n  {\n    diagnostic_updater_->removeByName(\"diagnostic updater\");\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::cleanup(bool called_from_base)\n{\n  NodeCanopenDriver<NODETYPE>::cleanup(called_from_base);\n  // this->lely_driver_->unset_sync_function();\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::shutdown(bool called_from_base)\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::add_to_master()\n{\n  RCLCPP_INFO(this->node_->get_logger(), \"eds file %s\", this->eds_.c_str());\n  RCLCPP_INFO(this->node_->get_logger(), \"bin file %s\", this->bin_.c_str());\n  std::shared_ptr<std::promise<std::shared_ptr<ros2_canopen::LelyDriverBridge>>> prom;\n  prom = std::make_shared<std::promise<std::shared_ptr<ros2_canopen::LelyDriverBridge>>>();\n  std::future<std::shared_ptr<ros2_canopen::LelyDriverBridge>> f = prom->get_future();\n  this->exec_->post(\n    [this, prom]()\n    {\n      std::scoped_lock<std::mutex> lock(this->driver_mutex_);\n      this->lely_driver_ = std::make_shared<ros2_canopen::LelyDriverBridge>(\n        *(this->exec_), *(this->master_), this->node_id_, this->node_->get_name(), this->eds_,\n        this->bin_, std::chrono::milliseconds(this->sdo_timeout_ms_),\n        std::chrono::milliseconds(this->boot_timeout_ms_));\n      this->driver_ = std::static_pointer_cast<lely::canopen::BasicDriver>(this->lely_driver_);\n      prom->set_value(lely_driver_);\n    });\n\n  auto future_status = f.wait_for(this->non_transmit_timeout_);\n  if (future_status != std::future_status::ready)\n  {\n    RCLCPP_ERROR(this->node_->get_logger(), \"Adding timed out.\");\n    throw DriverException(\"add_to_master: adding timed out\");\n  }\n  this->lely_driver_ = f.get();\n  this->driver_ = std::static_pointer_cast<lely::canopen::BasicDriver>(this->lely_driver_);\n  if (!this->lely_driver_->IsReady())\n  {\n    bool boot_success = false;\n    int boot_attempts = 0;\n    const int max_boot_attempts = 3;  // 1 retry allowed\n    RCLCPP_WARN(this->node_->get_logger(), \"Wait for device to boot...\");\n    while (!boot_success && boot_attempts < max_boot_attempts)\n    {\n      boot_attempts++;\n      try\n      {\n        this->lely_driver_->wait_for_boot();  // This will block and throw on failure\n        boot_success = true;\n        RCLCPP_INFO(this->node_->get_logger(), \"Driver booted and ready.\");\n      }\n      catch (const std::exception & e)\n      {\n        RCLCPP_ERROR(\n          this->node_->get_logger(), \"Boot attempt %d failed: %s\", boot_attempts, e.what());\n\n        if (boot_attempts < max_boot_attempts)\n        {\n          RCLCPP_INFO(this->node_->get_logger(), \"Sending NMT reset before retrying boot\");\n          this->lely_driver_->nmt_command(canopen::NmtCommand::RESET_NODE);\n          this->lely_driver_->Boot();  // Trigger boot again\n          RCLCPP_WARN(this->node_->get_logger(), \"Retrying boot configuration...\");\n        }\n        else\n        {\n          RCLCPP_ERROR(this->node_->get_logger(), \"Boot failed after %d attempts\", boot_attempts);\n        }\n      }\n    }\n    if (!boot_success)\n    {\n      throw DriverException(\n        std::string(\"Boot failed after \") + std::to_string(boot_attempts) + \" attempts\");\n    }\n  }\n\n  if (diagnostic_enabled_.load())\n  {\n    diagnostic_collector_->updateAll(\n      diagnostic_msgs::msg::DiagnosticStatus::OK, \"Device ready\", \"DEVICE\", \"Added to master.\");\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::remove_from_master()\n{\n  std::shared_ptr<std::promise<void>> prom = std::make_shared<std::promise<void>>();\n  auto f = prom->get_future();\n  this->exec_->post(\n    [this, prom]()\n    {\n      this->driver_.reset();\n      this->lely_driver_.reset();\n      prom->set_value();\n    });\n\n  auto future_status = f.wait_for(this->non_transmit_timeout_);\n  if (future_status != std::future_status::ready)\n  {\n    throw DriverException(\"remove_from_master: removing timed out\");\n  }\n  if (diagnostic_enabled_.load())\n  {\n    diagnostic_collector_->updateAll(\n      diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"Device removed\", \"DEVICE\",\n      \"Removed from master.\");\n  }\n}\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::nmt_listener()\n{\n  while (rclcpp::ok())\n  {\n    std::future<lely::canopen::NmtState> f;\n    {\n      std::scoped_lock<std::mutex> lock(this->driver_mutex_);\n      f = this->lely_driver_->async_request_nmt();\n    }\n    while (f.wait_for(this->non_transmit_timeout_) != std::future_status::ready)\n    {\n      if (!this->activated_.load()) return;\n    }\n    try\n    {\n      auto state = f.get();\n      if (nmt_state_cb_)\n      {\n        nmt_state_cb_(state, this->lely_driver_->get_id());\n      }\n      on_nmt(state);\n    }\n    catch (const std::future_error & e)\n    {\n      break;\n    }\n  }\n}\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::on_nmt(canopen::NmtState nmt_state)\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::on_rpdo(COData data)\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::on_emcy(COEmcy emcy)\n{\n  diagnostic_collector_->summary(\n    diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"Emergency message received\");\n  std::string emcy_msg = \"Emergency message: \";\n  emcy_msg.append(\"eec: \");\n  emcy_msg.append(std::to_string(emcy.eec));\n  emcy_msg.append(\" er: \");\n  emcy_msg.append(std::to_string(emcy.er));\n  emcy_msg.append(\" msef: \");\n  for (auto & msef : emcy.msef)\n  {\n    emcy_msg.append(std::to_string(msef));\n    emcy_msg.append(\" \");\n  }\n  diagnostic_collector_->add(\"EMCY\", emcy_msg);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::rdpo_listener()\n{\n  RCLCPP_INFO(this->node_->get_logger(), \"Starting RPDO Listener\");\n  auto q = lely_driver_->get_rpdo_queue();\n  while (rclcpp::ok())\n  {\n    ros2_canopen::COData rpdo;\n    while (!q->wait_and_pop_for(this->non_transmit_timeout_, rpdo))\n    {\n      if (!this->activated_.load()) return;\n    }\n    try\n    {\n      if (rpdo_cb_)\n      {\n        rpdo_cb_(rpdo, this->lely_driver_->get_id());\n      }\n      on_rpdo(rpdo);\n    }\n    catch (const std::exception & e)\n    {\n      RCLCPP_ERROR_STREAM(this->node_->get_logger(), \"RPDO Listener error: \" << e.what());\n      break;\n    }\n  }\n}\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::poll_timer_callback()\n{\n  for (int i = 0; i < 10; i++)\n  {\n    auto opt = emcy_queue_->try_pop();\n    if (!opt.has_value())\n    {\n      break;\n    }\n    try\n    {\n      if (emcy_cb_)\n      {\n        emcy_cb_(opt.value(), this->lely_driver_->get_id());\n      }\n      on_emcy(opt.value());\n    }\n    catch (const std::exception & e)\n    {\n      RCLCPP_ERROR_STREAM(this->node_->get_logger(), \"EMCY poll error: \" << e.what());\n      break;\n    }\n  }\n  for (int i = 0; i < 10; i++)\n  {\n    auto opt = rpdo_queue_->try_pop();\n    if (!opt.has_value())\n    {\n      break;\n    }\n    try\n    {\n      if (rpdo_cb_)\n      {\n        rpdo_cb_(opt.value(), this->lely_driver_->get_id());\n      }\n      on_rpdo(opt.value());\n    }\n    catch (const std::exception & e)\n    {\n      RCLCPP_ERROR_STREAM(this->node_->get_logger(), \"RPDO Poll error: \" << e.what());\n      break;\n    }\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::emcy_listener()\n{\n  RCLCPP_INFO(this->node_->get_logger(), \"Starting EMCY Listener\");\n  auto q = lely_driver_->get_emcy_queue();\n  while (rclcpp::ok())\n  {\n    ros2_canopen::COEmcy emcy;\n    while (!q->wait_and_pop_for(this->non_transmit_timeout_, emcy))\n    {\n      if (!this->activated_.load()) return;\n    }\n    try\n    {\n      if (emcy_cb_)\n      {\n        emcy_cb_(emcy, this->lely_driver_->get_id());\n      }\n      on_emcy(emcy);\n    }\n    catch (const std::exception & e)\n    {\n      RCLCPP_ERROR_STREAM(this->node_->get_logger(), \"EMCY Listener error: \" << e.what());\n      break;\n    }\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBaseDriver<NODETYPE>::diagnostic_callback(\n  diagnostic_updater::DiagnosticStatusWrapper & stat)\n{\n}\n\n#endif\n"
  },
  {
    "path": "canopen_base_driver/include/canopen_base_driver/visibility_control.h",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CANOPEN_BASE_DRIVER__VISIBILITY_CONTROL_H_\n#define CANOPEN_BASE_DRIVER__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_BASE_DRIVER_EXPORT __attribute__((dllexport))\n#define CANOPEN_BASE_DRIVER_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_BASE_DRIVER_EXPORT __declspec(dllexport)\n#define CANOPEN_BASE_DRIVER_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_BASE_DRIVER_BUILDING_LIBRARY\n#define CANOPEN_BASE_DRIVER_PUBLIC CANOPEN_BASE_DRIVER_EXPORT\n#else\n#define CANOPEN_BASE_DRIVER_PUBLIC CANOPEN_BASE_DRIVER_IMPORT\n#endif\n#define CANOPEN_BASE_DRIVER_PUBLIC_TYPE CANOPEN_BASE_DRIVER_PUBLIC\n#define CANOPEN_BASE_DRIVER_LOCAL\n#else\n#define CANOPEN_BASE_DRIVER_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_BASE_DRIVER_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_BASE_DRIVER_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_BASE_DRIVER_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_BASE_DRIVER_PUBLIC\n#define CANOPEN_BASE_DRIVER_LOCAL\n#endif\n#define CANOPEN_BASE_DRIVER_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_BASE_DRIVER__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_base_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_base_driver</name>\n  <version>0.3.2</version>\n  <description>Library containing abstract CANopen driver class for ros2_canopen</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake_ros</buildtool_depend>\n\n  <depend>canopen_core</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>lely_core_libraries</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n  <depend>std_msgs</depend>\n  <depend>std_srvs</depend>\n  <depend>boost</depend>\n  <depend>diagnostic_updater</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_base_driver/src/base_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_base_driver/base_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nBaseDriver::BaseDriver(rclcpp::NodeOptions node_options) : CanopenDriver(node_options)\n{\n  node_canopen_base_driver_ =\n    std::make_shared<node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>>(this);\n  node_canopen_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(\n    node_canopen_base_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::BaseDriver)\n"
  },
  {
    "path": "canopen_base_driver/src/lely_driver_bridge.cpp",
    "content": "//   Copyright 2022 Christoph Hellmann Santos\n//\n//   Licensed under the Apache License, Version 2.0 (the \"License\");\n//   you may not use this file except in compliance with the License.\n//   You may obtain a copy of the License at\n//\n//   http://www.apache.org/licenses/LICENSE-2.0\n//\n//   Unless required by applicable law or agreed to in writing, software\n//   distributed under the License is distributed on an \"AS IS\" BASIS,\n//   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//   See the License for the specific language governing permissions and\n//   limitations under the License.\n//\n#include \"canopen_base_driver/lely_driver_bridge.hpp\"\n#include <bitset>\n#include <memory>\n\nconst ros2_canopen::LelyBridgeErrCategory LelyBridgeErrCategoryInstance{};\n\nstd::error_code std::make_error_code(ros2_canopen::LelyBridgeErrc e)\n{\n  return {static_cast<int>(e), LelyBridgeErrCategoryInstance};\n}\n\nnamespace ros2_canopen\n{\n\nconst char * LelyBridgeErrCategory::name() const noexcept { return \"LelyBridgeError\"; }\n\nstd::string LelyBridgeErrCategory::message(int ev) const\n{\n  switch (static_cast<LelyBridgeErrc>(ev))\n  {\n    case LelyBridgeErrc::NotListedDevice:\n      return \"The CANopen device is not listed in object 1F81.\";\n    case LelyBridgeErrc::NoResponseOnDeviceType:\n      return \"No response received for upload request of object 1000.\";\n    case LelyBridgeErrc::DeviceTypeDifference:\n      return \"Value of object 1000 from CANopen device is different to value in object 1F84 \"\n             \"(Device type).\";\n    case LelyBridgeErrc::VendorIdDifference:\n      return \"Value of object 1018:01 from CANopen device is different to value in object 1F85 \"\n             \"(Vendor-ID).\";\n    case LelyBridgeErrc::HeartbeatIssue:\n      return \"Heartbeat event. No heartbeat message received from CANopen device.\";\n    case LelyBridgeErrc::NodeGuardingIssue:\n      return \"Node guarding event. No confirmation for guarding request received from CANopen \"\n             \"device.\";\n    case LelyBridgeErrc::InconsistentProgramDownload:\n      return \"Objects for program download are not configured or inconsistent.\";\n    case LelyBridgeErrc::SoftwareUpdateRequired:\n      return \"Software update is required, but not allowed because of configuration or current \"\n             \"status.\";\n    case LelyBridgeErrc::SoftwareDownloadFailed:\n      return \"Software update is required, but program download failed.\";\n    case LelyBridgeErrc::ConfigurationDownloadFailed:\n      return \"Configuration download failed.\";\n    case LelyBridgeErrc::StartErrorControlFailed:\n      return \"Heartbeat event during start error control service. No heartbeat message received \"\n             \"from CANopen device during start error control service.\";\n    case LelyBridgeErrc::NmtSlaveInitiallyOperational:\n      return \"NMT slave was initially operational. (CANopen manager may resume operation with \"\n             \"other CANopen devices)\";\n    case LelyBridgeErrc::ProductCodeDifference:\n      return \"Value of object 1018:02 from CANopen device is different to value in object 1F86 \"\n             \"(Product code).\";\n    case LelyBridgeErrc::RevisionCodeDifference:\n      return \"Value of object 1018:03 from CANopen device is different to value in object 1F87 \"\n             \"(Revision number).\";\n    case LelyBridgeErrc::SerialNumberDifference:\n      return \"Value of object 1018:04 from CANopen device is different to value in object 1F88 \"\n             \"(Serial number).\";\n    case LelyBridgeErrc::TimeOut:\n      return \"The boot configure process timeout!\";\n    default:\n      return \"(unrecognized error)\";\n  }\n}\n\nvoid LelyDriverBridge::OnState(canopen::NmtState state) noexcept\n{\n  canopen::NmtState st = state;\n  // We assume 1F80 bit 2 is false. All slaves are put into Operational after boot-up.\n  // Lelycore does not track NMT states in this mode except BOOTUP.\n  if (st == canopen::NmtState::BOOTUP)\n  {\n    st = canopen::NmtState::START;\n  }\n\n  if (!nmt_state_is_set.load())\n  {\n    // We do not care so much about missing a message, rather push them through.\n    std::unique_lock<std::mutex> lk(nmt_mtex, std::defer_lock);\n    if (lk.try_lock())\n    {\n      nmt_state_is_set.store(true);\n      nmt_state_promise.set_value(st);\n    }\n  }\n}\n\nvoid LelyDriverBridge::OnBoot(canopen::NmtState st, char es, const ::std::string & what) noexcept\n{\n  FiberDriver::OnBoot(st, es, what);\n  if (es == 0)\n  {\n    booted.store(true);\n  }\n  std::unique_lock<std::mutex> lck(boot_mtex);\n  this->boot_state = st;\n  this->boot_status = es;\n  this->boot_what = what;\n  boot_cond.notify_all();\n}\n\n// void LelyDriverBridge::OnConfig(::std::function<void(::std::error_code ec)> res) noexcept\n// {\n//   std::cout << \"OnConfig\" << std::endl;\n//   this->SubmitWait(\n//     std::chrono::seconds(10),\n//     [this, res](std::error_code ec)\n//     {\n//       std::cout << \"OnConfig\" << std::endl;\n//       FiberDriver::OnConfig(res);\n//     });\n// }\n\nvoid LelyDriverBridge::OnRpdoWrite(uint16_t idx, uint8_t subidx) noexcept\n{\n  lely::COSub * sub = this->dictionary_->find(idx, subidx);\n  if (sub == nullptr)\n  {\n    std::cout << \"OnRpdoWrite: id=\" << (unsigned int)this->get_id() << \" index=0x\" << std::hex\n              << (unsigned int)idx << \" subindex=\" << (unsigned int)subidx\n              << \" object does not exist\" << std::endl;\n    return;\n  }\n  uint8_t co_def = (uint8_t)sub->getType();\n  uint32_t data = 0;\n  switch (co_def)\n  {\n    case CO_DEFTYPE_BOOLEAN:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_BOOLEAN>((bool)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_BOOLEAN>(), 1);\n      break;\n    }\n    case CO_DEFTYPE_UNSIGNED8:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_UNSIGNED8>((uint8_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_UNSIGNED8>(), 1);\n      break;\n    }\n    case CO_DEFTYPE_INTEGER8:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_INTEGER8>((int8_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_INTEGER8>(), 1);\n      break;\n    }\n    case CO_DEFTYPE_UNSIGNED16:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_UNSIGNED16>((uint16_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_UNSIGNED16>(), 2);\n      break;\n    }\n    case CO_DEFTYPE_INTEGER16:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_INTEGER16>((int16_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_INTEGER16>(), 2);\n      break;\n    }\n    case CO_DEFTYPE_UNSIGNED32:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_UNSIGNED32>((uint32_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_UNSIGNED32>(), 4);\n      break;\n    }\n    case CO_DEFTYPE_INTEGER32:\n    {\n      std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n      sub->setVal<CO_DEFTYPE_INTEGER32>((int32_t)rpdo_mapped[idx][subidx]);\n      std::memcpy(&data, &sub->getVal<CO_DEFTYPE_INTEGER32>(), 4);\n      break;\n    }\n    default:\n      std::cerr << \"Unsupported CO_DEFTYPE: \" << std::hex << (unsigned int)co_def << std::endl;\n      break;\n  }\n  COData codata = {idx, subidx, data};\n\n  //  We do not care so much about missing a message, rather push them through.\n  rpdo_queue->push(codata);\n}\n\nvoid LelyDriverBridge::OnEmcy(uint16_t eec, uint8_t er, uint8_t msef[5]) noexcept\n{\n  FiberDriver::OnEmcy(eec, er, msef);\n\n  COEmcy emcy;\n  emcy.eec = eec;\n  emcy.er = er;\n  for (int i = 0; i < 5; i++) emcy.msef[i] = msef[i];\n\n  emcy_queue->push(emcy);\n}\n\nstd::future<bool> LelyDriverBridge::async_sdo_write(COData data)\n{\n  std::unique_lock<std::mutex> lck(sdo_mutex);\n  if (running)\n  {\n    sdo_cond.wait(lck);\n  }\n  running = true;\n\n  sdo_write_data_promise = std::make_shared<std::promise<bool>>();\n  lely::COSub * sub = this->dictionary_->find(data.index_, data.subindex_);\n  if (sub == nullptr)\n  {\n    std::cout << \"async_sdo_write: id=\" << (unsigned int)this->get_id() << \" index=0x\" << std::hex\n              << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n              << \" object does not exist\" << std::endl;\n    this->sdo_write_data_promise->set_value(false);\n    this->running = false;\n    return sdo_write_data_promise->get_future();\n  }\n  uint8_t co_def = (uint8_t)sub->getType();\n  try\n  {\n    switch (co_def)\n    {\n      case CO_DEFTYPE_BOOLEAN:\n      {\n        this->submit_write<bool>(data);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED8:\n      {\n        this->submit_write<uint8_t>(data);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER8:\n      {\n        this->submit_write<int8_t>(data);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED16:\n      {\n        this->submit_write<uint16_t>(data);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER16:\n      {\n        this->submit_write<int16_t>(data);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED32:\n      {\n        this->submit_write<uint32_t>(data);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER32:\n      {\n        this->submit_write<int32_t>(data);\n        break;\n      }\n      default:\n        std::cerr << \"Unsupported CO_DEFTYPE: \" << std::hex << (unsigned int)co_def << std::endl;\n        break;\n    }\n  }\n  catch (lely::canopen::SdoError & e)\n  {\n    this->sdo_read_data_promise->set_exception(lely::canopen::make_sdo_exception_ptr(\n      this->get_id(), data.index_, data.subindex_, e.code(), \"AsyncUpload\"));\n    this->running = false;\n    this->sdo_cond.notify_one();\n  }\n\n  return sdo_write_data_promise->get_future();\n}\n\nstd::future<COData> LelyDriverBridge::async_sdo_read(COData data)\n{\n  std::unique_lock<std::mutex> lck(sdo_mutex);\n  if (running)\n  {\n    sdo_cond.wait(lck);\n  }\n  running = true;\n\n  sdo_read_data_promise = std::make_shared<std::promise<COData>>();\n  lely::COSub * sub = this->dictionary_->find(data.index_, data.subindex_);\n  if (sub == nullptr)\n  {\n    std::cout << \"async_sdo_read: id=\" << (unsigned int)this->get_id() << \" index=0x\" << std::hex\n              << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n              << \" object does not exist\" << std::endl;\n    try\n    {\n      throw lely::canopen::SdoError(\n        this->get_id(), data.index_, data.subindex_, lely::canopen::SdoErrc::NO_OBJ);\n    }\n    catch (...)\n    {\n      this->sdo_read_data_promise->set_exception(std::current_exception());\n    }\n    this->running = false;\n    return sdo_read_data_promise->get_future();\n  }\n  uint8_t co_def = (uint8_t)sub->getType();\n  try\n  {\n    if (co_def == CO_DEFTYPE_BOOLEAN)\n    {\n      this->submit_read<bool>(data);\n    }\n    if (co_def == CO_DEFTYPE_UNSIGNED8)\n    {\n      this->submit_read<uint8_t>(data);\n    }\n    if (co_def == CO_DEFTYPE_INTEGER8)\n    {\n      this->submit_read<int8_t>(data);\n    }\n    if (co_def == CO_DEFTYPE_UNSIGNED16)\n    {\n      this->submit_read<uint16_t>(data);\n    }\n    if (co_def == CO_DEFTYPE_INTEGER16)\n    {\n      this->submit_read<int16_t>(data);\n    }\n    if (co_def == CO_DEFTYPE_UNSIGNED32)\n    {\n      this->submit_read<uint32_t>(data);\n    }\n    if (co_def == CO_DEFTYPE_INTEGER32)\n    {\n      this->submit_read<int32_t>(data);\n    }\n  }\n  catch (lely::canopen::SdoError & e)\n  {\n    this->sdo_read_data_promise->set_exception(lely::canopen::make_sdo_exception_ptr(\n      this->get_id(), data.index_, data.subindex_, e.code(), \"AsyncUpload\"));\n    this->running = false;\n    this->sdo_cond.notify_one();\n  }\n  return sdo_read_data_promise->get_future();\n}\n\nstd::future<canopen::NmtState> LelyDriverBridge::async_request_nmt()\n{\n  std::scoped_lock<std::mutex> lk(nmt_mtex);\n  nmt_state_is_set.store(false);\n  nmt_state_promise = std::promise<canopen::NmtState>();\n  return nmt_state_promise.get_future();\n}\n\nstd::shared_ptr<SafeQueue<COData>> LelyDriverBridge::get_rpdo_queue() { return rpdo_queue; }\n\nstd::shared_ptr<SafeQueue<COEmcy>> LelyDriverBridge::get_emcy_queue() { return emcy_queue; }\n\nvoid LelyDriverBridge::tpdo_transmit(COData data)\n{\n  lely::COSub * sub = this->dictionary_->find(data.index_, data.subindex_);\n  if (sub == nullptr)\n  {\n    std::cout << \"async_pdo_write: id=\" << (unsigned int)get_id() << \" index=0x\" << std::hex\n              << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n              << \" object does not exist\" << std::endl;\n    return;\n  }\n  uint8_t co_def = (uint8_t)sub->getType();\n  try\n  {\n    switch (co_def)\n    {\n      case CO_DEFTYPE_BOOLEAN:\n      {\n        bool val;\n        std::memcpy(&val, &data.data_, sizeof(bool));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_BOOLEAN>(val);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED8:\n      {\n        uint8_t val;\n        std::memcpy(&val, &data.data_, sizeof(uint8_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_UNSIGNED8>(val);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER8:\n      {\n        int8_t val;\n        std::memcpy(&val, &data.data_, sizeof(int8_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_INTEGER8>(val);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED16:\n      {\n        uint16_t val;\n        std::memcpy(&val, &data.data_, sizeof(uint16_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_UNSIGNED16>(val);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER16:\n      {\n        int16_t val;\n        std::memcpy(&val, &data.data_, sizeof(int16_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_INTEGER16>(val);\n        break;\n      }\n      case CO_DEFTYPE_UNSIGNED32:\n      {\n        uint32_t val;\n        std::memcpy(&val, &data.data_, sizeof(uint32_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_UNSIGNED32>(val);\n        break;\n      }\n      case CO_DEFTYPE_INTEGER32:\n      {\n        int32_t val;\n        std::memcpy(&val, &data.data_, sizeof(int32_t));\n        tpdo_mapped[data.index_][data.subindex_] = val;\n        std::scoped_lock<std::mutex> lck(this->dictionary_mutex_);\n        sub->setVal<CO_DEFTYPE_INTEGER32>(val);\n        break;\n      }\n      default:\n        std::cout << \"async_pdo_write: id=\" << (unsigned int)get_id() << \" index=0x\" << std::hex\n                  << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n                  << \" type=\" << std::hex << (unsigned int)co_def\n                  << \" data:\" << (uint32_t)data.data_\n                  << \"TYPE NOT IMPLEMENTED - DATA WILL NOT BE WRTITTEN!!\" << std::endl;\n        break;\n    }\n    tpdo_mapped[data.index_][data.subindex_].WriteEvent();\n    // Reduce the amount of output - this is not needed as it is on every write\n    // std::cout << \"async_pdo_write: id=\" << (unsigned int)get_id() << \" index=0x\" << std::hex\n    //           << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n    //           << \" type=\" << std::hex << (unsigned int)co_def << \" data:\" << (uint32_t)data.data_\n    //           << std::endl;\n  }\n  catch (lely::canopen::SdoError & e)\n  {\n    std::cout << \"async_pdo_write: id=\" << (unsigned int)get_id() << \" index=0x\" << std::hex\n              << (unsigned int)data.index_ << \" subindex=\" << (unsigned int)data.subindex_\n              << \" type=\" << std::hex << (unsigned int)co_def << e.what() << std::endl;\n    return;\n  }\n}\n\nvoid LelyDriverBridge::nmt_command(canopen::NmtCommand command)\n{\n  this->master.Command(command, nodeid);\n}\n\nuint8_t LelyDriverBridge::get_id() { return nodeid; }\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_base_driver/src/lifecycle_base_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#include \"canopen_base_driver/lifecycle_base_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nLifecycleBaseDriver::LifecycleBaseDriver(rclcpp::NodeOptions node_options)\n: LifecycleCanopenDriver(node_options)\n{\n  node_canopen_base_driver_ =\n    std::make_shared<node_interfaces::NodeCanopenBaseDriver<rclcpp_lifecycle::LifecycleNode>>(this);\n  node_canopen_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(\n    node_canopen_base_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleBaseDriver)\n"
  },
  {
    "path": "canopen_base_driver/src/node_interfaces/node_canopen_base_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver_impl.hpp\"\n#include \"canopen_core/driver_error.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopenBaseDriver<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopenBaseDriver<\n  rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_base_driver/test/CMakeLists.txt",
    "content": "ament_add_gtest(test_node_canopen_base_driver_ros\ntest_node_canopen_base_driver_ros.cpp\n)\ntarget_include_directories(test_node_canopen_base_driver_ros PUBLIC\n  ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_canopen_base_driver_ros\n  ${canopen_interfaces_TARGETS}\n  ${std_msgs_TARGETS}\n  ${std_srvs_TARGETS}\n  Boost::thread\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  diagnostic_updater::diagnostic_updater\n  node_canopen_base_driver\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n\n\n\nament_add_gtest(test_base_driver_component\ntest_base_driver_component.cpp\n)\ntarget_include_directories(test_base_driver_component PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_base_driver_component\n  ${canopen_interfaces_TARGETS}\n  ${std_msgs_TARGETS}\n  ${std_srvs_TARGETS}\n  Boost::thread\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  diagnostic_updater::diagnostic_updater\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n\nfile(COPY ${CMAKE_CURRENT_SOURCE_DIR}/master.dcf DESTINATION ${CMAKE_CURRENT_BINARY_DIR})\n"
  },
  {
    "path": "canopen_base_driver/test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=2\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=32\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1A00\n20=0x1A01\n21=0x1F25\n22=0x1F55\n23=0x1F80\n24=0x1F81\n25=0x1F82\n26=0x1F84\n27=0x1F85\n28=0x1F86\n29=0x1F87\n30=0x1F88\n31=0x1F89\n32=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=12\n1=0x2000\n2=0x2001\n3=0x2200\n4=0x2201\n5=0x5800\n6=0x5801\n7=0x5A00\n8=0x5A01\n9=0x5C00\n10=0x5C01\n11=0x5E00\n12=0x5E01\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=2\n2=0x00000082\n3=0x00000083\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=2\n2=0x00000005\n3=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=2\n2=0x00000360\n3=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=proxy_device_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=proxy_device_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=proxy_device_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=proxy_device_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_base_driver/test/test_base_driver_component.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <rclcpp_components/component_manager.hpp>\n#include <rclcpp_components/node_factory.hpp>\n#include <rclcpp_components/node_instance_wrapper.hpp>\n#include <thread>\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"gtest/gtest.h\"\nusing namespace rclcpp_components;\n\nTEST(ComponentLoad, test_load_component_1)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_base_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[0]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n\nTEST(ComponentLoad, test_load_component_2)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_base_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[1]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_base_driver/test/test_node_canopen_base_driver_ros.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <thread>\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"gtest/gtest.h\"\n\nTEST(NodeCanopenBaseDriver, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp::Node * node = new rclcpp::Node(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenBaseDriver(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\n    \"config\",\n    \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage: \\\"canopen_core\\\"\\ndcf: \"\n    \"\\\"simple.eds\\\"\\ndcf_path: \\\"\\\"\\n\");\n  node->set_parameter(container_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  // Can't activate as master cannot be set.\n  EXPECT_ANY_THROW(iface->activate());\n  iface->shutdown();\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n\nTEST(NodeCanopenBasicLifecycleMaster, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp_lifecycle::LifecycleNode * node = new rclcpp_lifecycle::LifecycleNode(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenBaseDriver(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\n    \"config\",\n    \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage: \\\"canopen_core\\\"\\ndcf: \"\n    \"\\\"simple.eds\\\"\\ndcf_path: \\\"\\\"\\n\");\n  node->set_parameter(container_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  // Can't activate as master cannot be set.\n  EXPECT_ANY_THROW(iface->activate());\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n"
  },
  {
    "path": "canopen_core/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_core\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.2.9 (2024-04-16)\n------------------\n* Add timeouts\n* Contributors: Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.3.2 (2025-12-05)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n* Add namespacing support\n* Contributors: Christoph Hellmann Santos, Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* Merge pull request `#270 <https://github.com/ros-industrial/ros2_canopen/issues/270>`_ from gsalinas/can-namespace-pr\n  Put components loaded by the device container into its namespace, if any.\n* pre-commit update\n* Put components loaded by the device container into its namespace, if any.\n* Merge pull request `#280 <https://github.com/ros-industrial/ros2_canopen/issues/280>`_ from ipa-vsp/fix/yaml-build-error\n  Fix undefined reference to yaml library\n* fix undefined reference to yaml\n* Fix logging in device_container.cpp (`#277 <https://github.com/ros-industrial/ros2_canopen/issues/277>`_)\n* 0.2.9\n* forthcoming\n* Merge pull request `#220 <https://github.com/ros-industrial/ros2_canopen/issues/220>`_ from ipa-vsp/feature/timeout-config\n  Add timeouts\n* change from 100ms to 2000ms\n* non transmit time from bus.yml\n* timeout for booting slave\n* Contributors: Christoph Hellmann Santos, Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix maintainer naming\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix master and driver lifecycle\n* Fix QoS build warning in canopen_core\n* Use consistenlty HEX output for NodeID and Index.\n* Contributors: Christoph Hellmann Santos, Denis Štogl, Vishnuprasad Prachandabhanu\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Aulon Bajrami, Borong Yuan, Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Lovro, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_core/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5)\nproject(canopen_core)\n\n# Default to C99\nif(NOT CMAKE_C_STANDARD)\n  set(CMAKE_C_STANDARD 99)\nendif()\n\n# Default to C++17\nif(NOT CMAKE_CXX_STANDARD)\n  set(CMAKE_CXX_STANDARD 17)\nendif()\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\nendif()\n\nset(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -pthread\")\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(lely_core_libraries REQUIRED)\nfind_package(lifecycle_msgs REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\nfind_package(yaml_cpp_vendor REQUIRED)\ninclude(ConfigExtras.cmake)\n\nadd_library(node_canopen_driver\n  SHARED\n  src/node_interfaces/node_canopen_driver.cpp\n  src/driver_error.cpp\n  src/driver_node.cpp\n)\ntarget_compile_features(node_canopen_driver  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_driver PUBLIC -fPIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(node_canopen_driver PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${lely_core_libraries_LIBRARIES}\n  rclcpp::rclcpp\n  rclcpp_lifecycle::rclcpp_lifecycle\n  yaml-cpp\n)\n\nadd_library(node_canopen_master\n  SHARED\n  src/node_interfaces/node_canopen_master.cpp\n  src/master_error.cpp\n  src/master_node.cpp\n)\ntarget_compile_features(node_canopen_master  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_master PUBLIC -fPIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_master PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(node_canopen_master PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${lely_core_libraries_LIBRARIES}\n  rclcpp::rclcpp\n  rclcpp_lifecycle::rclcpp_lifecycle\n  yaml-cpp\n)\n\n\nadd_library(device_container\n  SHARED\n  src/device_container.cpp\n  src/configuration_manager.cpp\n  src/device_container_error.cpp\n  src/lifecycle_manager.cpp\n)\ntarget_compile_features(device_container  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(device_container PUBLIC -fPIC -Wl,--no-undefined)\ntarget_include_directories(device_container PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n)\ntarget_link_libraries(device_container PUBLIC\n  ${canopen_interfaces_TARGETS}\n  node_canopen_driver\n  node_canopen_master\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n  yaml-cpp\n)\n\nadd_executable(device_container_node\n  src/device_container_node.cpp\n)\ntarget_link_libraries(device_container_node PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${lifecycle_msgs_TARGETS}\n  device_container\n  node_canopen_driver\n  node_canopen_master\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\ntarget_include_directories(device_container_node PUBLIC\n  \"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\"\n  \"$<INSTALL_INTERFACE:include>\"\n  ${rclcpp_INCLUDE_DIRS}\n)\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\ninstall(\n  DIRECTORY launch/\n  DESTINATION share/${PROJECT_NAME}/launch/\n)\n\ninstall(\n  TARGETS node_canopen_driver node_canopen_master device_container\n  EXPORT export_${PROJECT_NAME}\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  RUNTIME DESTINATION bin\n)\n\n\n\ninstall(TARGETS device_container_node\n  DESTINATION lib/${PROJECT_NAME}\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_gtest REQUIRED)\n  find_package(ament_cmake_gmock REQUIRED)\n  add_subdirectory(test)\nendif()\n\nament_export_include_directories(\n  include\n)\n\nament_export_libraries(\n  node_canopen_driver\n  node_canopen_master\n)\n\nament_export_targets(\n  export_${PROJECT_NAME}\n)\n\nament_export_dependencies(\n  Boost\n  canopen_interfaces\n  lely_core_libraries\n  lifecycle_msgs\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n  yaml_cpp_vendor\n)\n\n# https://github.com/ament/ament_cmake/blob/e78ed7e084489c2a48cb91dec9da92c13e9653c9/ament_cmake_core/cmake/core/ament_package.cmake#L24-L32\nament_package(CONFIG_EXTRAS ConfigExtras.cmake)\n"
  },
  {
    "path": "canopen_core/ConfigExtras.cmake",
    "content": "#   Copyright (c) 2023 Vishnuprasad Prachandabhanu\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n#\nfind_package(Boost REQUIRED system thread)\n"
  },
  {
    "path": "canopen_core/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_core/include/canopen_core/configuration_manager.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CONFIGURATION_MANAGER_HPP\n#define CONFIGURATION_MANAGER_HPP\n\n#include <iostream>\n#include <map>\n#include <optional>\n#include <rclcpp/rclcpp.hpp>\n#include <string>\n#include <vector>\n#include \"yaml-cpp/yaml.h\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Manager for Bus Configuration.\n *\n * The Bus configuration Manager stores the YAML bus configuration and\n * enables reading configuration entries. The configuration manager is passed\n * to all ros2_canopen master and slave drivers to enable reading driver specific\n * configuration parameters from the YAML configuration file.\n *\n */\nclass ConfigurationManager\n{\nprivate:\n  std::string file_;                           ///< Stores the configuration file name\n  YAML::Node root_;                            ///< Stores YAML root node\n  std::map<std::string, YAML::Node> devices_;  ///< Stores all configuration per device\n\npublic:\n  ConfigurationManager(std::string & file) : file_(file) { root_ = YAML::LoadFile(file_.c_str()); }\n\n  /**\n   * @brief Gets a configuration entry for a specific device\n   *\n   * @tparam T                Datatype of the retrieved object\n   * @param device_name       Device name\n   * @param entry_name        Entry name\n   * @return std::optional<T> Return value, can be empty.\n   */\n  template <typename T>\n  std::optional<T> get_entry(std::string device_name, std::string entry_name)\n  {\n    try\n    {\n      auto config = devices_.at(device_name);\n      return std::optional<T>(config[entry_name.c_str()].as<T>());\n    }\n    catch (const std::exception & e)\n    {\n      RCLCPP_INFO(\n        rclcpp::get_logger(\"yaml-cpp\"), \"Failed to load entry \\\"%s\\\" for device \\\"%s\\\" \",\n        entry_name.c_str(), device_name.c_str());\n    }\n\n    return std::nullopt;\n  }\n\n  /**\n   * @brief Dump device string\n   *\n   * @param device_name\n   * @return std::string\n   */\n  std::string dump_device(std::string device_name)\n  {\n    std::string result;\n    try\n    {\n      auto config = devices_.at(device_name);\n      result = YAML::Dump(config);\n    }\n    catch (const std::exception & e)\n    {\n      std::cerr << e.what() << '\\n';\n    }\n    return result;\n  }\n\n  /**\n   * @brief Initialises the configuration.\n   *\n   */\n  void init_config();\n\n  /**\n   * @brief Returns all device names\n   *\n   * @param devices           List with names of all devices\n   * @return uint32_t         Number of devices discovered\n   */\n  uint32_t get_all_devices(std::vector<std::string> & devices);\n};\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/device_container.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef LIFECYCLE_DEVICE_CONTAINER_NODE_HPP\n#define LIFECYCLE_DEVICE_CONTAINER_NODE_HPP\n\n#include <chrono>\n#include <memory>\n#include <rclcpp/executors.hpp>\n#include <rclcpp_components/component_manager.hpp>\n#include <vector>\n#include \"canopen_core/configuration_manager.hpp\"\n#include \"canopen_core/driver_node.hpp\"\n#include \"canopen_core/lifecycle_manager.hpp\"\n#include \"canopen_core/master_node.hpp\"\n#include \"canopen_interfaces/srv/co_node.hpp\"\n#include \"rcl_interfaces/srv/set_parameters.hpp\"\n\nusing namespace std::chrono_literals;\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle Device Container for CANopen\n *\n * This class provides the functionality for loading a\n * the CANopen Master and CANopen Device Drivers based on the\n * Configuration Files. Configuration files need to be passed in\n * as parameters.\n *\n */\nclass DeviceContainer : public rclcpp_components::ComponentManager\n{\npublic:\n  /**\n   * @brief Construct a new Lifecycle Device Container Node object\n   *\n   * @param [in] executor     The executor to add loaded master and devices to.\n   * @param [in] node_name    The name of the node\n   * @param [in] node_options Passed to the device_container node\n   */\n  DeviceContainer(\n    std::weak_ptr<rclcpp::Executor> executor =\n      std::weak_ptr<rclcpp::executors::MultiThreadedExecutor>(),\n    std::string node_name = \"device_container\",\n    const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp_components::ComponentManager(executor, node_name, node_options)\n  {\n    executor_ = executor;\n    this->declare_parameter<std::string>(\"can_interface_name\", \"\");\n    this->declare_parameter<std::string>(\"master_config\", \"\");\n    this->declare_parameter<std::string>(\"bus_config\", \"\");\n    this->declare_parameter<std::string>(\"master_bin\", \"\");\n    client_cbg_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n    init_driver_service_ = this->create_service<canopen_interfaces::srv::CONode>(\n      \"~/init_driver\",\n      std::bind(\n        &DeviceContainer::on_init_driver, this, std::placeholders::_1, std::placeholders::_2),\n      rclcpp::QoS(10), client_cbg_);\n\n    this->loadNode_srv_.reset();\n    this->unloadNode_srv_.reset();\n    lifecycle_operation_ = false;\n  }\n\n  ~DeviceContainer() override { shutdown(); }\n\n  /**\n   * @brief Executes the initialisation\n   *\n   * This will read nodes parameters and initialize\n   * the configuration defined in the parameters. It\n   * will also start loading the components.\n   *\n   * @return true\n   * @return false\n   */\n  void init();\n\n  /**\n   * @brief Executes the initialisation\n   *\n   * Same as init() only that ros parameters are not used.\n   *\n   * @param can_interface_name\n   * @param master_config\n   * @param bus_config\n   * @param master_bin\n   */\n  void init(\n    const std::string & can_interface_name, const std::string & master_config,\n    const std::string & bus_config, const std::string & master_bin = \"\");\n\n  virtual void configure();\n  /**\n   * @brief Loads drivers from configuration\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool load_drivers();\n  /**\n   * @brief Loads master from configuration\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool load_master();\n  /**\n   * @brief Loads the device manager\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool load_manager();\n\n  /**\n   * @brief Load a component\n   *\n   * @param [in] package_name     Name of the package\n   * @param [in] driver_name      Name of the driver class to load\n   * @param [in] node_id          CANopen node id of the target device\n   * @param [in] node_name        Node name of the ROS node\n   * @return true\n   * @return false\n   */\n  virtual bool load_component(\n    const std::string package_name, const std::string driver_name, const uint16_t node_id,\n    const std::string node_name, std::vector<rclcpp::Parameter> & params,\n    const std::string node_namespace = \"\");\n\n  /**\n   * @brief Shutdown all devices.\n   *\n   * This function will shutdown all devices that were created.\n   * The function calls the shutdown function of each created\n   * device.\n   *\n   */\n  virtual void shutdown()\n  {\n    for (auto it = registered_drivers_.begin(); it != registered_drivers_.end(); ++it)\n    {\n      try\n      {\n        it->second->shutdown();\n      }\n      catch (const std::exception & e)\n      {\n        std::cerr << e.what() << '\\n';\n      }\n    }\n    try\n    {\n      can_master_->shutdown();\n    }\n    catch (const std::exception & e)\n    {\n      std::cerr << e.what() << '\\n';\n    }\n  }\n  /**\n   * @brief Callback for the listing service\n   *\n   * @param request_header\n   * @param request\n   * @param response\n   */\n  virtual void on_list_nodes(\n    const std::shared_ptr<rmw_request_id_t> request_header,\n    const std::shared_ptr<ListNodes::Request> request,\n    std::shared_ptr<ListNodes::Response> response) override;\n\n  /**\n   * @brief Get the registered drivers object\n   *\n   * This function will return a map of all driver objects that were created.\n   * The returned map can be queried by node id.\n   *\n   * @return std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>>\n   */\n  virtual std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>> get_registered_drivers()\n  {\n    return registered_drivers_;\n  }\n\n  /**\n   * @brief Get the number of registered drivers\n   *\n   * @return size_t\n   */\n  virtual size_t count_drivers() { return registered_drivers_.size(); }\n\n  /**\n   * @brief Get node ids of all drivers with type\n   *\n   * This function gets the ids of all drivers that have the passed\n   * in type. The type must be the fully qualified class name of the\n   * driver as string.\n   *\n   * @param [in] type\n   * @return std::vector<uint16_t>\n   */\n  std::vector<uint16_t> get_ids_of_drivers_with_type(std::string type)\n  {\n    std::vector<std::string> devices;\n    std::vector<uint16_t> ids;\n    uint32_t count = this->config_->get_all_devices(devices);\n    if (count == 0)\n    {\n      return ids;\n    }\n\n    for (auto it = devices.begin(); it != devices.end(); it++)\n    {\n      auto driver_name = config_->get_entry<std::string>(*it, \"driver\");\n      if (driver_name.has_value())\n      {\n        std::string name = driver_name.value();\n        if (name.compare(type) == 0)\n        {\n          auto node_id = config_->get_entry<uint16_t>(*it, \"node_id\");\n          ids.push_back(node_id.value());\n        }\n      }\n    }\n    return ids;\n  }\n  /**\n   * @brief Get the type of driver by node id\n   *\n   * This function will return the type of the driver that is registered\n   * for the passed node ids.\n   *\n   * @param [in] id\n   * @return std::string\n   */\n  std::string get_driver_type(uint16_t id)\n  {\n    std::vector<std::string> devices;\n    uint32_t count = this->config_->get_all_devices(devices);\n    if (count == 0)\n    {\n      return \"\";\n    }\n    for (auto it = devices.begin(); it != devices.end(); it++)\n    {\n      auto node_id = config_->get_entry<uint16_t>(*it, \"node_id\");\n      if (node_id.has_value() && node_id.value() == id)\n      {\n        auto driver_name = config_->get_entry<std::string>(*it, \"driver\");\n        return driver_name.value();\n      }\n    }\n  }\n\nprotected:\n  // Components\n  std::map<uint16_t, std::shared_ptr<CanopenDriverInterface>>\n    registered_drivers_;  ///< Map of drivers registered in busconfiguration. Name is key.\n  std::shared_ptr<ros2_canopen::CanopenMasterInterface>\n    can_master_;  ///< Pointer to can master instance\n  uint16_t can_master_id_;\n  std::unique_ptr<ros2_canopen::LifecycleManager> lifecycle_manager_;\n\n  // Configuration\n  std::shared_ptr<ros2_canopen::ConfigurationManager>\n    config_;                        ///< Pointer to configuration manager instance\n  std::string dcf_txt_;             ///< Cached value of .dcf file parameter\n  std::string bus_config_;          ///< Cached value of bus.yml file parameter\n  std::string dcf_bin_;             ///< Cached value of .bin file parameter\n  std::string can_interface_name_;  ///< Cached value of can interface name\n  bool lifecycle_operation_;\n\n  // ROS Objects\n  std::weak_ptr<rclcpp::Executor> executor_;  ///< Pointer to ros executor instance\n  rclcpp::Service<canopen_interfaces::srv::CONode>::SharedPtr\n    init_driver_service_;                        ///< Service object for init_driver service\n  rclcpp::CallbackGroup::SharedPtr client_cbg_;  ///< Callback group for services\n\n  /**\n   * @brief Set the ROS executor object\n   *\n   * @param [in] executor     Pointer to the Executor\n   */\n  void set_executor(const std::weak_ptr<rclcpp::Executor> executor);\n\n  /**\n   * @brief Initialises a driver\n   *\n   * This function needs to be called before a driver can be added\n   * to the CANopen Master Event Loop. It sets the master and executor,\n   * the driver will be added to.\n   *\n   * @param node_id       CANopen node id of the target device\n   *\n   * @return true\n   * @return false\n   */\n  bool init_driver(uint16_t node_id);\n\n  /**\n   * @brief Callback for init driver service\n   *\n   * @param request\n   * @param response\n   */\n  void on_init_driver(\n    const canopen_interfaces::srv::CONode::Request::SharedPtr request,\n    canopen_interfaces::srv::CONode::Response::SharedPtr response)\n  {\n    response->success = init_driver(request->nodeid);\n  }\n\n  /**\n   * @brief Returns a list of components\n   *\n   * @return std::map<uint16_t, std::string>\n   */\n  std::map<uint16_t, std::string> list_components();\n\n  /**\n   * @brief Add node to executor\n   *\n   * @param [in] node_interface  NodeBaseInterface of the node that should be added to the executor.\n   */\n  virtual void add_node_to_executor(\n    rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_interface)\n  {\n    if (auto exec = executor_.lock())\n    {\n      RCLCPP_INFO(\n        this->get_logger(), \"Added %s to executor\", node_interface->get_fully_qualified_name());\n      exec->add_node(node_interface, true);\n    }\n    else\n    {\n      RCLCPP_ERROR(\n        this->get_logger(), \"Failed to add component %s\",\n        node_interface->get_fully_qualified_name());\n    }\n  }\n};\n\n}  // namespace ros2_canopen\n#endif  // LIFECYCLE_DEVICE_CONTAINER_NODE_HPP\n"
  },
  {
    "path": "canopen_core/include/canopen_core/device_container_error.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef DEVICE_CONTAINER_ERROR_HPP_\n#define DEVICE_CONTAINER_ERROR_HPP_\n\n#include <string>\n#include <system_error>\n\nnamespace ros2_canopen\n{\n\n/**\n * @brief Device Container Exception\n *\n * This exception is used, when the device container\n * fails.\n *\n */\nclass DeviceContainerException : public std::exception\n{\nprivate:\n  std::string what_;\n\npublic:\n  DeviceContainerException(std::string what) { what_ = what; }\n\n  char * what();\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/driver_error.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef DRIVER_ERROR_HPP_\n#define DRIVER_ERROR_HPP_\n\n#include <string>\n#include <system_error>\n\nnamespace ros2_canopen\n{\n/**\n * @brief Driver Exception\n *\n * This exception is used, when a driver\n * fails.\n *\n */\nclass DriverException : public std::exception\n{\nprivate:\n  std::string what_;\n\npublic:\n  DriverException(std::string what) { what_ = what; }\n\n  char * what();\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/driver_node.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef DRIVER_NODE_HPP_\n#define DRIVER_NODE_HPP_\n\n#include <rclcpp/rclcpp.hpp>\n#include \"canopen_core/node_interfaces/node_canopen_driver.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Canopen Driver Interface\n *\n * This provides an interface that all driver nodes that are loaded\n * by ros2_canopen::DeviceContainer need to implement.\n *\n */\nclass CanopenDriverInterface\n{\npublic:\n  /**\n   * @brief Initialise the driver\n   *\n   * This function will initialise the drivers functionalities.\n   * It will be called by the device_container when the node has\n   * been added to the executor.\n   */\n  virtual void init() = 0;\n\n  /**\n   * @brief Set the master object\n   *\n   * This function will set the Canopen Master Objects that are\n   * necessary for the driver to be instantiated. It will be called\n   * by the device container when the init_driver service is invoked.\n   *\n   * @param exec\n   * @param master\n   */\n  virtual void set_master(\n    std::shared_ptr<lely::ev::Executor> exec,\n    std::shared_ptr<lely::canopen::AsyncMaster> master) = 0;\n\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function shall return an rclcpp::node_interfaces::NodeBaseInterface::SharedPtr.\n   * The pointer will be used to add the driver node to the executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() = 0;\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function will shutdown the driver and will especially\n   * join all threads to enable a clean shutdown.\n   *\n   */\n  virtual void shutdown() = 0;\n\n  /**\n   * @brief Check whether this is a LifecycleNode\n   *\n   * This function provides runtime information on whether the driver\n   * is a lifecycle driver or not.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool is_lifecycle() = 0;\n\n  /**\n   * @brief Get the node canopen driver interface object\n   *\n   * This function gives access to the underlying NodeCanopenDriverInterface.\n   *\n   * @return std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n   */\n  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n  get_node_canopen_driver_interface() = 0;\n};\n\n/**\n * @brief Canopen Driver\n *\n * This provides a class, that driver nodes that are based on rclcpp::Node\n * should be derived of. This class implements the ros2_canopen::CanopenDriverInterface.\n *\n */\nclass CanopenDriver : public CanopenDriverInterface, public rclcpp::Node\n{\npublic:\n  std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_;\n  explicit CanopenDriver(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp::Node(\"canopen_driver\", node_options)\n  {\n    node_canopen_driver_ = std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp::Node>>(this);\n  }\n\n  /**\n   * @brief Initialise the driver\n   *\n   * This function will activate the driver using the instantiated\n   * node_canopen_driver_. It will call the init, configure, demand_set_master and activate\n   * of the NodeCanopenDriverInterface. If the function finishes without exception,\n   * the driver is activated and ready for use.\n   *\n   */\n  virtual void init() override;\n\n  /**\n   * @brief Set the master object\n   *\n   * This function will set the Canopen Master Objects that are\n   * necessary for the driver to be instantiated. It will be called\n   * by the device container when the init_driver service is invoked.\n   *\n   * @param exec\n   * @param master\n   */\n  virtual void set_master(\n    std::shared_ptr<lely::ev::Executor> exec,\n    std::shared_ptr<lely::canopen::AsyncMaster> master) override;\n\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function shall return an rclcpp::node_interfaces::NodeBaseInterface::SharedPtr.\n   * The pointer will be used to add the driver node to the executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override\n  {\n    return rclcpp::Node::get_node_base_interface();\n  }\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function will shutdown the driver by calling the\n   * shutdown() function of node_canopen_driver_.\n   *\n   */\n  virtual void shutdown() override;\n\n  /**\n   * @brief Check whether this is a LifecycleNode\n   *\n   * @return false\n   */\n  virtual bool is_lifecycle() override { return false; }\n\n  /**\n   * @brief Get the node canopen driver interface object\n   *\n   * This function gives access to the underlying NodeCanopenDriverInterface.\n   *\n   * @return std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n   */\n  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n  get_node_canopen_driver_interface()\n  {\n    return node_canopen_driver_;\n  }\n};\n\n/**\n * @brief Lifecycle Canopen Driver\n *\n * This provides a class, that driver nodes that are based on rclcpp_lifecycle::LifecycleNode\n * should be derived of. This class implements the ros2_canopen::CanopenDriverInterface.\n *\n */\nclass LifecycleCanopenDriver : public CanopenDriverInterface, public rclcpp_lifecycle::LifecycleNode\n{\nprotected:\n  std::shared_ptr<node_interfaces::NodeCanopenDriverInterface> node_canopen_driver_;\n\npublic:\n  explicit LifecycleCanopenDriver(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp_lifecycle::LifecycleNode(\"lifecycle_canopen_driver\", node_options)\n  {\n    node_canopen_driver_ =\n      std::make_shared<node_interfaces::NodeCanopenDriver<rclcpp_lifecycle::LifecycleNode>>(this);\n  }\n  /**\n   * @brief Initialise the driver\n   *\n   * This function will activate the driver using the instantiated\n   * node_canopen_driver_. It will call init()\n   * of the NodeCanopenDriverInterface. If the function finishes without exception,\n   * the driver can be configured.\n   *\n   */\n  virtual void init() override;\n\n  /**\n   * @brief Set the master object\n   *\n   * This function will set the Canopen Master Objects that are\n   * necessary for the driver to be instantiated. It will be called\n   * by the device container when the init_driver service is invoked.\n   *\n   * @param exec\n   * @param master\n   */\n  virtual void set_master(\n    std::shared_ptr<lely::ev::Executor> exec,\n    std::shared_ptr<lely::canopen::AsyncMaster> master) override;\n\n  /**\n   * @brief Configure Callback\n   *\n   * This function will call configure() and demand_set_master() of the\n   * node_canopen_driver_.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Activate Callback\n   *\n   * This function will call activate() of the\n   * node_canopen_driver_.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Deactivate Callback\n   *\n   * This function will call deactivate() of the\n   * node_canopen_driver_.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Deactivate Callback\n   *\n   * This function will call cleanup() of the\n   * node_canopen_driver_.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Deactivate Callback\n   *\n   * This function will call shutdown() of the\n   * node_canopen_driver_.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function shall return an rclcpp::node_interfaces::NodeBaseInterface::SharedPtr.\n   * The pointer will be used to add the driver node to the executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override\n  {\n    return rclcpp_lifecycle::LifecycleNode::get_node_base_interface();\n  }\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function will shutdown the driver by calling the\n   * shutdown() function of node_canopen_driver_.\n   *\n   */\n  virtual void shutdown() override;\n  /**\n   * @brief Check whether this is a LifecycleNode\n   *\n   * @return true\n   */\n  virtual bool is_lifecycle() override { return true; }\n  /**\n   * @brief Get the node canopen driver interface object\n   *\n   * This function gives access to the underlying NodeCanopenDriverInterface.\n   *\n   * @return std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n   */\n  virtual std::shared_ptr<node_interfaces::NodeCanopenDriverInterface>\n  get_node_canopen_driver_interface()\n  {\n    return node_canopen_driver_;\n  }\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/exchange.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef EXCHANGE_HPP\n#define EXCHANGE_HPP\n\n#include <boost/lockfree/queue.hpp>\n#include <boost/optional.hpp>\n#include <boost/thread.hpp>\n\nnamespace ros2_canopen\n{\n\nstruct COData\n{\npublic:\n  uint16_t index_;\n  uint8_t subindex_;\n  uint32_t data_;\n};\n\nstruct COEmcy\n{\npublic:\n  uint16_t eec;\n  uint8_t er;\n  uint8_t msef[5];\n};\n\n/**\n * @brief Thread Safe Queue for CANOpen Data Exchange\n * @tparam T Type of the data to be exchanged\n * @details This class is a wrapper around boost::lockfree::queue to provide thread safe data\n * exchange between threads using the queue.\n */\ntemplate <typename T>\nclass SafeQueue\n{\nprivate:\n  std::size_t capacity_;\n  std::unique_ptr<boost::lockfree::queue<T>> queue_;\n\npublic:\n  /**\n   * @brief Constructor for the SafeQueue\n   * @param capacity Capacity of the queue\n   */\n  explicit SafeQueue(std::size_t capacity = 10)\n  : capacity_(capacity), queue_(new boost::lockfree::queue<T>(capacity_))\n  {\n  }\n\n  /**\n   * @brief Push a value to the queue\n   * @param value Value to be pushed\n   */\n  void push(T value) { queue_->push(std::move(value)); }\n\n  /**\n   * @brief Try to pop a value from the queue\n   * @return Value if available, boost::none otherwise\n   */\n  std::optional<T> try_pop()\n  {\n    T value;\n    if (queue_->pop(value)) return std::optional<T>(std::move(value));\n    return std::optional<T>();\n  }\n\n  /**\n   * @brief Try to pop a value from the queue\n   * @param value Value to be returned\n   */\n  bool try_pop(T & value)\n  {\n    if (queue_->pop(value)) return true;\n    return false;\n  }\n\n  /**\n   * @brief Wait for a value to be available in the queue\n   * @return Value if available, boost::none otherwise\n   */\n  boost::optional<T> wait_and_pop()\n  {\n    T value;\n    while (!queue_->pop(value)) boost::this_thread::yield();\n    return value;\n  }\n\n  /**\n   * @brief Wait for a value to be available in the queue for a given timeout\n   * @param value Value to be returned\n   */\n  void wait_and_pop(T & value)\n  {\n    while (!queue_->pop(value)) boost::this_thread::yield();\n  }\n\n  /**\n   * @brief Wait for a value to be available in the queue for a given timeout\n   * @param timeout Timeout in milliseconds\n   * @return Value if available, boost::none otherwise\n   */\n  boost::optional<T> wait_and_pop_for(const std::chrono::milliseconds & timeout)\n  {\n    T value;\n    auto start_time = std::chrono::steady_clock::now();\n    while (!queue_->pop(value))\n    {\n      if (\n        timeout != std::chrono::milliseconds::zero() &&\n        std::chrono::steady_clock::now() - start_time >= timeout)\n        return boost::none;\n      boost::this_thread::yield();\n    }\n    return value;\n  }\n\n  /**\n   * @brief Wait for a value to be available in the queue for a given timeout\n   * @param timeout Timeout in milliseconds\n   * @param value Value to be returned\n   */\n  bool wait_and_pop_for(const std::chrono::milliseconds & timeout, T & value)\n  {\n    auto start_time = std::chrono::steady_clock::now();\n    while (!queue_->pop(value))\n    {\n      if (\n        timeout != std::chrono::milliseconds::zero() &&\n        std::chrono::steady_clock::now() - start_time >= timeout)\n        return false;\n      boost::this_thread::yield();\n    }\n    return true;\n  }\n\n  bool empty() const { return queue_->empty(); }\n};\n}  // namespace ros2_canopen\n\n#endif  // EXCHANGE_HPP\n"
  },
  {
    "path": "canopen_core/include/canopen_core/lifecycle_manager.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef LIFECYCLE_DEVICE_MANAGER_NODE_HPP\n#define LIFECYCLE_DEVICE_MANAGER_NODE_HPP\n\n#include <chrono>\n#include <memory>\n#include <string>\n#include <thread>\n\n#include \"lifecycle_msgs/msg/state.hpp\"\n#include \"lifecycle_msgs/msg/transition.hpp\"\n#include \"lifecycle_msgs/srv/change_state.hpp\"\n#include \"lifecycle_msgs/srv/get_state.hpp\"\n//#include \"std_srvs/srv/trigger.hpp\"\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"rclcpp_lifecycle/lifecycle_node.hpp\"\n\n#include \"canopen_core/configuration_manager.hpp\"\n#include \"canopen_interfaces/srv/co_node.hpp\"\n\nusing namespace std::chrono_literals;\n/*\n\n*/\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle Device Manager Node\n *\n * This class provides functionalities to coordinate the lifecycle\n * of master and device drivers that are loaded into the executor.\n *\n * Start-up sequence\n * --------------------------------------------------------------------\n * master | unconfigured | x |\n *        | inactive     |   | x |\n *        | active       |       | x | x | x | x | x |...\n * --------------------------------------------------------------------\n * drv1   | unconfigured | x | x | x |\n *        | inactive     |           | x |\n *        | active       |               | x | x | x |...\n * --------------------------------------------------------------------\n * driv2  | unconfigured | x | x | x | x | x |\n *        | inactive     |                   | x |\n *        | active       |                       | x |...\n * --------------------------------------------------------------------\n *\n *\n *\n */\nclass LifecycleManager : public rclcpp_lifecycle::LifecycleNode\n{\npublic:\n  /**\n   * @brief Construct a new Lifecycle Device Manager Node object\n   *\n   * @param node_options\n   */\n  LifecycleManager(const rclcpp::NodeOptions & node_options)\n  : rclcpp_lifecycle::LifecycleNode(\"lifecycle_manager\", node_options)\n  {\n    this->declare_parameter(\"container_name\", \"\");\n    cbg_clients = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n  }\n\n  void init(std::shared_ptr<ros2_canopen::ConfigurationManager> config);\n\nprotected:\n  rclcpp::CallbackGroup::SharedPtr cbg_clients;\n  std::shared_ptr<ros2_canopen::ConfigurationManager> config_;\n\n  /**\n   * @brief Callback for the Configure Transition\n   *\n   * This will cause the device manager to load the configuration\n   * from the configuration file.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Callback for the Activate Transition\n   *\n   * This will bringup master and device drivers using the\n   * bring_up_all function.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Callback for the Deactivate Transition\n   *\n   * This will bring down master and device drivers using the\n   * bring_down_all function.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Callback for the Cleanup Transition\n   *\n   * Does nothing.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State & state);\n\n  /**\n   * @brief Callback for the Shutdown Transition\n   *\n   * Does nothing.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State & state);\n\n  std::map<uint8_t, rclcpp::Client<lifecycle_msgs::srv::GetState>::SharedPtr>\n    drivers_get_state_clients;  ///< stores node_id and get_state client\n  std::map<uint8_t, rclcpp::Client<lifecycle_msgs::srv::ChangeState>::SharedPtr>\n    drivers_change_state_clients;                      ///< stores node_id and change_state client\n  std::map<std::string, uint8_t> device_names_to_ids;  // stores device_name and node_id\n\n  /**\n   * @todo Remove relicts?\n   *\n   */\n  rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr\n    add_driver_client_;  ///< Service client object for adding a driver\n  rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr\n    remove_driver_client_;  ///< Service client object for removing a driver\n\n  uint8_t master_id_;           ///< Stores master id\n  std::string container_name_;  ///< Stores name of the associated device_container\n\nprotected:\n  template <typename FutureT, typename WaitTimeT>\n  std::future_status wait_for_result(FutureT & future, WaitTimeT time_to_wait)\n  {\n    auto end = std::chrono::steady_clock::now() + time_to_wait;\n    std::chrono::milliseconds wait_period(100);\n    std::future_status status = std::future_status::timeout;\n    do\n    {\n      auto now = std::chrono::steady_clock::now();\n      auto time_left = end - now;\n      if (time_left <= std::chrono::seconds(0))\n      {\n        break;\n      }\n      status = future.wait_for((time_left < wait_period) ? time_left : wait_period);\n    } while (rclcpp::ok() && status != std::future_status::ready);\n    return status;\n  }\n\n  /**\n   * @brief Get the lifecycle state of a driver node\n   *\n   * @param [in] node_id\n   * @param [in] time_out\n   * @return unsigned int\n   */\n  virtual unsigned int get_state(uint8_t node_id, std::chrono::seconds time_out);\n\n  /**\n   * @brief Change the lifecycle state of a driver node\n   *\n   * @param [in] node_id      CANopen node id of the driver\n   * @param [in] transition   Lifecycle transition to trigger\n   * @param [in] time_out     Timeout\n   * @return true\n   * @return false\n   */\n  virtual bool change_state(uint8_t node_id, uint8_t transition, std::chrono::seconds time_out);\n\n  /**\n   * @brief Brings up master and all drivers\n   *\n   * This funnnction brings up the CANopen master and all drivers that are defined\n   * in the configuration. The order of bringing up drivers is arbitrary.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool bring_up_all();\n\n  /**\n   * @brief Brings down master and all drivers\n   *\n   * This funnnction brings up the CANopen master and all drivers that are defined\n   * in the configuration. First all drivers are brought down, then the master.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool bring_down_all();\n\n  /**\n   * @brief Brings up master\n   *\n   * This function brings up the CANopen master. The master transitioned twice,\n   * first the configure transition is triggered. Once the transition is successfully\n   * finished, the activate transition is triggered.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool bring_up_master();\n\n  /**\n   * @brief Bring down master\n   *\n   * This function brrignsdown the CANopen master. The master transitioned twice,\n   * first the deactivate transition is triggered. Once the transition is successfully\n   * finished, the cleanup transition is triggered.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool bring_down_master();\n\n  /**\n   * @brief Brings up the drivers with specified node_id\n   *\n   * This function bringsup the CANopen driver for the device with the specified\n   * node_id. The driver is transitioned twice,\n   * first the configure transition is triggered. Once the transition is successfully\n   * finished, the activate transition is triggered.\n   *\n   * @param device_name\n   * @return true\n   * @return false\n   */\n  virtual bool bring_up_driver(std::string device_name);\n\n  /**\n   * @brief Brings down the driver with specified node_id\n   *\n   * This function brings down the CANopen driver for the device with the specified\n   * node_id. The driver is transitioned twice,\n   * first the deactivate transition is triggered. Once the transition is successfully\n   * finished, the cleanup transition is triggered.\n   *\n   * @param device_name\n   * @return true\n   * @return false\n   */\n  virtual bool bring_down_driver(std::string device_name);\n\n  /**\n   * @brief Load information from configuration\n   *\n   * This function loads the information about the CANopen Bus specified in\n   * the configuration file and creates the necessary ROS2 services and clients.\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool load_from_config();\n};\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/master_error.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef MASTER_ERROR_HPP_\n#define MASTER_ERROR_HPP_\n\n#include <system_error>\n\nnamespace ros2_canopen\n{\n/**\n * @brief Master Exception\n *\n * This exception is used, when a master\n * fails.\n *\n */\nclass MasterException : public std::exception\n{\nprivate:\n  std::string what_;\n\npublic:\n  MasterException(std::string what) { what_ = what; }\n\n  char * what();\n};\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/master_node.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef MASTER_NODE_HPP_\n#define MASTER_NODE_HPP_\n\n#include <rclcpp/rclcpp.hpp>\n#include \"canopen_core/node_interfaces/node_canopen_master.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Canopen Master Interface\n *\n * This class provides the interface that all master's that are loaded\n * by the device container need to implement.\n */\nclass CanopenMasterInterface\n{\npublic:\n  /**\n   * @brief Initialise the master\n   *\n   * This function should initialise the master's functionality.\n   * It will be called by the device container after the node was\n   * added to the ros executor.\n   */\n  virtual void init() = 0;\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function should shutdown all functionality and make sure that\n   * the master will exit cleanly. It will be called by the device container\n   * before exiting.\n   *\n   */\n  virtual void shutdown() = 0;\n  /**\n   * @brief Get the master object\n   *\n   * This function should return the lely master object. It should\n   * throw a ros2_canopen::MasterException if the master object\n   * was not yet set.\n   *\n   * @return std::shared_ptr<lely::canopen::AsyncMaster>\n   */\n  virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() = 0;\n  /**\n   * @brief Get the executor object\n   *\n   * This function gets the lely executor object. It should throw\n   * a ros2_canopen::MasterException if the executor object is not\n   * yet instantiated.\n   *\n   * @return std::shared_ptr<lely::ev::Executor>\n   */\n  virtual std::shared_ptr<lely::ev::Executor> get_executor() = 0;\n\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function should return the NodeBaseInterface of the associated\n   * ROS node. This is used by device container to add the master to the\n   * ros executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() = 0;\n\n  /**\n   * @brief Check whether the node is a lifecycle node\n   *\n   * @return true\n   * @return false\n   */\n  virtual bool is_lifecycle() = 0;\n};\n\n/**\n * @brief Canopen Master\n *\n * This class implements the Canopen Master Interface and is derived\n * from rclcpp::Node. All unmanaged master nodes should inherit from\n * this class.\n *\n */\nclass CanopenMaster : public CanopenMasterInterface, public rclcpp::Node\n{\npublic:\n  std::shared_ptr<node_interfaces::NodeCanopenMasterInterface> node_canopen_master_;\n  explicit CanopenMaster(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp::Node(\"canopen_master\", node_options)\n  {\n    // node_canopen_master_ =\n    // std::make_shared<node_interfaces::NodeCanopenMaster<rclcpp::Node>>(this);\n  }\n  /**\n   * @brief Initialises the driver\n   *\n   * This function initialises the driver. It is called by the\n   * device container after adding the node to the ros executor.\n   * This function uses the NodeCanopenMasterInterface. It will\n   * call init(), configure() and activate(). If this function\n   * does not throw, the driver is successfully initialised and\n   * ready to be used.\n   *\n   */\n  virtual void init() override;\n\n  /**\n   * @brief Shuts the master down\n   *\n   * This function is called by the device container before exiting,\n   * it should enable a clean exit of the master and especially join\n   * all threads. It will call the shutdown() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   */\n  virtual void shutdown() override;\n\n  /**\n   * @brief Get the master object\n   *\n   * This function should return the lely master object. It should\n   * throw a ros2_canopen::MasterException if the master object\n   * was not yet set.\n   *\n   * @return std::shared_ptr<lely::canopen::AsyncMaster>\n   */\n  virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() override;\n  /**\n   * @brief Get the executor object\n   *\n   * This function gets the lely executor object. It should throw\n   * a ros2_canopen::MasterException if the executor object is not\n   * yet instantiated.\n   *\n   * @return std::shared_ptr<lely::ev::Executor>\n   */\n  virtual std::shared_ptr<lely::ev::Executor> get_executor() override;\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function should return the NodeBaseInterface of the associated\n   * ROS node. This is used by device container to add the master to the\n   * ros executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override\n  {\n    return rclcpp::Node::get_node_base_interface();\n  }\n  /**\n   * @brief Check whether the node is a lifecycle node\n   *\n   * @return false\n   */\n  virtual bool is_lifecycle() { return false; }\n};\n\nclass LifecycleCanopenMaster : public CanopenMasterInterface, public rclcpp_lifecycle::LifecycleNode\n{\nprotected:\n  std::shared_ptr<node_interfaces::NodeCanopenMasterInterface> node_canopen_master_;\n\npublic:\n  LifecycleCanopenMaster(const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp_lifecycle::LifecycleNode(\"lifecycle_canopen_master\", node_options)\n  {\n    node_canopen_master_ =\n      std::make_shared<node_interfaces::NodeCanopenMaster<rclcpp_lifecycle::LifecycleNode>>(this);\n  }\n  /**\n   * @brief Initialises the driver\n   *\n   * This function initialises the driver. It is called by the\n   * device container after adding the node to the ros executor.\n   * This function uses the NodeCanopenMasterInterface. It will\n   * call init(). If this function\n   * does not throw, the driver is successfully initialised and\n   * ready to switch through the lifecycle.\n   *\n   */\n  virtual void init() override;\n\n  /**\n   * @brief Shuts the master down\n   *\n   * This function is called by the device container before exiting,\n   * it should enable a clean exit of the master and especially join\n   * all threads. It will call the shutdown() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   */\n  virtual void shutdown() override;\n  /**\n   * @brief Get the master object\n   *\n   * This function should return the lely master object. It should\n   * throw a ros2_canopen::MasterException if the master object\n   * was not yet set.\n   *\n   * @return std::shared_ptr<lely::canopen::AsyncMaster>\n   */\n  virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() override;\n  /**\n   * @brief Get the executor object\n   *\n   * This function gets the lely executor object. It should throw\n   * a ros2_canopen::MasterException if the executor object is not\n   * yet instantiated.\n   *\n   * @return std::shared_ptr<lely::ev::Executor>\n   */\n  virtual std::shared_ptr<lely::ev::Executor> get_executor() override;\n  /**\n   * @brief Configure Transition Callback\n   *\n   * This function will call the configure() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Activate Transition Callback\n   *\n   * This function will call the active() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Deactivet Transition Callback\n   *\n   * This function will call the deactivate() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Cleanup Transition Callback\n   *\n   * This function will call the cleanup() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Shutdown Transition Callback\n   *\n   * This function will call the shutdown() function of the\n   * NodeCanopenMasterInterface object associated with this class.\n   *\n   * @param state\n   * @return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\n   */\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State & state);\n  /**\n   * @brief Get the node base interface object\n   *\n   * This function should return the NodeBaseInterface of the associated\n   * ROS node. This is used by device container to add the master to the\n   * ros executor.\n   *\n   * @return rclcpp::node_interfaces::NodeBaseInterface::SharedPtr\n   */\n  virtual rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface() override\n  {\n    return rclcpp_lifecycle::LifecycleNode::get_node_base_interface();\n  }\n  /**\n   * @brief Check whether the node is a lifecycle node\n   *\n   * @return true\n   */\n  virtual bool is_lifecycle() { return true; }\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/node_interfaces/node_canopen_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_DRIVER_HPP_\n#define NODE_CANOPEN_DRIVER_HPP_\n\n#include <yaml-cpp/yaml.h>\n#include <atomic>\n#include <lely/coapp/driver.hpp>\n#include <map>\n#include <memory>\n#include <rclcpp/node_interfaces/node_base_interface.hpp>\n#include <rclcpp/node_interfaces/node_clock_interface.hpp>\n#include <rclcpp/node_interfaces/node_graph_interface.hpp>\n#include <rclcpp/node_interfaces/node_logging_interface.hpp>\n#include <rclcpp/node_interfaces/node_parameters_interface.hpp>\n#include <rclcpp/node_interfaces/node_services_interface.hpp>\n#include <rclcpp/node_interfaces/node_time_source_interface.hpp>\n#include <rclcpp/node_interfaces/node_timers_interface.hpp>\n#include <rclcpp/node_interfaces/node_topics_interface.hpp>\n#include <rclcpp/node_interfaces/node_waitables_interface.hpp>\n#include <rclcpp/rclcpp.hpp>\n#include <rclcpp_lifecycle/lifecycle_node.hpp>\n#include <type_traits>\n#include <vector>\n#include \"canopen_core/driver_error.hpp\"\n#include \"canopen_core/node_interfaces/node_canopen_driver_interface.hpp\"\n#include \"canopen_core/visibility_control.h\"\n#include \"canopen_interfaces/srv/co_node.hpp\"\n\nusing namespace rclcpp;\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n/**\n * @brief Node Canopen Driver\n *\n * This class implements the NodeCanopenDriverInterface. It provides\n * core functionality and logic for CanopenDriver, indepentently of the\n * ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode\n * and derived classes are supported. Other node types will lead to compile\n * time error.\n *\n * @tparam NODETYPE\n */\ntemplate <class NODETYPE>\nclass NodeCanopenDriver : public NodeCanopenDriverInterface\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  NODETYPE * node_;\n\n  std::shared_ptr<lely::ev::Executor> exec_;\n  std::shared_ptr<lely::canopen::AsyncMaster> master_;\n  std::shared_ptr<lely::canopen::BasicDriver> driver_;\n\n  std::chrono::milliseconds non_transmit_timeout_;\n  YAML::Node config_;\n  uint8_t node_id_;\n  std::string container_name_;\n  std::string eds_;\n  std::string bin_;\n\n  rclcpp::CallbackGroup::SharedPtr client_cbg_;\n  rclcpp::CallbackGroup::SharedPtr timer_cbg_;\n\n  std::atomic<bool> master_set_;\n  std::atomic<bool> initialised_;\n  std::atomic<bool> configured_;\n  std::atomic<bool> activated_;\n\npublic:\n  NodeCanopenDriver(NODETYPE * node)\n  : master_set_(false), initialised_(false), configured_(false), activated_(false)\n  {\n    node_ = node;\n  }\n\n  /**\n   * @brief Set Master\n   *\n   * Sets the Lely Canopen Master Objects needed by the driver\n   * to add itself to the master.\n   *\n   */\n  virtual void set_master(\n    std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master)\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"set_master_start\");\n    if (!configured_.load())\n    {\n      throw DriverException(\"Set Master: driver is not configured\");\n    }\n    if (activated_.load())\n    {\n      throw DriverException(\"Set Master: driver is not activated\");\n    }\n    this->exec_ = exec;\n    this->master_ = master;\n    this->master_set_.store(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"set_master_end\");\n  }\n\n  /**\n   * @brief Initialise the driver\n   *\n   * In this function the ROS interface should be created and\n   * potentially necessary callback groups.\n   *\n   */\n  void init()\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"init_start\");\n    if (configured_.load())\n    {\n      throw DriverException(\"Init: Driver is already configured\");\n    }\n    if (activated_.load())\n    {\n      throw DriverException(\"Init: Driver is already activated\");\n    }\n    client_cbg_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n    timer_cbg_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n\n    node_->declare_parameter(\"container_name\", \"\");\n    node_->declare_parameter(\"node_id\", 0);\n    node_->declare_parameter(\"non_transmit_timeout\", 100);\n    node_->declare_parameter(\"config\", \"\");\n    this->init(true);\n    this->initialised_.store(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"init_end\");\n  }\n\n  /**\n   * @brief Initialises the driver\n   *\n   * This does not do anything, it is an empty function. it\n   * should be overridden by derived classes.\n   *\n   * @todo\n   * Potentially make this an abstract function. This is mainly\n   * for debugging purposes.\n   *\n   * @param called_from_base\n   */\n  virtual void init(bool called_from_base) {}\n\n  /**\n   * @brief Configure the driver\n   *\n   * This function should contain the configuration related things,\n   * such as reading parameter data or configuration data from files.\n   *\n   * This function reads the parameters container_name, non_transmit_timeout,\n   * node_id and config. Once done it will call the configure(bool) function\n   * that should be over\n   *\n   */\n  void configure()\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"configure_start\");\n    if (!initialised_.load())\n    {\n      throw DriverException(\"Configure: driver is not initialised\");\n    }\n    if (configured_.load())\n    {\n      throw DriverException(\"Configure: driver is already configured\");\n    }\n    if (activated_.load())\n    {\n      throw DriverException(\"Configure: driver is already activated\");\n    }\n    int non_transmit_timeout;\n    std::string config;\n    node_->get_parameter(\"container_name\", container_name_);\n    node_->get_parameter(\"non_transmit_timeout\", non_transmit_timeout);\n    node_->get_parameter(\"node_id\", this->node_id_);\n    node_->get_parameter(\"config\", config);\n    this->config_ = YAML::Load(config);\n    this->non_transmit_timeout_ = std::chrono::milliseconds(non_transmit_timeout);\n    auto path = this->config_[\"dcf_path\"].template as<std::string>();\n    auto dcf = this->config_[\"dcf\"].template as<std::string>();\n    auto name = this->node_->get_name();\n    eds_ = path + \"/\" + dcf;\n    bin_ = path + \"/\" + name + \".bin\";\n    this->configure(true);\n    this->configured_.store(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"configure_end\");\n  }\n  /**\n   * @brief Configure the driver\n   *\n   * This function should be overridden by derived classes.\n   *\n   * @param called_from_base\n   */\n  virtual void configure(bool called_from_base) {}\n\n  /**\n   * @brief Activate the driver\n   *\n   * This function should activate the driver, consequently it needs to start all timers and threads\n   * necessary for the operation of the driver.\n   *\n   */\n  void activate()\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"activate_start\");\n    if (!master_set_.load())\n    {\n      throw DriverException(\"Activate: master is not set\");\n    }\n    if (!initialised_.load())\n    {\n      throw DriverException(\"Activate: driver is not initialised\");\n    }\n    if (!configured_.load())\n    {\n      throw DriverException(\"Activate: driver is not configured\");\n    }\n    if (activated_.load())\n    {\n      throw DriverException(\"Activate: driver is already activated\");\n    }\n    this->add_to_master();\n    this->activate(true);\n    this->activated_.store(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"activate_end\");\n  }\n\n  /**\n   * @brief Activates the driver.\n   *\n   * This function should be overridden by derived\n   * classes.\n   *\n   * @param called_from_base\n   */\n  virtual void activate(bool called_from_base) {}\n\n  /**\n   * @brief Deactivate the driver\n   *\n   * This function should deactivate the driver, consequently it needs to stop all timers and\n   * threads that are related to the operation of the diver.\n   *\n   */\n  void deactivate()\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"deactivate_start\");\n    if (!master_set_.load())\n    {\n      throw DriverException(\"Activate: master is not set\");\n    }\n    if (!initialised_.load())\n    {\n      throw DriverException(\"Deactivate: driver is not initialised\");\n    }\n    if (!configured_.load())\n    {\n      throw DriverException(\"Deactivate: driver is not configured\");\n    }\n    if (!activated_.load())\n    {\n      throw DriverException(\"Deactivate: driver is not activated\");\n    }\n    this->activated_.store(false);\n    this->remove_from_master();\n    this->deactivate(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"deactivate_end\");\n  }\n  /**\n   * @brief Deactivates the driver\n   *\n   * This function should be overridden by derived classes.\n   *\n   * @param called_from_base\n   */\n  virtual void deactivate(bool called_from_base) {}\n\n  /**\n   * @brief Cleanup the driver\n   *\n   * This function needs to clean the internal state of the driver. This means\n   * all data should be deleted.\n   *\n   */\n  void cleanup()\n  {\n    if (!initialised_.load())\n    {\n      throw DriverException(\"Cleanup: driver is not initialised\");\n    }\n    if (!configured_.load())\n    {\n      throw DriverException(\"Cleanup: driver is not configured\");\n    }\n    if (activated_.load())\n    {\n      throw DriverException(\"Cleanup: driver is still activated\");\n    }\n    this->cleanup(true);\n    this->configured_.store(false);\n  }\n\n  /**\n   * @brief Cleanup the driver\n   *\n   * This function should be overridden by derived classes.\n   *\n   * @param called_from_base\n   */\n  virtual void cleanup(bool called_from_base)\n  {\n    RCLCPP_INFO(this->node_->get_logger(), \"Cleanup\");\n    this->exec_.reset();\n    this->master_.reset();\n    this->master_set_.store(false);\n  }\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function should shutdown the driver.\n   *\n   */\n  void shutdown()\n  {\n    RCLCPP_DEBUG(this->node_->get_logger(), \"Shutting down.\");\n    if (this->activated_)\n    {\n      this->deactivate();\n    }\n    if (this->configured_)\n    {\n      this->cleanup();\n    }\n    shutdown(true);\n    this->master_set_.store(false);\n    this->initialised_.store(false);\n    this->configured_.store(false);\n    this->activated_.store(false);\n  }\n  /**\n   * @brief Shuts down the driver\n   *\n   * This function should be overridden by derived classes.\n   *\n   * @param called_from_base\n   */\n  virtual void shutdown(bool called_from_base) {}\n\n  virtual void demand_set_master();\n\nprotected:\n  /**\n   * @brief Add the driver to master\n   *\n   */\n  virtual void add_to_master() { throw DriverException(\"Add to master not implemented.\"); }\n\n  /**\n   * @brief Remove the driver from master\n   *\n   */\n  virtual void remove_from_master()\n  {\n    throw DriverException(\"Remove from master not implemented.\");\n  }\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/node_interfaces/node_canopen_driver_interface.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_DRIVER_INTERFACE_HPP_\n#define NODE_CANOPEN_DRIVER_INTERFACE_HPP_\n\n#include <lely/coapp/master.hpp>\n#include <lely/ev/exec.hpp>\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n/**\n * @brief Node Canopen Driver Interface\n *\n * This node provides the interface for NodeCanopenDriver classes\n * that provide ROS node independent CANopen functionality.\n *\n */\nclass NodeCanopenDriverInterface\n{\npublic:\n  NodeCanopenDriverInterface() {}\n  /**\n   * @brief Set Master\n   *\n   * Sets the Lely Canopen Master Objects needed by the driver\n   * to add itself to the master.\n   *\n   */\n  virtual void set_master(\n    std::shared_ptr<lely::ev::Executor> exec,\n    std::shared_ptr<lely::canopen::AsyncMaster> master) = 0;\n\n  /**\n   * @brief Demand set Master\n   *\n   * This function should ask the drivers parent container to\n   * set the master objects. This should result in a call to\n   * set_master function.\n   *\n   */\n  virtual void demand_set_master() = 0;\n\n  /**\n   * @brief Initialise the driver\n   *\n   * In this function the ROS interface should be created and\n   * potentially necessary callback groups.\n   *\n   */\n  virtual void init() = 0;\n\n  /**\n   * @brief Configure the driver\n   *\n   * This function should contain the configuration related things,\n   * such as reading parameter data or configuration data from files.\n   *\n   */\n  virtual void configure() = 0;\n\n  /**\n   * @brief Activate the driver\n   *\n   * This function should activate the driver, consequently it needs to start all timers and threads\n   * necessary for the operation of the driver.\n   *\n   */\n  virtual void activate() = 0;\n\n  /**\n   * @brief Deactivate the driver\n   *\n   * This function should deactivate the driver, consequently it needs to stop all timers and\n   * threads that are related to the operation of the diver.\n   *\n   */\n  virtual void deactivate() = 0;\n\n  /**\n   * @brief Cleanup the driver\n   *\n   * This function needs to clean the internal state of the driver. This means\n   * all data should be deleted.\n   *\n   */\n  virtual void cleanup() = 0;\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function should shutdown the driver.\n   *\n   */\n  virtual void shutdown() = 0;\n\n  /**\n   * @brief Add the driver to master\n   *\n   */\n  virtual void add_to_master() = 0;\n\n  /**\n   * @brief Remove the driver from master\n   *\n   */\n  virtual void remove_from_master() = 0;\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/node_interfaces/node_canopen_master.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_MASTER_HPP_\n#define NODE_CANOPEN_MASTER_HPP_\n\n#include <yaml-cpp/yaml.h>\n#include <atomic>\n#include <lely/coapp/master.hpp>\n#include <lely/coapp/slave.hpp>\n#include <lely/ev/exec.hpp>\n#include <lely/ev/loop.hpp>\n#include <lely/io2/linux/can.hpp>\n#include <lely/io2/posix/poll.hpp>\n#include <lely/io2/sys/io.hpp>\n#include <lely/io2/sys/sigset.hpp>\n#include <lely/io2/sys/timer.hpp>\n#include <rclcpp/rclcpp.hpp>\n#include <rclcpp_lifecycle/lifecycle_node.hpp>\n#include <thread>\n#include \"canopen_core/master_error.hpp\"\n#include \"canopen_core/node_interfaces/node_canopen_master_interface.hpp\"\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n/**\n * @brief Node Canopen Master\n *\n * This class implements the NodeCanopenMasterInterface. It provides\n * core functionality and logic for CanopenMaster, indepentently of the\n * ROS node type. Currently rclcpp::Node and rclcpp_lifecycle::LifecycleNode\n * and derived classes are supported. Other node types will lead to compile\n * time error.\n *\n * @tparam NODETYPE\n */\ntemplate <class NODETYPE>\nclass NodeCanopenMaster : public NodeCanopenMasterInterface\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  NODETYPE * node_;\n\n  std::atomic<bool> initialised_;\n  std::atomic<bool> configured_;\n  std::atomic<bool> activated_;\n  std::atomic<bool> master_set_;\n\n  std::shared_ptr<lely::canopen::AsyncMaster> master_;\n  std::shared_ptr<lely::ev::Executor> exec_;\n\n  std::unique_ptr<lely::io::IoGuard> io_guard_;\n  std::unique_ptr<lely::io::Context> ctx_;\n  std::unique_ptr<lely::io::Poll> poll_;\n  std::unique_ptr<lely::ev::Loop> loop_;\n  std::unique_ptr<lely::io::Timer> timer_;\n  std::unique_ptr<lely::io::CanController> ctrl_;\n  std::unique_ptr<lely::io::CanChannel> chan_;\n  std::unique_ptr<lely::io::SignalSet> sigset_;\n\n  rclcpp::CallbackGroup::SharedPtr client_cbg_;\n  rclcpp::CallbackGroup::SharedPtr timer_cbg_;\n\n  YAML::Node config_;\n  uint8_t node_id_;\n  std::chrono::milliseconds non_transmit_timeout_;\n  std::string container_name_;\n  std::string master_dcf_;\n  std::string master_bin_;\n  std::string can_interface_name_;\n  uint32_t timeout_;\n\n  std::thread spinner_;\n\npublic:\n  NodeCanopenMaster(NODETYPE * node)\n  : initialised_(false), configured_(false), activated_(false), master_set_(false)\n  {\n    node_ = node;\n  }\n\n  /**\n   * @brief Initialise Master\n   *\n   */\n  void init() override\n  {\n    RCLCPP_DEBUG(node_->get_logger(), \"init_start\");\n    if (configured_.load())\n    {\n      throw MasterException(\"Init: Master is already configured.\");\n    }\n    if (activated_.load())\n    {\n      throw MasterException(\"Init: Master is already activated.\");\n    }\n    client_cbg_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n    timer_cbg_ = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);\n\n    node_->declare_parameter(\"container_name\", \"\");\n    node_->declare_parameter(\"master_dcf\", \"\");\n    node_->declare_parameter(\"master_bin\", \"\");\n    node_->declare_parameter(\"can_interface_name\", \"vcan0\");\n    node_->declare_parameter(\"node_id\", 0);\n    node_->declare_parameter(\"non_transmit_timeout\", 100);\n    node_->declare_parameter(\"config\", \"\");\n    this->init(true);\n    this->initialised_.store(true);\n    RCLCPP_DEBUG(node_->get_logger(), \"init_end\");\n  }\n  virtual void init(bool called_from_base) {}\n\n  /**\n   * @brief Configure the driver\n   *\n   * This function should contain the configuration related things,\n   * such as reading parameter data or configuration data from files.\n   *\n   */\n  void configure() override\n  {\n    if (!initialised_.load())\n    {\n      throw MasterException(\"Configure: Master is not initialised.\");\n    }\n    if (configured_.load())\n    {\n      throw MasterException(\"Configure: Master is already configured.\");\n    }\n    if (activated_.load())\n    {\n      throw MasterException(\"Configure: Master is already activated.\");\n    }\n\n    int non_transmit_timeout;\n    std::string config;\n\n    node_->get_parameter(\"container_name\", container_name_);\n    node_->get_parameter(\"master_dcf\", master_dcf_);\n    node_->get_parameter(\"master_bin\", master_bin_);\n    node_->get_parameter(\"can_interface_name\", can_interface_name_);\n    node_->get_parameter(\"node_id\", node_id_);\n    node_->get_parameter(\"non_transmit_timeout\", non_transmit_timeout);\n    node_->get_parameter(\"config\", config);\n\n    this->config_ = YAML::Load(config);\n    this->non_transmit_timeout_ = std::chrono::milliseconds(non_transmit_timeout);\n\n    this->configure(true);\n    this->configured_.store(true);\n  }\n\n  virtual void configure(bool called_from_base)\n  {\n    std::optional<int> timeout;\n    try\n    {\n      timeout = this->config_[\"boot_timeout\"].as<int>();\n    }\n    catch (...)\n    {\n      RCLCPP_WARN(\n        this->node_->get_logger(),\n        \"No timeout parameter found in config file. Using default value of 100ms.\");\n    }\n    this->timeout_ = timeout.value_or(2000);\n    RCLCPP_INFO_STREAM(\n      this->node_->get_logger(), \"Master boot timeout set to \" << this->timeout_ << \"ms.\");\n  }\n\n  /**\n   * @brief Activate the driver\n   *\n   * This function should activate the driver, consequently it needs to start all timers and threads\n   * necessary for the operation of the driver.\n   *\n   */\n  void activate() override\n  {\n    RCLCPP_DEBUG(this->node_->get_logger(), \"NodeCanopenMaster activate start\");\n    if (!initialised_.load())\n    {\n      throw MasterException(\"Activate: master is not initialised\");\n    }\n    if (!configured_.load())\n    {\n      throw MasterException(\"Activate: master is not configured\");\n    }\n    if (activated_.load())\n    {\n      throw MasterException(\"Activate: master is already activated\");\n    }\n\n    io_guard_ = std::make_unique<lely::io::IoGuard>();\n    ctx_ = std::make_unique<lely::io::Context>();\n    poll_ = std::make_unique<lely::io::Poll>(*ctx_);\n    loop_ = std::make_unique<lely::ev::Loop>(poll_->get_poll());\n\n    exec_ = std::make_shared<lely::ev::Executor>(loop_->get_executor());\n    timer_ = std::make_unique<lely::io::Timer>(*poll_, *exec_, CLOCK_MONOTONIC);\n    ctrl_ = std::make_unique<lely::io::CanController>(can_interface_name_.c_str());\n    chan_ = std::make_unique<lely::io::CanChannel>(*poll_, *exec_);\n    chan_->open(*ctrl_);\n\n    this->activate(true);\n    if (!master_)\n    {\n      throw MasterException(\"Activate: master not set\");\n    }\n    this->master_set_.store(true);\n    this->master_->Reset();\n    this->spinner_ = std::thread(\n      [this]()\n      {\n        try\n        {\n          loop_->run();\n        }\n        catch (const std::exception & e)\n        {\n          RCLCPP_INFO(this->node_->get_logger(), e.what());\n        }\n        RCLCPP_INFO(this->node_->get_logger(), \"Canopen master loop stopped\");\n      });\n    this->activated_.store(true);\n    RCLCPP_DEBUG(this->node_->get_logger(), \"NodeCanopenMaster activate end\");\n  }\n  /**\n   * @brief Activate hook for derived classes\n   *\n   * This function should create a Master using exec_, timer_, master_dcf_, master_bin_\n   * and node_id_ members and store it in master_. It should also create a thread and run\n   * the master's event loop.\n   *\n   * @param called_from_base\n   */\n  virtual void activate(bool called_from_base) {}\n\n  /**\n   * @brief Deactivate the driver\n   *\n   * This function should deactivate the driver, consequently it needs to stop all timers and\n   * threads that are related to the operation of the diver.\n   *\n   */\n  void deactivate() override\n  {\n    if (!initialised_.load())\n    {\n      throw MasterException(\"Deactivate: master is not initialised\");\n    }\n    if (!configured_.load())\n    {\n      throw MasterException(\"Deactivate: master is not configured\");\n    }\n    if (!activated_.load())\n    {\n      throw MasterException(\"Deactivate: master is not activated\");\n    }\n    exec_->post(\n      [this]()\n      {\n        RCLCPP_INFO(node_->get_logger(), \"Lely Core Context Shutdown\");\n        ctx_->shutdown();\n      });\n    this->spinner_.join();\n\n    this->deactivate(true);\n    this->activated_.store(false);\n  }\n\n  /**\n   * @brief Deactivate hook for derived classes\n   *\n   * This function should wait to join the thread created in the activate\n   * function.\n   *\n   * @param called_from_base\n   */\n  virtual void deactivate(bool called_from_base) {}\n\n  /**\n   * @brief Cleanup the driver\n   *\n   * This function needs to clean the internal state of the driver. This means\n   * all data should be deleted.\n   *\n   */\n  void cleanup() override\n  {\n    if (!initialised_.load())\n    {\n      throw MasterException(\"Cleanup: master is not initialised.\");\n    }\n    if (!configured_.load())\n    {\n      throw MasterException(\"Cleanup: master is not configured\");\n    }\n    if (activated_.load())\n    {\n      throw MasterException(\"Cleanup: master is still active\");\n    }\n    this->cleanup(true);\n    io_guard_.reset();\n    ctx_.reset();\n    poll_.reset();\n    loop_.reset();\n\n    exec_.reset();\n    timer_.reset();\n    ctrl_.reset();\n    chan_.reset();\n    this->configured_.store(false);\n    this->master_set_.store(false);\n  }\n  virtual void cleanup(bool called_from_base) {}\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function should shutdown the driver.\n   *\n   */\n  void shutdown() override\n  {\n    RCLCPP_DEBUG(this->node_->get_logger(), \"Shutting down.\");\n    if (this->activated_)\n    {\n      this->deactivate();\n    }\n\n    if (this->configured_)\n    {\n      this->cleanup();\n    }\n    shutdown(true);\n\n    this->master_set_.store(false);\n    this->initialised_.store(false);\n    this->configured_.store(false);\n    this->activated_.store(false);\n  }\n  virtual void shutdown(bool called_from_base) {}\n\n  /**\n   * @brief Get the master object\n   *\n   * @return std::shared_ptr<lely::canopen::AsyncMaster>\n   */\n  virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master()\n  {\n    if (!master_set_.load())\n    {\n      throw MasterException(\"Get Master: Master is not set.\");\n    }\n    return master_;\n  }\n  /**\n   * @brief Get the executor object\n   *\n   * @return std::shared_ptr<lely::canopen::Executor>\n   */\n  virtual std::shared_ptr<lely::ev::Executor> get_executor()\n  {\n    if (!master_set_.load())\n    {\n      throw MasterException(\"Get Executor: master is not set\");\n    }\n    return exec_;\n  }\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/node_interfaces/node_canopen_master_interface.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_MASTER_INTERFACE_HPP_\n#define NODE_CANOPEN_MASTER_INTERFACE_HPP_\n\n#include <lely/coapp/master.hpp>\n#include <lely/ev/exec.hpp>\n#include \"canopen_core/node_interfaces/node_canopen_driver_interface.hpp\"\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n/**\n * @brief Node Canopen Master Interface\n *\n * This node provides the interface for NodeCanopenMaster classes\n * that provide ROS node independent CANopen functionality.\n *\n */\nclass NodeCanopenMasterInterface\n{\npublic:\n  /**\n   * @brief Initialise Master\n   *\n   */\n  virtual void init() = 0;\n\n  /**\n   * @brief Configure the driver\n   *\n   * This function should contain the configuration related things,\n   * such as reading parameter data or configuration data from files.\n   *\n   */\n  virtual void configure() = 0;\n\n  /**\n   * @brief Activate the driver\n   *\n   * This function should activate the driver, consequently it needs to start all timers and threads\n   * necessary for the operation of the driver.\n   *\n   */\n  virtual void activate() = 0;\n\n  /**\n   * @brief Deactivate the driver\n   *\n   * This function should deactivate the driver, consequently it needs to stop all timers and\n   * threads that are related to the operation of the diver.\n   *\n   */\n  virtual void deactivate() = 0;\n\n  /**\n   * @brief Cleanup the driver\n   *\n   * This function needs to clean the internal state of the driver. This means\n   * all data should be deleted.\n   *\n   */\n  virtual void cleanup() = 0;\n\n  /**\n   * @brief Shutdown the driver\n   *\n   * This function should shutdown the driver.\n   *\n   */\n  virtual void shutdown() = 0;\n  /**\n   * @brief Get the master object\n   *\n   * @return std::shared_ptr<lely::canopen::AsyncMaster>\n   */\n  virtual std::shared_ptr<lely::canopen::AsyncMaster> get_master() = 0;\n  /**\n   * @brief Get the executor object\n   *\n   * @return std::shared_ptr<lely::canopen::Executor>\n   */\n  virtual std::shared_ptr<lely::ev::Executor> get_executor() = 0;\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n#endif\n"
  },
  {
    "path": "canopen_core/include/canopen_core/visibility_control.h",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef CANOPEN_CORE__VISIBILITY_CONTROL_H_\n#define CANOPEN_CORE__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_CORE_EXPORT __attribute__((dllexport))\n#define CANOPEN_CORE_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_CORE_EXPORT __declspec(dllexport)\n#define CANOPEN_CORE_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_CORE_BUILDING_LIBRARY\n#define CANOPEN_CORE_PUBLIC CANOPEN_CORE_EXPORT\n#else\n#define CANOPEN_CORE_PUBLIC CANOPEN_CORE_IMPORT\n#endif\n#define CANOPEN_CORE_PUBLIC_TYPE CANOPEN_CORE_PUBLIC\n#define CANOPEN_CORE_LOCAL\n#else\n#define CANOPEN_CORE_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_CORE_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_CORE_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_CORE_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_CORE_PUBLIC\n#define CANOPEN_CORE_LOCAL\n#endif\n#define CANOPEN_CORE_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_CORE__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_core/launch/canopen.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nimport sys\n\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\"))  # noqa\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\", \"..\", \"launch\"))  # noqa\n\nimport launch\nimport launch.actions\nimport launch.events\n\nimport launch_ros\nimport launch_ros.events\nimport launch_ros.events.lifecycle\nfrom launch.substitutions import LaunchConfiguration, PythonExpression, TextSubstitution\nfrom launch.actions import DeclareLaunchArgument\nimport lifecycle_msgs.msg\n\n\ndef generate_launch_description():\n\n    bus_conf_arg = DeclareLaunchArgument(\n        \"bus_config\",\n        default_value=TextSubstitution(text=\"\"),\n        description=\"Path to the bus configuration to use.\",\n    )\n\n    master_conf_arg = DeclareLaunchArgument(\n        \"master_config\",\n        default_value=TextSubstitution(text=\"\"),\n        description=\"Path to the master configuration to use (dcf).\",\n    )\n\n    master_bin_arg = DeclareLaunchArgument(\n        \"master_bin\",\n        default_value=TextSubstitution(text=\"\"),\n        description=\"Path to the master configuration to use (bin).\",\n    )\n\n    can_interface_name_arg = DeclareLaunchArgument(\n        \"can_interface_name\",\n        default_value=TextSubstitution(text=\"vcan0\"),\n        description=\"CAN interface used by master and drivers.\",\n    )\n    namespace_arg = DeclareLaunchArgument(\n        \"namespace\",\n        default_value=TextSubstitution(text=\"\"),\n        description=\"Namespace for the device container node.\",\n    )\n\n    ld = launch.LaunchDescription()\n    logging = launch.actions.GroupAction(\n        actions=[\n            launch.actions.LogInfo(msg=LaunchConfiguration(\"bus_config\")),\n            launch.actions.LogInfo(msg=LaunchConfiguration(\"master_config\")),\n            launch.actions.LogInfo(msg=LaunchConfiguration(\"master_bin\")),\n            launch.actions.LogInfo(msg=LaunchConfiguration(\"can_interface_name\")),\n        ]\n    )\n    lifecycle_device_container_node = launch_ros.actions.LifecycleNode(\n        name=\"device_container_node\",\n        namespace=LaunchConfiguration(\"namespace\"),\n        package=\"canopen_core\",\n        output=\"screen\",\n        executable=\"device_container_node\",\n        parameters=[\n            {\"bus_config\": LaunchConfiguration(\"bus_config\")},\n            {\"master_config\": LaunchConfiguration(\"master_config\")},\n            {\"master_bin\": LaunchConfiguration(\"master_bin\")},\n            {\"can_interface_name\": LaunchConfiguration(\"can_interface_name\")},\n        ],\n    )\n\n    ld.add_action(bus_conf_arg)\n    ld.add_action(master_conf_arg)\n    ld.add_action(master_bin_arg)\n    ld.add_action(can_interface_name_arg)\n    ld.add_action(namespace_arg)\n    ld.add_action(logging)\n    ld.add_action(lifecycle_device_container_node)\n\n    return ld\n"
  },
  {
    "path": "canopen_core/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_core</name>\n  <version>0.3.2</version>\n  <description>Core ros2_canopen functionalities such as DeviceContainer and master</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <depend>canopen_interfaces</depend>\n  <depend>lely_core_libraries</depend>\n  <depend>lifecycle_msgs</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n  <depend>yaml_cpp_vendor</depend>\n  <depend>boost</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_core/readme.md",
    "content": "# ROS2 canopen {#mainpage}\n\nWelcome to the ROS2 canopen documentation.\n\n## About\nROS2 CANopen is being developed and maintainted by the [ROS-Industrial Consortium](rosindustrial.org). The package heavily builds on top of [Lely's canopen stack](https://opensource.lely.com/canopen/).\n\n\n## Getting started\nClone the ros2_canopen repository into your workspace's source directory and build:\n\n      git clone git@gitlab.cc-asp.fraunhofer.de:ipa326/ros-industrial/ros2_canopen.git\n\n      cd ..\n\n      colcon build\n\n      . install/setup.sh\n\nOnce built, you are ready to use the package but you need to setup the can interface.\n\n\n## Setting up your CANopen network configuration\nIn order to use the package for your CANopen network, you need to create a network configuration. We recommend the tools Lely CANopen provides for this (dcfgen). How to do this:\n\n1. Gather the EDS files for the CANopen devices connected to your network and put them into a folder.\n\n2. Create a yaml description of your network. Find an example below. Further options can be found and documentation of the yaml file structure can be found [here](https://opensource.lely.com/canopen/docs/dcf-tools/). ROS2 canopen extends the slave description by the tag driver, which specifies the driver to be used for the specific device. The driver is later loaded using pluginlib.\n\n        master:\n        node_id: 1\n\n        motioncontroller_1:\n        node_id: 2\n        dcf: \"simple.eds\"\n        driver: \"BasicDevice\"\n\n\n3. Generate a master.dcf file using Lely CANopen's dcfgen tool. This outputs a master.dcf.\n\n        dcfgen -r [path to yaml file]\n\n4. Create a ROS parameters YAML file setting the path to your created dcf and yaml file:\n\n        canopen_master:\n          ros__parameters:\n            dcf_path: [Absolute path to your master dcf]\n            yaml_path: [Absolute path to your bus yaml]\n            can_interface_name: [interface name]\n\n\n\n## ROS2 canopen (preliminary)\n1.\n\n        ros2 launch bring_up_master.launch.py parameter_file_path:=[Path to your config yaml]\n\n\n2. Set configuration files and can interface.\nsh\n\n        ros2 param set /canopen_master/dcf_path [path to dcf]\n        ros2 param set /canopen_master/yaml_path [path to yaml]\n        ros2 param set /canopen_master/can_interface_name [if_name]\n\n3. Now you can configure the canopen_master via lifecycle management. The master will now load the configuration files and spawn the necessary driver nodes for each device on the network. You can check the new nodes with ros2 node command.\n\n        ros2 lifecycle set /canopen_master configure\n        ros2 node list\n\n\n4. Configure all driver nodes with lifecycle management\n\n5. Activate canopen_master node and then all driver nodes.\n\n6. The system should now be running and you should be able to use the driver nodes to communicate with your devices.\n"
  },
  {
    "path": "canopen_core/scripts/setup_vcan.sh",
    "content": "modprobe vcan\nip link add dev vcan0 type vcan\nip link set up vcan0\n"
  },
  {
    "path": "canopen_core/src/configuration_manager.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/configuration_manager.hpp\"\n#include <stdexcept>\n\nnamespace ros2_canopen\n{\n\nvoid ConfigurationManager::init_config()\n{\n  std::string dcf_path = \"\";\n  for (YAML::const_iterator it = root_.begin(); it != root_.end(); it++)\n  {\n    std::string driver_name = it->first.as<std::string>();\n    if (driver_name != \"options\") continue;\n    YAML::Node config_node = it->second;\n    if (config_node[\"dcf_path\"])\n    {\n      dcf_path = config_node[\"dcf_path\"].as<std::string>();\n    }\n  }\n\n  for (YAML::const_iterator it = root_.begin(); it != root_.end(); it++)\n  {\n    std::string driver_name = it->first.as<std::string>();\n    if (driver_name == \"options\") continue;\n    YAML::Node config_node = it->second;\n    if (!config_node[\"dcf_path\"])\n    {\n      config_node[\"dcf_path\"] = dcf_path;\n    }\n    devices_.insert({driver_name, config_node});\n  }\n}\n\nuint32_t ConfigurationManager::get_all_devices(std::vector<std::string> & devices)\n{\n  uint32_t count = 0;\n  for (auto it = devices_.begin(); it != devices_.end(); it++)\n  {\n    devices.emplace_back(it->first);\n    count++;\n  }\n  return count;\n}\n\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_core/src/device_container.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/device_container.hpp\"\n#include \"canopen_core/device_container_error.hpp\"\n\nusing namespace ros2_canopen;\n\nvoid DeviceContainer::set_executor(const std::weak_ptr<rclcpp::Executor> executor)\n{\n  executor_ = executor;\n}\n\nbool DeviceContainer::init_driver(uint16_t node_id)\n{\n  RCLCPP_DEBUG(this->get_logger(), \"init_driver\");\n  registered_drivers_[node_id]->set_master(\n    this->can_master_->get_executor(), this->can_master_->get_master());\n  return true;\n}\n\nbool DeviceContainer::load_component(\n  const std::string package_name, const std::string driver_name, const uint16_t node_id,\n  const std::string node_name, std::vector<rclcpp::Parameter> & params,\n  const std::string node_namespace)\n{\n  ComponentResource component;\n  std::string resource_index(\"rclcpp_components\");\n  std::vector<ComponentResource> components =\n    this->get_component_resources(package_name, resource_index);\n  for (auto it = components.begin(); it != components.end(); ++it)\n  {\n    if (it->first.compare(driver_name) == 0)\n    {\n      std::shared_ptr<rclcpp_components::NodeFactory> factory_node =\n        this->create_component_factory(*it);\n      rclcpp::NodeOptions opts;\n      opts.use_global_arguments(false);\n      opts.use_intra_process_comms(true);\n      std::vector<std::string> remap_rules;\n\n      remap_rules.push_back(\"--ros-args\");\n      // remap_rules.push_back(\"--log-level\");\n      // remap_rules.push_back(\"debug\");\n      remap_rules.push_back(\"-r\");\n      remap_rules.push_back(\"__node:=\" + node_name);\n\n      // Prefer node_namespace if provided, else fallback to container namespace\n      std::string canopen_ns = node_namespace.empty() ? this->get_namespace() : node_namespace;\n      remap_rules.push_back(\"-r\");\n      remap_rules.push_back(\"__ns:=\" + canopen_ns);\n\n      if (node_namespace.empty())\n      {\n        RCLCPP_WARN(\n          this->get_logger(), \"Namespace not provided for node '%s', using container namespace: %s\",\n          node_name.c_str(), canopen_ns.c_str());\n      }\n      else\n      {\n        RCLCPP_INFO(\n          this->get_logger(), \"Namespace set for node '%s': %s\", node_name.c_str(),\n          node_namespace.c_str());\n      }\n      opts.arguments(remap_rules);\n      opts.parameter_overrides(params);\n\n      try\n      {\n        auto wrapper = factory_node->create_node_instance(opts);\n        if (node_name.compare(\"master\") == 0)\n        {\n          RCLCPP_INFO(this->get_logger(), \"Load master component.\");\n          can_master_ =\n            std::static_pointer_cast<CanopenMasterInterface>(wrapper.get_node_instance());\n        }\n        else\n        {\n          RCLCPP_INFO(this->get_logger(), \"Load driver component.\");\n          if (this->lifecycle_operation_)\n          {\n            auto node =\n              std::static_pointer_cast<CanopenDriverInterface>(wrapper.get_node_instance());\n            if (!node->is_lifecycle())\n            {\n              std::string execption_string;\n              execption_string.append(\"Driver \");\n              execption_string.append(driver_name);\n              execption_string.append(\" for device \");\n              execption_string.append(node_name);\n              execption_string.append(\" is not a lifecycle driver while the master is.\");\n              RCLCPP_ERROR(this->get_logger(), execption_string.c_str());\n              throw DeviceContainerException(execption_string);\n            }\n            else\n            {\n              registered_drivers_[node_id] = node;\n            }\n          }\n          else\n          {\n            auto node =\n              std::static_pointer_cast<CanopenDriverInterface>(wrapper.get_node_instance());\n            if (node->is_lifecycle())\n            {\n              std::string execption_string;\n              execption_string.append(\"Driver \");\n              execption_string.append(driver_name);\n              execption_string.append(\" for device \");\n              execption_string.append(node_name);\n              execption_string.append(\" is a lifecycle driver while the master is not.\");\n              RCLCPP_ERROR(this->get_logger(), execption_string.c_str());\n              throw DeviceContainerException(execption_string);\n            }\n            else\n            {\n              registered_drivers_[node_id] = node;\n            }\n          }\n        }\n      }\n      catch (const std::exception & ex)\n      {\n        // In the case that the component constructor throws an exception,\n        // rethrow into the following catch block.\n        throw DeviceContainerException(\n          \"Component constructor threw an exception: \" + std::string(ex.what()));\n      }\n      catch (...)\n      {\n        // In the case that the component constructor throws an exception,\n        // rethrow into the following catch block.\n        throw DeviceContainerException(\"Component constructor threw an exception\");\n      }\n\n      return true;\n    }\n  }\n  return false;\n}\n\nvoid DeviceContainer::configure()\n{\n  if (!this->get_parameter(\"can_interface_name\", can_interface_name_))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter can_interface_name could not be read.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n  if (!this->get_parameter(\"master_config\", dcf_txt_))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter master_config could not be read.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n  if (!this->get_parameter(\"master_bin\", dcf_bin_))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter master_bin could not be read.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n\n  if (!this->get_parameter(\"bus_config\", bus_config_))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter bus_config could not be read.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n\n  if (can_interface_name_.length() == 0)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter can_interface_name was not set.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n\n  if (dcf_txt_.length() == 0)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter master_config was not set.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n\n  if (bus_config_.length() == 0)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Parameter bus_config was not set.\");\n    throw DeviceContainerException(\"Fatal: Getting Parameter failed.\");\n  }\n\n  RCLCPP_INFO(this->get_logger(), \"Starting Device Container with:\");\n  RCLCPP_INFO(this->get_logger(), \"\\t master_config %s\", dcf_txt_.c_str());\n  RCLCPP_INFO(this->get_logger(), \"\\t bus_config %s\", bus_config_.c_str());\n  RCLCPP_INFO(this->get_logger(), \"\\t can_interface_name %s\", can_interface_name_.c_str());\n\n  try\n  {\n    this->config_ = std::make_unique<ros2_canopen::ConfigurationManager>(bus_config_);\n    this->config_->init_config();\n  }\n  catch (const std::exception & e)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Loading bus configuration %s failed\", bus_config_.c_str());\n    throw DeviceContainerException(\"Fatal: Loading bus configuration \" + bus_config_ + \" failed.\");\n  }\n}\n\nbool DeviceContainer::load_master()\n{\n  RCLCPP_INFO(this->get_logger(), \"Loading Master Configuration.\");\n  std::vector<std::string> devices;\n  uint32_t count = this->config_->get_all_devices(devices);\n  if (count == 0)\n  {\n    return false;\n  }\n  bool master_found = false;\n\n  // Find master in configuration\n  for (auto it = devices.begin(); it != devices.end(); it++)\n  {\n    if (it->find(\"master\") != std::string::npos && !master_found)\n    {\n      auto node_id = config_->get_entry<uint16_t>(*it, \"node_id\");\n      auto driver_name = config_->get_entry<std::string>(*it, \"driver\");\n      auto package_name = config_->get_entry<std::string>(*it, \"package\");\n      auto node_namespace = config_->get_entry<std::string>(*it, \"namespace\").value_or(\"\");\n      if (!node_id.has_value() || !driver_name.has_value() || !package_name.has_value())\n      {\n        RCLCPP_ERROR(\n          this->get_logger(), \"Error: Bus Configuration has incomplete configuration for master\");\n        return false;\n      }\n      std::vector<rclcpp::Parameter> params;\n      params.push_back(rclcpp::Parameter(\"container_name\", this->get_fully_qualified_name()));\n      params.push_back(rclcpp::Parameter(\"master_dcf\", this->dcf_txt_));\n      params.push_back(rclcpp::Parameter(\"master_bin\", this->dcf_bin_));\n      params.push_back(rclcpp::Parameter(\"can_interface_name\", this->can_interface_name_));\n      params.push_back(rclcpp::Parameter(\"node_id\", (int)node_id.value()));\n      params.push_back(rclcpp::Parameter(\"non_transmit_timeout\", 100));\n      params.push_back(rclcpp::Parameter(\"config\", config_->dump_device(*it)));\n\n      if (!this->load_component(\n            package_name.value(), driver_name.value(), node_id.value(), *it, params,\n            node_namespace))\n      {\n        RCLCPP_ERROR(this->get_logger(), \"Error: Loading master failed.\");\n        return false;\n      }\n\n      add_node_to_executor(can_master_->get_node_base_interface());\n      can_master_->init();\n      master_found = true;\n      can_master_id_ = node_id.value();\n      this->lifecycle_operation_ = can_master_->is_lifecycle();\n    }\n  }\n\n  if (!master_found)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Error: Master not in configuration\");\n    return false;\n  }\n  return true;\n}\n\nbool DeviceContainer::load_drivers()\n{\n  RCLCPP_INFO(this->get_logger(), \"Loading Driver Configuration.\");\n  std::vector<std::string> devices;\n  uint32_t count = this->config_->get_all_devices(devices);\n  if (count == 0)\n  {\n    return false;\n  }\n\n  for (auto it = devices.begin(); it != devices.end(); it++)\n  {\n    if (it->find(\"master\") == std::string::npos && it->find(\"options\") == std::string::npos)\n    {\n      auto node_id = config_->get_entry<uint16_t>(*it, \"node_id\");\n      auto driver_name = config_->get_entry<std::string>(*it, \"driver\");\n      auto package_name = config_->get_entry<std::string>(*it, \"package\");\n      auto node_namespace = config_->get_entry<std::string>(*it, \"namespace\").value_or(\"\");\n      if (!node_id.has_value() || !driver_name.has_value() || !package_name.has_value())\n      {\n        RCLCPP_ERROR(\n          this->get_logger(), \"Error: Bus Configuration has incomplete configuration for %s\",\n          it->c_str());\n        return false;\n      }\n\n      if (node_id.value() == can_master_id_)\n      {\n        RCLCPP_ERROR(\n          this->get_logger(), \"Error: Bus Configuration has duplicate entry for node id %i\",\n          node_id.value());\n        return false;\n      }\n\n      if (registered_drivers_.count(node_id.value()) != 0)\n      {\n        RCLCPP_ERROR(\n          this->get_logger(), \"Error: Bus Configuration has duplicate entry for node id %i\",\n          node_id.value());\n        return false;\n      }\n\n      RCLCPP_INFO(\n        this->get_logger(), \"Found device %s with driver %s\", it->c_str(),\n        driver_name.value().c_str());\n\n      std::vector<rclcpp::Parameter> params;\n      params.push_back(rclcpp::Parameter(\"container_name\", this->get_fully_qualified_name()));\n      params.push_back(rclcpp::Parameter(\"node_id\", (int)node_id.value()));\n      params.push_back(rclcpp::Parameter(\"config\", config_->dump_device(*it)));\n      params.push_back(rclcpp::Parameter(\"non_transmit_timeout\", 100));\n\n      if (!this->load_component(\n            package_name.value(), driver_name.value(), node_id.value(), *it, params,\n            node_namespace))\n      {\n        RCLCPP_ERROR(\n          this->get_logger(),\n          \"Loading driver failed: node_id(%hu), node_name(%s), driver(%s), driver_package(%s)\",\n          node_id.value(), it->c_str(), driver_name.value().c_str(), package_name.value().c_str());\n        return false;\n      }\n      add_node_to_executor(registered_drivers_[node_id.value()]->get_node_base_interface());\n      registered_drivers_[node_id.value()]->init();\n    }\n  }\n  return true;\n}\n\nbool DeviceContainer::load_manager()\n{\n  if (this->lifecycle_operation_)\n  {\n    RCLCPP_INFO(this->get_logger(), \"Loading Manager Configuration.\");\n    auto node_options = rclcpp::NodeOptions();\n    node_options.use_global_arguments(false);\n\n    // Set parameters\n    rclcpp::Parameter container_name(\"container_name\", this->get_fully_qualified_name());\n    std::vector<rclcpp::Parameter> params;\n    params.push_back(container_name);\n    node_options.parameter_overrides(params);\n\n    // Instantiate Manager\n    this->lifecycle_manager_ = std::make_unique<ros2_canopen::LifecycleManager>(node_options);\n\n    // Add to executor\n    add_node_to_executor(this->lifecycle_manager_->get_node_base_interface());\n\n    // Initialise based on configuration file.\n    this->lifecycle_manager_->init(this->config_);\n  }\n  return true;\n}\n\nvoid DeviceContainer::init()\n{\n  configure();\n  if (!this->load_master())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Master Failed.\");\n  }\n  if (!this->load_drivers())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Drivers Failed.\");\n  }\n\n  if (!this->load_manager())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Manager Failed.\");\n  }\n}\n\nvoid DeviceContainer::init(\n  const std::string & can_interface_name, const std::string & master_config,\n  const std::string & bus_config, const std::string & master_bin)\n{\n  can_interface_name_ = can_interface_name;\n  dcf_txt_ = master_config;\n  dcf_bin_ = master_bin;\n  bus_config_ = bus_config;\n\n  RCLCPP_INFO(this->get_logger(), \"Starting Device Container with:\");\n  RCLCPP_INFO(this->get_logger(), \"\\t can_interface_name %s\", can_interface_name_.c_str());\n  RCLCPP_INFO(this->get_logger(), \"\\t master_config %s\", dcf_txt_.c_str());\n  RCLCPP_INFO(this->get_logger(), \"\\t bus_config %s\", bus_config_.c_str());\n\n  this->config_ = std::make_unique<ros2_canopen::ConfigurationManager>(bus_config_);\n  this->config_->init_config();\n\n  if (!this->load_master())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Master Failed.\");\n  }\n  if (!this->load_drivers())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Drivers Failed.\");\n  }\n\n  if (!this->load_manager())\n  {\n    throw DeviceContainerException(\"Fatal: Loading Manager Failed.\");\n  }\n}\n\nvoid DeviceContainer::on_list_nodes(\n  const std::shared_ptr<rmw_request_id_t> request_header,\n  const std::shared_ptr<ListNodes::Request> request, std::shared_ptr<ListNodes::Response> response)\n{\n  auto components = list_components();\n  for (auto it = components.begin(); it != components.end(); ++it)\n  {\n    RCLCPP_INFO(this->get_logger(), \"%hu - %s\", it->first, it->second.c_str());\n    response->unique_ids.push_back((uint64_t)it->first);\n    response->full_node_names.push_back(it->second);\n  }\n}\n\nstd::map<uint16_t, std::string> DeviceContainer::list_components()\n{\n  std::map<uint16_t, std::string> components;\n\n  components[can_master_id_] = can_master_->get_node_base_interface()->get_fully_qualified_name();\n\n  if (this->lifecycle_operation_)\n  {\n    components[256] = lifecycle_manager_->get_node_base_interface()->get_fully_qualified_name();\n  }\n\n  for (auto & driver : registered_drivers_)\n  {\n    components[driver.first] = driver.second->get_node_base_interface()->get_fully_qualified_name();\n  }\n\n  return components;\n}\n\n// int main(int argc, char const *argv[])\n// {\n//     rclcpp::init(argc, argv);\n//     auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n//     auto lifecycle_device_container_node = std::make_shared<DeviceContainer>(exec);\n//     exec->add_node(lifecycle_device_container_node);\n//     std::thread spinThread([&exec]()\n//                            { exec->spin(); });\n//     std::this_thread::sleep_for(100ms);\n//     if (lifecycle_device_container_node->init())\n//     {\n//         RCLCPP_INFO(lifecycle_device_container_node->get_logger(), \"Initialisation successful.\");\n//     }\n//     else\n//     {\n//         RCLCPP_INFO(lifecycle_device_container_node->get_logger(), \"Initialisation failed.\");\n//     }\n\n//     spinThread.join();\n//     return 0;\n// }\n\n// bool DeviceContainer::set_remote_paramter(std::string node_name, rclcpp::Parameter &param)\n// {\n//     std::string service_name = node_name + \"/set_parameters\";\n//     rclcpp::Client<rcl_interfaces::srv::SetParameters>::SharedPtr set_parameter_client;\n\n//     set_parameter_client = node_->create_client<rcl_interfaces::srv::SetParameters>(\n//         service_name);\n\n//     while (!set_parameter_client->wait_for_service(non_transmit_timeout_))\n//     {\n//         if (!rclcpp::ok())\n//         {\n//             RCLCPP_ERROR(node_->get_logger(), \"Interrupted while waiting for init_driver service.\n//             Exiting.\");\n//         }\n//         RCLCPP_INFO(node_->get_logger(), \"init_driver service not available, waiting again...\");\n//     }\n//     auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();\n//     request->parameters.push_back(param.to_parameter_msg());\n\n//     auto future_result = demand_set_master_client->async_send_request(request);\n\n//     auto future_status = future_result.wait_for(std::chrono::milliseconds(1000));\n//     RCLCPP_DEBUG(node_->get_logger(), \"demand_set_master end\");\n\n//     if (future_status == std::future_status::ready)\n//     {\n//         future_result.get();\n//     }\n// }\n"
  },
  {
    "path": "canopen_core/src/device_container_error.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/device_container_error.hpp\"\n#include <cstring>\nnamespace ros2_canopen\n{\n\nchar * DeviceContainerException::what()\n{\n  char * res = new char[1000];\n  strcpy(res, what_.c_str());\n  return res;\n}\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_core/src/device_container_node.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/device_container.hpp\"\n\nusing namespace ros2_canopen;\n\nint main(int argc, char const * argv[])\n{\n  rclcpp::init(argc, argv);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto device_container = std::make_shared<DeviceContainer>(exec);\n  std::thread spinThread([&device_container]() { device_container->init(); });\n  exec->add_node(device_container);\n  exec->spin();\n  spinThread.join();\n  device_container->shutdown();\n  rclcpp::shutdown();\n  return 0;\n}\n"
  },
  {
    "path": "canopen_core/src/driver_error.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/driver_error.hpp\"\n#include <cstring>\nnamespace ros2_canopen\n{\nchar * DriverException::what()\n{\n  char * res = new char[1000];\n  strcpy(res, what_.c_str());\n  return res;\n}\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_core/src/driver_node.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/driver_node.hpp\"\n\nusing namespace ros2_canopen;\nvoid CanopenDriver::init()\n{\n  node_canopen_driver_->init();\n  node_canopen_driver_->configure();\n  bool success = false;\n  for (int i = 0; i < 5; i++)\n  {\n    try\n    {\n      node_canopen_driver_->demand_set_master();\n      success = true;\n      break;\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_WARN(\n        this->get_logger(), \"Failed to get demand set master result becauss %s. Retrying.\",\n        e.what());\n    }\n  }\n  if (!success)\n  {\n    RCLCPP_WARN(this->get_logger(), \"Failed to get demand set master result. Exiting...\");\n    throw DriverException(\"Failed to get demand set master result. Exiting...\");\n  }\n  node_canopen_driver_->activate();\n}\n\nvoid CanopenDriver::shutdown() { node_canopen_driver_->shutdown(); }\n\nvoid CanopenDriver::set_master(\n  std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master)\n{\n  node_canopen_driver_->set_master(exec, master);\n}\n\nvoid LifecycleCanopenDriver::init() { node_canopen_driver_->init(); }\n\nvoid LifecycleCanopenDriver::shutdown() { node_canopen_driver_->shutdown(); }\n\nvoid LifecycleCanopenDriver::set_master(\n  std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master)\n{\n  node_canopen_driver_->set_master(exec, master);\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenDriver::on_configure(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_driver_->configure();\n  bool success = false;\n  for (int i = 0; i < 5; i++)\n  {\n    try\n    {\n      node_canopen_driver_->demand_set_master();\n      success = true;\n      break;\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_WARN(\n        this->get_logger(), \"Failed to get demand set master result becauss %s. Retrying.\",\n        e.what());\n    }\n  }\n  if (!success)\n  {\n    RCLCPP_WARN(this->get_logger(), \"Failed to get demand set master result. Exiting...\");\n    throw DriverException(\"Failed to get demand set master result. Exiting...\");\n  }\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenDriver::on_activate(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_driver_->activate();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenDriver::on_deactivate(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_driver_->deactivate();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenDriver::on_cleanup(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_driver_->cleanup();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenDriver::on_shutdown(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_driver_->shutdown();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n"
  },
  {
    "path": "canopen_core/src/lifecycle_manager.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/lifecycle_manager.hpp\"\n\nnamespace ros2_canopen\n{\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleManager::on_configure(const rclcpp_lifecycle::State & state)\n{\n  this->get_parameter<std::string>(\"container_name\", this->container_name_);\n\n  bool res = this->load_from_config();\n  if (!res)\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Failed to load from config\");\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;\n  }\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleManager::on_activate(const rclcpp_lifecycle::State & state)\n{\n  if (!this->bring_up_all())\n  {\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;\n  }\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleManager::on_deactivate(const rclcpp_lifecycle::State & state)\n{\n  if (!this->bring_down_all())\n  {\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;\n  }\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleManager::on_cleanup(const rclcpp_lifecycle::State & state)\n{\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleManager::on_shutdown(const rclcpp_lifecycle::State & state)\n{\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nvoid LifecycleManager::init(std::shared_ptr<ros2_canopen::ConfigurationManager> config)\n{\n  this->config_ = config;\n}\n\nbool LifecycleManager::load_from_config()\n{\n  std::vector<std::string> devices;\n  uint32_t count = this->config_->get_all_devices(devices);\n  RCLCPP_INFO(this->get_logger(), \"Configuring for %u devices.\", count);\n\n  // Find master in configuration\n  for (auto it = devices.begin(); it != devices.end(); it++)\n  {\n    uint8_t node_id = config_->get_entry<uint8_t>(*it, \"node_id\").value();\n    std::string change_state_client_name = *it;\n    std::string get_state_client_name = *it;\n    get_state_client_name += \"/get_state\";\n    change_state_client_name += \"/change_state\";\n    RCLCPP_INFO(this->get_logger(), \"Found %s (node_id=%hu)\", it->c_str(), node_id);\n    device_names_to_ids.emplace(*it, node_id);\n    rclcpp::Client<lifecycle_msgs::srv::GetState>::SharedPtr get_state_client =\n      this->create_client<lifecycle_msgs::srv::GetState>(\n        get_state_client_name, rclcpp::QoS(10), cbg_clients);\n\n    rclcpp::Client<lifecycle_msgs::srv::ChangeState>::SharedPtr change_state_client =\n      this->create_client<lifecycle_msgs::srv::ChangeState>(\n        change_state_client_name, rclcpp::QoS(10), cbg_clients);\n\n    this->drivers_get_state_clients.emplace(node_id, get_state_client);\n    this->drivers_change_state_clients.emplace(node_id, change_state_client);\n\n    if (it->find(\"master\") != std::string::npos)\n    {\n      this->master_id_ = node_id;\n    }\n  }\n  return true;\n}\n\nunsigned int LifecycleManager::get_state(uint8_t node_id, std::chrono::seconds time_out)\n{\n  auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();\n  auto client = this->drivers_get_state_clients[node_id];\n  if (!client->wait_for_service(time_out))\n  {\n    RCLCPP_ERROR(get_logger(), \"Service %s is not available.\", client->get_service_name());\n    return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;\n  }\n\n  // We send the service request for asking the current\n  // state of the lc_talker node.\n  auto future_result = client->async_send_request(request);\n\n  // Let's wait until we have the answer from the node.\n  // If the request times out, we return an unknown state.\n  auto future_status = wait_for_result(future_result, time_out);\n\n  if (future_status != std::future_status::ready)\n  {\n    RCLCPP_ERROR(\n      get_logger(), \"Server time out while getting current state for node 0x%X\", node_id);\n    return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;\n  }\n  auto result = future_result.get()->current_state;\n  return result.id;\n}\n\nbool LifecycleManager::change_state(\n  uint8_t node_id, uint8_t transition, std::chrono::seconds time_out)\n{\n  auto client = this->drivers_change_state_clients[node_id];\n  auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();\n  request->transition.id = transition;\n  if (!client->wait_for_service(time_out))\n  {\n    RCLCPP_ERROR(get_logger(), \"Service %s is not available.\", client->get_service_name());\n    return false;\n  }\n\n  // We send the request with the transition we want to invoke.\n  auto future_result = client->async_send_request(request);\n\n  // Let's wait until we have the answer from the node.\n  // If the request times out, we return an unknown state.\n  auto future_status = wait_for_result(future_result, time_out);\n\n  if (future_status != std::future_status::ready)\n  {\n    RCLCPP_ERROR(\n      get_logger(), \"Server time out while getting current state for node 0x%X\", node_id);\n    return false;\n  }\n\n  if (future_result.get()->success)\n  {\n    return true;\n  }\n  else\n  {\n    RCLCPP_WARN(\n      get_logger(), \"Failed to trigger transition %u\", static_cast<unsigned int>(transition));\n    return false;\n  }\n  return false;\n}\n\nbool LifecycleManager::bring_up_master()\n{\n  auto state = this->get_state(master_id_, 3s);\n  if (state != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)\n  {\n    RCLCPP_ERROR(\n      this->get_logger(), \"Failed to bring up master. Master not in unconfigured state.\");\n    return false;\n  }\n  RCLCPP_DEBUG(this->get_logger(), \"Master (node_id=%hu) has state unconfigured.\", master_id_);\n  if (!this->change_state(master_id_, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE, 3s))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Failed to bring up master. Configure Transition failed.\");\n    return false;\n  }\n  RCLCPP_DEBUG(this->get_logger(), \"Master (node_id=%hu) has state inactive.\", master_id_);\n  if (!this->change_state(master_id_, lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE, 3s))\n  {\n    RCLCPP_ERROR(this->get_logger(), \"Failed to bring up master. Activate Transition failed.\");\n    return false;\n  }\n  RCLCPP_DEBUG(this->get_logger(), \"Master (node_id=%hu) has state active.\", master_id_);\n  return true;\n}\n\nbool LifecycleManager::bring_down_master()\n{\n  this->change_state(master_id_, lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE, 3s);\n  this->change_state(master_id_, lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP, 3s);\n\n  auto state = this->get_state(master_id_, 3s);\n\n  if (state != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)\n  {\n    return false;\n  }\n\n  return true;\n}\n\nbool LifecycleManager::bring_up_driver(std::string device_name)\n{\n  auto node_id = this->device_names_to_ids[device_name];\n  RCLCPP_DEBUG(this->get_logger(), \"Bringing up %s with id %u\", device_name.c_str(), node_id);\n  auto master_state = this->get_state(master_id_, 3s);\n  if (master_state != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)\n  {\n    RCLCPP_ERROR(\n      this->get_logger(), \"Failed to bring up %s. Master not in active state.\",\n      device_name.c_str());\n    return false;\n  }\n  auto state = this->get_state(node_id, 3s);\n  if (state != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)\n  {\n    RCLCPP_ERROR(\n      this->get_logger(), \"Failed to bring up %s. Not in unconfigured state.\", device_name.c_str());\n    return false;\n  }\n  RCLCPP_DEBUG(\n    this->get_logger(), \"%s (node_id=%hu) has state unconfigured. Attempting to configure.\",\n    device_name.c_str(), node_id);\n  if (!this->change_state(node_id, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE, 3s))\n  {\n    RCLCPP_ERROR(\n      this->get_logger(), \"Failed to bring up %s. Configure Transition failed.\",\n      device_name.c_str());\n    return false;\n  }\n  RCLCPP_DEBUG(\n    this->get_logger(), \"%s (node_id=%hu) has state inactive. Attempting to activate.\",\n    device_name.c_str(), node_id);\n  if (!this->change_state(node_id, lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE, 3s))\n  {\n    RCLCPP_ERROR(\n      this->get_logger(), \"Failed to bring up %s. Activate Transition failed.\",\n      device_name.c_str());\n    return false;\n  }\n  RCLCPP_DEBUG(\n    this->get_logger(), \"%s (node_id=%hu) has state active.\", device_name.c_str(), node_id);\n  return true;\n}\n\nbool LifecycleManager::bring_down_driver(std::string device_name)\n{\n  auto node_id = this->device_names_to_ids[device_name];\n\n  this->change_state(node_id, lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE, 3s);\n  this->change_state(node_id, lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP, 3s);\n  auto state = this->get_state(node_id, 3s);\n  if (state != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)\n  {\n    return false;\n  }\n  return true;\n}\n\nbool LifecycleManager::bring_up_all()\n{\n  if (!this->bring_up_master())\n  {\n    return false;\n  }\n  for (auto it = this->device_names_to_ids.begin(); it != this->device_names_to_ids.end(); ++it)\n  {\n    if (it->first.find(\"master\") == std::string::npos)\n    {\n      if (!this->bring_up_driver(it->first))\n      {\n        return false;\n      }\n    }\n    else\n    {\n      RCLCPP_DEBUG(this->get_logger(), \"Skipped master.\");\n    }\n  }\n  return true;\n}\n\nbool LifecycleManager::bring_down_all()\n{\n  RCLCPP_INFO(this->get_logger(), \"Bring Down all\");\n  for (auto it = this->device_names_to_ids.begin(); it != this->device_names_to_ids.end(); ++it)\n  {\n    if (it->first.compare(\"master\") != 0)\n    {\n      if (!this->bring_down_driver(it->first))\n      {\n        return false;\n      }\n    }\n  }\n  if (!this->bring_down_master())\n  {\n    return false;\n  }\n\n  return true;\n}\n\n}  // namespace ros2_canopen\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleManager)\n"
  },
  {
    "path": "canopen_core/src/master_error.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/master_error.hpp\"\n#include <cstring>\nnamespace ros2_canopen\n{\n\nchar * MasterException::what()\n{\n  char * res = new char[1000];\n  strcpy(res, what_.c_str());\n  return res;\n}\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_core/src/master_node.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/master_node.hpp\"\n\nusing namespace ros2_canopen;\n\nvoid CanopenMaster::init()\n{\n  node_canopen_master_->init();\n  node_canopen_master_->configure();\n  node_canopen_master_->activate();\n}\nvoid CanopenMaster::shutdown() { node_canopen_master_->shutdown(); }\n\nstd::shared_ptr<lely::canopen::AsyncMaster> CanopenMaster::get_master()\n{\n  return node_canopen_master_->get_master();\n}\n\nstd::shared_ptr<lely::ev::Executor> CanopenMaster::get_executor()\n{\n  return node_canopen_master_->get_executor();\n}\n\nvoid LifecycleCanopenMaster::init() { node_canopen_master_->init(); }\n\nvoid LifecycleCanopenMaster::shutdown() { node_canopen_master_->shutdown(); }\n\nstd::shared_ptr<lely::canopen::AsyncMaster> LifecycleCanopenMaster::get_master()\n{\n  return node_canopen_master_->get_master();\n}\n\nstd::shared_ptr<lely::ev::Executor> LifecycleCanopenMaster::get_executor()\n{\n  return node_canopen_master_->get_executor();\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenMaster::on_configure(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_master_->configure();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenMaster::on_activate(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_master_->activate();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenMaster::on_deactivate(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_master_->deactivate();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenMaster::on_cleanup(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_master_->cleanup();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n\nrclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn\nLifecycleCanopenMaster::on_shutdown(const rclcpp_lifecycle::State & state)\n{\n  node_canopen_master_->shutdown();\n  return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n}\n"
  },
  {
    "path": "canopen_core/src/node_interfaces/node_canopen_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#include \"canopen_core/node_interfaces/node_canopen_driver.hpp\"\nusing namespace std::chrono_literals;\n\ntemplate <>\nvoid ros2_canopen::node_interfaces::NodeCanopenDriver<rclcpp::Node>::demand_set_master()\n{\n  RCLCPP_DEBUG(node_->get_logger(), \"demand_set_master_start\");\n  if (!configured_.load())\n  {\n    throw ros2_canopen::DriverException(\"Set Master: driver is not configured\");\n  }\n  std::string init_service_name = container_name_ + \"/init_driver\";\n  RCLCPP_DEBUG(node_->get_logger(), \"Service: %s\", init_service_name.c_str());\n  rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr demand_set_master_client;\n  // demand_set_master_client;\n  demand_set_master_client = node_->create_client<canopen_interfaces::srv::CONode>(\n    init_service_name, rclcpp::QoS(10), client_cbg_);\n\n  while (!demand_set_master_client->wait_for_service(non_transmit_timeout_))\n  {\n    if (!rclcpp::ok())\n    {\n      RCLCPP_ERROR(\n        node_->get_logger(), \"Interrupted while waiting for init_driver service. Exiting.\");\n    }\n    RCLCPP_INFO(node_->get_logger(), \"init_driver service not available, waiting again...\");\n  }\n  auto request = std::make_shared<canopen_interfaces::srv::CONode::Request>();\n  request->nodeid = node_id_;\n\n  auto future_result = demand_set_master_client->async_send_request(request);\n\n  auto future_status = future_result.wait_for(non_transmit_timeout_);\n  RCLCPP_DEBUG(node_->get_logger(), \"demand_set_master end\");\n\n  if (future_status == std::future_status::ready)\n  {\n    future_result.get();\n  }\n  else\n  {\n    RCLCPP_ERROR(node_->get_logger(), \"Could not get result.\");\n    throw DriverException(\"Could not get result.\");\n  }\n}\n\ntemplate <>\nvoid ros2_canopen::node_interfaces::NodeCanopenDriver<\n  rclcpp_lifecycle::LifecycleNode>::demand_set_master()\n{\n  RCLCPP_DEBUG(node_->get_logger(), \"demand_set_master_start\");\n  if (!configured_.load())\n  {\n    throw ros2_canopen::DriverException(\"Set Master: driver is not configured\");\n  }\n  std::string init_service_name = container_name_ + \"/init_driver\";\n  rclcpp::Client<canopen_interfaces::srv::CONode>::SharedPtr demand_set_master_client;\n  // demand_set_master_client;\n  demand_set_master_client = node_->create_client<canopen_interfaces::srv::CONode>(\n    init_service_name, rclcpp::QoS(10), client_cbg_);\n\n  while (!demand_set_master_client->wait_for_service(non_transmit_timeout_))\n  {\n    if (!rclcpp::ok())\n    {\n      RCLCPP_ERROR(\n        node_->get_logger(), \"Interrupted while waiting for init_driver service. Exiting.\");\n    }\n    RCLCPP_INFO(node_->get_logger(), \"init_driver service not available, waiting again...\");\n  }\n  auto request = std::make_shared<canopen_interfaces::srv::CONode::Request>();\n  request->nodeid = node_id_;\n\n  auto future_result = demand_set_master_client->async_send_request(request);\n\n  auto future_status = future_result.wait_for(non_transmit_timeout_);\n  RCLCPP_DEBUG(node_->get_logger(), \"demand_set_master end\");\n\n  if (future_status == std::future_status::ready)\n  {\n    future_result.get();\n  }\n  else\n  {\n    RCLCPP_ERROR(node_->get_logger(), \"Could not get result.\");\n    throw DriverException(\"Could not get result.\");\n  }\n}\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopenDriver<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopenDriver<rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_core/src/node_interfaces/node_canopen_master.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/node_interfaces/node_canopen_master.hpp\"\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopenMaster<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopenMaster<rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_core/test/CMakeLists.txt",
    "content": "ament_add_gmock(test_node_canopen_driver\n    test_node_canopen_driver.cpp\n)\ntarget_include_directories(test_node_canopen_driver PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_canopen_driver\n    ${canopen_interfaces_TARGETS}\n    node_canopen_driver\n    rclcpp::rclcpp\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\nament_add_gmock(test_node_canopen_master\n  test_node_canopen_master.cpp\n)\ntarget_include_directories(test_node_canopen_master PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_canopen_master\n    ${canopen_interfaces_TARGETS}\n    node_canopen_master\n    rclcpp::rclcpp\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\n# Temporary fixing ci build stability\nif(DEVICE_CONTAINER_TESTING)\nament_add_gmock(test_device_container\n  test_device_container.cpp\n)\ntarget_include_directories(test_device_container PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_device_container\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    device_container\n    node_canopen_driver\n    node_canopen_master\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n)\nendif()\n\nfile(COPY bus_configs DESTINATION ${CMAKE_CURRENT_BINARY_DIR})\n\nament_add_gmock(test_canopen_driver\ntest_canopen_driver.cpp\n)\ntarget_include_directories(test_canopen_driver PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_canopen_driver\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    node_canopen_driver\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\nament_add_gmock(test_lifecycle_canopen_driver\ntest_lifecycle_canopen_driver.cpp\n)\ntarget_include_directories(test_lifecycle_canopen_driver PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_lifecycle_canopen_driver\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    node_canopen_driver\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\nament_add_gmock(test_canopen_master\ntest_canopen_master.cpp\n)\ntarget_include_directories(test_canopen_master PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_canopen_master\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    node_canopen_master\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\nament_add_gmock(test_lifecycle_canopen_master\ntest_lifecycle_canopen_master.cpp\n)\ntarget_include_directories(test_lifecycle_canopen_master PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_lifecycle_canopen_master\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    node_canopen_master\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n    yaml-cpp\n)\n\nament_add_gmock(test_lifecycle_manager\ntest_lifecycle_manager.cpp\n)\ntarget_include_directories(test_lifecycle_manager PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_lifecycle_manager\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    device_container\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n)\n\nament_add_gmock(test_errors\ntest_errors.cpp\n)\ntarget_include_directories(test_errors PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_errors\n    ${canopen_interfaces_TARGETS}\n    ${lifecycle_msgs_TARGETS}\n    device_container\n    node_canopen_driver\n    node_canopen_master\n    rclcpp::rclcpp\n    rclcpp_components::component\n    rclcpp_components::component_manager\n    rclcpp_lifecycle::rclcpp_lifecycle\n)\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_driver_duplicate.yml",
    "content": "---\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_driver_no_driver.yml",
    "content": "---\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_driver_no_id.yml",
    "content": "---\nproxy_device_1:\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_driver_no_package.yml",
    "content": "---\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_master_no_driver.yml",
    "content": "---\nmaster:\n  node_id: 1\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_master_no_id.yml",
    "content": "---\nmaster:\n  driver: \"ros2_canopen::CanopenMaster\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_master_no_package.yml",
    "content": "---\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::CanopenMaster\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/bad_no_master.yml",
    "content": "---\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n\nproxy_device_2:\n  node_id: 3\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/good_driver.yml",
    "content": "---\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/good_master.yml",
    "content": "---\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::CanopenMaster\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/bus_configs/good_master_and_two_driver.yml",
    "content": "---\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::CanopenMaster\"\n  package: \"canopen_core\"\n\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n\nproxy_device_2:\n  node_id: 3\n  dcf: \"simple.eds\"\n  dcf_path: \"install/canopen_tests/share/canopen_tests/config/simple\"\n  driver: \"ros2_canopen::CanopenDriver\"\n  package: \"canopen_core\"\n"
  },
  {
    "path": "canopen_core/test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=2\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=32\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1A00\n20=0x1A01\n21=0x1F25\n22=0x1F55\n23=0x1F80\n24=0x1F81\n25=0x1F82\n26=0x1F84\n27=0x1F85\n28=0x1F86\n29=0x1F87\n30=0x1F88\n31=0x1F89\n32=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=12\n1=0x2000\n2=0x2001\n3=0x2200\n4=0x2201\n5=0x5800\n6=0x5801\n7=0x5A00\n8=0x5A01\n9=0x5C00\n10=0x5C01\n11=0x5E00\n12=0x5E01\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=2\n2=0x00000082\n3=0x00000083\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=2\n2=0x00000005\n3=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=2\n2=0x00000360\n3=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=proxy_device_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=proxy_device_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=proxy_device_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=proxy_device_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_core/test/simple.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=11\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1A00\n\n[ManufacturerObjects]\nSupportedObjects=2\n1=0x4000\n2=0x4001\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n"
  },
  {
    "path": "canopen_core/test/test_canopen_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/driver_node.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockNodeCanopenMaster : public ros2_canopen::node_interfaces::NodeCanopenDriverInterface\n{\npublic:\n  MOCK_METHOD(\n    void, set_master,\n    (std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master),\n    (override));\n  MOCK_METHOD(void, demand_set_master, (), (override));\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(void, configure, (), (override));\n  MOCK_METHOD(void, activate, (), (override));\n  MOCK_METHOD(void, deactivate, (), (override));\n  MOCK_METHOD(void, cleanup, (), (override));\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(void, add_to_master, (), (override));\n  MOCK_METHOD(void, remove_from_master, (), (override));\n};\n\nclass MockCanopenMaster : public CanopenDriver\n{\n  friend class CanopenDriverTest;\n  FRIEND_TEST(CanopenDriverTest, test_init);\n};\n\nclass CanopenDriverTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockCanopenMaster> canopen_driver;\n  std::shared_ptr<MockNodeCanopenMaster> node_canopen_driver;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenDriverTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    canopen_driver = std::make_shared<MockCanopenMaster>();\n    node_canopen_driver = std::make_shared<MockNodeCanopenMaster>();\n    canopen_driver->node_canopen_driver_ =\n      std::static_pointer_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface>(\n        node_canopen_driver);\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenDriverTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(CanopenDriverTest, test_init)\n{\n  EXPECT_CALL(*node_canopen_driver, init()).Times(1);\n  EXPECT_CALL(*node_canopen_driver, configure()).Times(1);\n  EXPECT_CALL(*node_canopen_driver, demand_set_master()).Times(1);\n  EXPECT_CALL(*node_canopen_driver, activate()).Times(1);\n  canopen_driver->init();\n}\n\nTEST_F(CanopenDriverTest, test_set_master)\n{\n  std::shared_ptr<lely::ev::Executor> exec;\n  std::shared_ptr<lely::canopen::AsyncMaster> master;\n\n  EXPECT_CALL(*node_canopen_driver, set_master(_, _)).Times(1);\n  EXPECT_NO_THROW(canopen_driver->set_master(exec, master));\n}\n\nTEST_F(CanopenDriverTest, test_get_node_base_interface)\n{\n  auto base_iface = canopen_driver->get_node_base_interface();\n  EXPECT_TRUE(base_iface);\n}\n\nTEST_F(CanopenDriverTest, test_shutdown)\n{\n  EXPECT_CALL(*node_canopen_driver, shutdown());\n  EXPECT_NO_THROW(canopen_driver->shutdown());\n}\n\nTEST_F(CanopenDriverTest, test_is_lifecycle) { EXPECT_FALSE(canopen_driver->is_lifecycle()); }\n\nTEST_F(CanopenDriverTest, test_get_node_canopen_driver_interface)\n{\n  EXPECT_TRUE(canopen_driver->get_node_canopen_driver_interface() == node_canopen_driver);\n}\n"
  },
  {
    "path": "canopen_core/test/test_canopen_master.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/master_node.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockNodeCanopenMaster : public ros2_canopen::node_interfaces::NodeCanopenMasterInterface\n{\npublic:\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(void, configure, (), (override));\n  MOCK_METHOD(void, activate, (), (override));\n  MOCK_METHOD(void, deactivate, (), (override));\n  MOCK_METHOD(void, cleanup, (), (override));\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::canopen::AsyncMaster>, get_master, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::ev::Executor>, get_executor, (), (override));\n};\n\nclass MockCanopenMaster : public CanopenMaster\n{\n  friend class CanopenMasterTest;\n  FRIEND_TEST(CanopenMasterTest, test_init);\n};\n\nclass CanopenMasterTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockCanopenMaster> canopen_master;\n  std::shared_ptr<MockNodeCanopenMaster> node_canopen_master;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    canopen_master = std::make_shared<MockCanopenMaster>();\n    node_canopen_master = std::make_shared<MockNodeCanopenMaster>();\n    canopen_master->node_canopen_master_ =\n      std::static_pointer_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface>(\n        node_canopen_master);\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(CanopenMasterTest, test_init)\n{\n  EXPECT_CALL(*node_canopen_master, init()).Times(1);\n  EXPECT_CALL(*node_canopen_master, configure()).Times(1);\n  EXPECT_CALL(*node_canopen_master, activate()).Times(1);\n  canopen_master->init();\n}\n\nTEST_F(CanopenMasterTest, test_get_node_base_interface)\n{\n  auto base_iface = canopen_master->get_node_base_interface();\n  EXPECT_TRUE(base_iface);\n}\n\nTEST_F(CanopenMasterTest, test_shutdown)\n{\n  EXPECT_CALL(*node_canopen_master, shutdown());\n  EXPECT_NO_THROW(canopen_master->shutdown());\n}\n\nTEST_F(CanopenMasterTest, test_is_lifecycle) { EXPECT_FALSE(canopen_master->is_lifecycle()); }\n\nTEST_F(CanopenMasterTest, test_get_master)\n{\n  EXPECT_CALL(*node_canopen_master, get_master());\n  EXPECT_NO_THROW(canopen_master->get_master());\n}\n\nTEST_F(CanopenMasterTest, test_get_executor)\n{\n  EXPECT_CALL(*node_canopen_master, get_executor());\n  EXPECT_NO_THROW(canopen_master->get_executor());\n}\n"
  },
  {
    "path": "canopen_core/test/test_device_container.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/device_container.hpp\"\n#include \"canopen_core/device_container_error.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockNodeFactory : public rclcpp_components::NodeFactory\n{\npublic:\n  MOCK_METHOD(\n    rclcpp_components::NodeInstanceWrapper, create_node_instance,\n    (const rclcpp::NodeOptions & options), (override));\n};\n\nclass FakeDeviceContainer\n{\npublic:\n  virtual std::vector<rclcpp_components::ComponentManager::ComponentResource>\n  get_component_resources(\n    const std::string & package_name,\n    const std::string & resource_index = \"rclcpp_components\") const\n  {\n    // RCLCPP_INFO(this->get_logger(), \"get_component_resources\");\n    std::vector<rclcpp_components::ComponentManager::ComponentResource> components;\n    components.push_back(rclcpp_components::ComponentManager::ComponentResource(\n      \"ros2_canopen::CanopenMaster\", \"canopen_core\"));\n    components.push_back(rclcpp_components::ComponentManager::ComponentResource(\n      \"ros2_canopen::LifecycleCanopenMaster\", \"canopen_core\"));\n    components.push_back(rclcpp_components::ComponentManager::ComponentResource(\n      \"ros2_canopen::CanopenDriver\", \"canopen_core\"));\n    components.push_back(rclcpp_components::ComponentManager::ComponentResource(\n      \"ros2_canopen::LifecycleCanopenDriver\", \"canopen_core\"));\n    // get_component_resources_mock(true);\n    return components;\n  }\n};\nusing namespace std::placeholders;\nclass MockDeviceContainer : public DeviceContainer\n{\n  FakeDeviceContainer fake_device_container;\n\npublic:\n  FRIEND_TEST(DeviceContainerTest, test_load_component_master);\n  FRIEND_TEST(DeviceContainerTest, test_load_component_driver_non_lifecycle);\n  FRIEND_TEST(DeviceContainerTest, test_load_component_driver_lifecycle);\n  FRIEND_TEST(DeviceContainerTest, test_get_registered_drivers);\n  FRIEND_TEST(DeviceContainerTest, test_shutdown);\n  FRIEND_TEST(DeviceContainerTest, test_get_ids_of_drivers_with_type);\n  FRIEND_TEST(DeviceContainerTest, test_get_driver_type);\n  FRIEND_TEST(DeviceContainerTest, test_on_list_nodes);\n  FRIEND_TEST(DeviceContainerTest, test_load_master_good);\n  FRIEND_TEST(DeviceContainerTest, test_load_master_load_component_fail);\n  FRIEND_TEST(DeviceContainerTest, test_load_master_bad_no_id);\n  FRIEND_TEST(DeviceContainerTest, test_load_master_bad_no_driver);\n  FRIEND_TEST(DeviceContainerTest, test_load_master_bad_no_package);\n  FRIEND_TEST(DeviceContainerTest, test_load_driver_good);\n  FRIEND_TEST(DeviceContainerTest, test_load_driver_load_component_fail);\n  FRIEND_TEST(DeviceContainerTest, test_load_driver_bad_no_id);\n  FRIEND_TEST(DeviceContainerTest, test_load_driver_bad_no_package);\n  FRIEND_TEST(DeviceContainerTest, test_load_driver_bad_no_driver);\n  FRIEND_TEST(DeviceContainerTest, test_load_manager_no_lifecycle);\n  FRIEND_TEST(DeviceContainerTest, test_load_manager_lifecycle);\n  FRIEND_TEST(DeviceContainerTest, test_configure_good);\n\n  MockDeviceContainer(\n    std::weak_ptr<rclcpp::Executor> executor =\n      std::weak_ptr<rclcpp::executors::MultiThreadedExecutor>())\n  : DeviceContainer(executor), fake_device_container()\n  {\n  }\n  MOCK_METHOD(\n    bool, load_component,\n    (std::string & package_name, std::string & driver_name, uint16_t node_id,\n     std::string & node_name, std::vector<rclcpp::Parameter> & params),\n    (override));\n  MOCK_METHOD(void, configure, (), (override));\n  MOCK_METHOD(bool, load_master, (), (override));\n  MOCK_METHOD(bool, load_drivers, (), (override));\n  MOCK_METHOD(bool, load_manager, (), (override));\n  MOCK_METHOD(\n    std::shared_ptr<rclcpp_components::NodeFactory>, create_component_factory,\n    (const ComponentResource & resource), (override));\n  MOCK_METHOD(\n    std::vector<ComponentResource>, get_component_resources,\n    (const std::string & package_name, const std::string & resource_index), (const, override));\n  MOCK_METHOD(\n    void, add_node_to_executor,\n    (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_interface), (override));\n\n  void DelegateToFake()\n  {\n    ON_CALL(*this, load_component)\n      .WillByDefault(\n        [this](\n          std::string & package_name, std::string & driver_name, uint16_t node_id,\n          std::string & node_name, std::vector<rclcpp::Parameter> & params) -> bool {\n          return DeviceContainer::load_component(\n            package_name, driver_name, node_id, node_name, params);\n        });\n    ON_CALL(*this, load_master)\n      .WillByDefault([this]() -> bool { return DeviceContainer::load_master(); });\n    ON_CALL(*this, load_drivers)\n      .WillByDefault([this]() -> bool { return DeviceContainer::load_drivers(); });\n    ON_CALL(*this, load_manager)\n      .WillByDefault([this]() -> bool { return DeviceContainer::load_manager(); });\n    ON_CALL(*this, configure).WillByDefault([this]() { return DeviceContainer::configure(); });\n    ON_CALL(*this, get_component_resources)\n      .WillByDefault(\n        [this](const std::string & package_name, const std::string & resource_index)\n          -> std::vector<ComponentResource>\n        { return fake_device_container.get_component_resources(package_name, resource_index); });\n    ON_CALL(*this, add_node_to_executor)\n      .WillByDefault([this](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_interface)\n                     { DeviceContainer::add_node_to_executor(node_interface); });\n  }\n};\n\nclass MockCanopenDriver : public CanopenDriverInterface, public rclcpp::Node\n{\npublic:\n  explicit MockCanopenDriver(\n    std::string name = \"mock_canopen_driver\",\n    const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp::Node(name, node_options)\n  {\n  }\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(\n    void, set_master,\n    (std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master),\n    (override));\n  // MOCK_METHOD(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr, get_node_base_interface, (),\n  // (override));\n  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()\n  {\n    return rclcpp::Node::get_node_base_interface();\n  }\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(bool, is_lifecycle, (), (override));\n  MOCK_METHOD(\n    std::shared_ptr<ros2_canopen::node_interfaces::NodeCanopenDriverInterface>,\n    get_node_canopen_driver_interface, (), (override));\n};\n\nclass MockCanopenMaster : public CanopenMasterInterface, public rclcpp::Node\n{\npublic:\n  explicit MockCanopenMaster(\n    std::string name = \"mock_canopen_master\",\n    const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions())\n  : rclcpp::Node(name, node_options)\n  {\n  }\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::canopen::AsyncMaster>, get_master, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::ev::Executor>, get_executor, (), (override));\n  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface()\n  {\n    return rclcpp::Node::get_node_base_interface();\n  }\n  MOCK_METHOD(bool, is_lifecycle, (), (override));\n};\n\nclass DeviceContainerTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockDeviceContainer> device_container;\n  std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> exec;\n  std::thread spinThread;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"DeviceContainerTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n    device_container = std::make_shared<MockDeviceContainer>(exec);\n    device_container->DelegateToFake();\n\n    exec->add_node(device_container);\n    spinThread = std::thread([this]() { exec->spin(); });\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"DeviceContainerTest\"), \"Teardown\");\n    exec->cancel();\n    spinThread.join();\n    RCLCPP_INFO(rclcpp::get_logger(\"DeviceContainerTest\"), \"Executor joined.\");\n    exec->remove_node(device_container);\n    RCLCPP_INFO(rclcpp::get_logger(\"DeviceContainerTest\"), \"Node removed.\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(DeviceContainerTest, test_name_and_parameters_declared)\n{\n  EXPECT_TRUE(std::string(\"device_container\").compare(device_container->get_name()) == 0);\n  EXPECT_TRUE(device_container->has_parameter(\"can_interface_name\"));\n  EXPECT_TRUE(device_container->has_parameter(\"master_config\"));\n  EXPECT_TRUE(device_container->has_parameter(\"bus_config\"));\n  EXPECT_TRUE(device_container->has_parameter(\"master_bin\"));\n}\n\nTEST_F(DeviceContainerTest, test_services_declared)\n{\n  auto services = device_container->get_service_names_and_types_by_node(\n    device_container->get_name(), device_container->get_namespace());\n  bool found_init_driver = false;\n  bool found_unload_node = false;\n  bool found_load_node = false;\n  for (auto it = services.begin(); it != services.end(); ++it)\n  {\n    if (it->first.compare(\"/device_container/init_driver\") == 0)\n    {\n      found_init_driver = true;\n    }\n    if (it->first.compare(\"/device_container/_container/unload_node\") == 0)\n    {\n      found_unload_node = true;\n    }\n    if (it->first.compare(\"/device_container/_container/load_node\") == 0)\n    {\n      found_load_node = true;\n    }\n  }\n  EXPECT_TRUE(found_init_driver);\n  EXPECT_FALSE(found_unload_node);\n  EXPECT_FALSE(found_load_node);\n}\n\nTEST_F(DeviceContainerTest, test_load_component_master)\n{\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenMaster\");\n  std::string node_name(\"master\");\n  uint16_t node_id = 1;\n  auto node = std::make_shared<MockCanopenMaster>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(node),\n    std::bind(&MockCanopenMaster::get_node_base_interface, node));\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n\n  // Check that can_master_ is assigned.\n  EXPECT_TRUE(((long)device_container->can_master_.get() == (long)node.get()));\n  // Check that master is not stored in driver map.\n  EXPECT_FALSE((long)device_container->registered_drivers_[node_id].get() == (long)node.get());\n}\n\nTEST_F(DeviceContainerTest, test_load_component_driver_non_lifecycle)\n{\n  // Lifecycle operation false\n  device_container->lifecycle_operation_ = false;\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  std::string node_name(\"driver\");\n\n  uint16_t node_id = 1;\n  auto node = std::make_shared<MockCanopenDriver>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, node));\n\n  // Lifecycle component leads to throw\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(true));\n  EXPECT_THROW(\n    device_container->load_component(package, driver_name, node_id, node_name, params),\n    DeviceContainerException);\n\n  // Non lifecycle component leads to normal behaviour\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n\n  // Check that can_master_ is not assigned.\n  EXPECT_FALSE(((long)device_container->can_master_.get() == (long)node.get()));\n  // Check that driver is stored in driver map.\n  EXPECT_TRUE((long)device_container->registered_drivers_[node_id].get() == (long)node.get());\n}\n\nTEST_F(DeviceContainerTest, test_load_component_driver_lifecycle)\n{\n  // Lifecycle operation true\n  device_container->lifecycle_operation_ = true;\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  std::string node_name(\"driver\");\n  uint16_t node_id = 1;\n  auto node = std::make_shared<MockCanopenDriver>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, node));\n\n  // Non lifecycle component leads to throw\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  EXPECT_THROW(\n    device_container->load_component(package, driver_name, node_id, node_name, params),\n    DeviceContainerException);\n\n  // Lifecycle component leads to normal behaviour\n  node_id = 2;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(true));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n\n  // Check that can_master_ is not assigned.\n  EXPECT_FALSE(((long)device_container->can_master_.get() == (long)node.get()));\n  // Check that driver is stored in driver map.\n  EXPECT_TRUE((long)device_container->registered_drivers_[node_id].get() == (long)node.get());\n}\n\nTEST_F(DeviceContainerTest, test_get_registered_drivers)\n{\n  // Lifecycle operation true\n  device_container->lifecycle_operation_ = false;\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  std::string node_name(\"driver\");\n  uint16_t node_id = 1;\n  auto node = std::make_shared<MockCanopenDriver>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, node));\n\n  // Should be zero at start\n  EXPECT_EQ(device_container->get_registered_drivers().size(), 0U);\n\n  // Load component and expect that size of registered drivers changes to 1\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n  EXPECT_EQ(device_container->get_registered_drivers().size(), 1U);\n\n  // Load component and expect that size of registered drivers changes to 2\n  node_id = 2;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n  EXPECT_EQ(device_container->get_registered_drivers().size(), 2U);\n}\n\nTEST_F(DeviceContainerTest, test_count_drivers)\n{\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  std::string node_name(\"driver1\");\n  uint16_t node_id = 1;\n  auto node = std::make_shared<MockCanopenDriver>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, node));\n\n  // Should be zero at start\n  EXPECT_EQ(device_container->count_drivers(), 0U);\n\n  // Load component and expect that size of registered drivers changes to 1\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n  EXPECT_EQ(device_container->count_drivers(), 1U);\n\n  // Load component and expect that size of registered drivers changes to 2\n  node_id = 2;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_)).Times(1).WillOnce(Return(node_instance));\n  EXPECT_CALL(*node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n  EXPECT_EQ(device_container->count_drivers(), 2U);\n}\n\nTEST_F(DeviceContainerTest, test_shutdown)\n{\n  // Lifecycle operation true\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string driver_name(\"ros2_canopen::CanopenMaster\");\n  std::string node_name(\"master\");\n  uint16_t node_id = 1;\n  auto master_node = std::make_shared<MockCanopenMaster>();\n  auto driver_node = std::make_shared<MockCanopenDriver>();\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto master_node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(master_node),\n    std::bind(&MockCanopenMaster::get_node_base_interface, master_node));\n  auto driver_node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(driver_node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, driver_node));\n\n  // Load component and expect that size of registered drivers changes to 1\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_))\n    .Times(1)\n    .WillOnce(Return(master_node_instance));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n\n  driver_name = \"ros2_canopen::CanopenDriver\";\n  node_name = \"driver2\";\n  node_id = 2;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_))\n    .Times(1)\n    .WillOnce(Return(driver_node_instance));\n  EXPECT_CALL(*driver_node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n\n  node_id = 3;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_))\n    .Times(1)\n    .WillOnce(Return(driver_node_instance));\n  EXPECT_CALL(*driver_node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, node_name, params);\n  EXPECT_EQ(device_container->get_registered_drivers().size(), 2U);\n\n  EXPECT_CALL(*driver_node, shutdown()).Times(2);\n  EXPECT_CALL(*master_node, shutdown()).Times(1);\n  device_container->shutdown();\n}\n\nTEST_F(DeviceContainerTest, test_get_ids_of_drivers_with_type)\n{\n  std::string file_name(\"bus_configs/good_master_and_two_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  auto ids = device_container->get_ids_of_drivers_with_type(driver_name);\n  EXPECT_EQ(ids.size(), 2U);\n}\n\nTEST_F(DeviceContainerTest, test_get_driver_type)\n{\n  std::string file_name(\"bus_configs/good_master_and_two_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  uint16_t node_id = 2;\n  auto driver_type = device_container->get_driver_type(node_id);\n  EXPECT_EQ(driver_type.compare(\"ros2_canopen::CanopenDriver\"), 0);\n}\n\nTEST_F(DeviceContainerTest, test_on_list_nodes)\n{\n  // Lifecycle operation true\n  std::vector<rclcpp::Parameter> params;\n  std::string package(\"canopen_core\");\n  std::string master_name(\"ros2_canopen::CanopenMaster\");\n  std::string driver_name(\"ros2_canopen::CanopenDriver\");\n  std::string master_node_name(\"master\");\n  std::string driver_node_name(\"driver\");\n  uint16_t node_id;\n  auto master_node = std::make_shared<MockCanopenMaster>(master_node_name);\n  auto driver_node = std::make_shared<MockCanopenDriver>(driver_node_name);\n  device_container->lifecycle_manager_ = std::make_unique<LifecycleManager>(rclcpp::NodeOptions());\n\n  auto node_factory = std::make_shared<MockNodeFactory>();\n  auto master_node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(master_node),\n    std::bind(&MockCanopenMaster::get_node_base_interface, master_node));\n  auto driver_node_instance = rclcpp_components::NodeInstanceWrapper(\n    std::static_pointer_cast<void>(driver_node),\n    std::bind(&MockCanopenDriver::get_node_base_interface, driver_node));\n\n  node_id = 1;\n  device_container->can_master_id_ = node_id;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_))\n    .Times(1)\n    .WillOnce(Return(master_node_instance));\n  device_container->load_component(package, master_name, node_id, master_node_name, params);\n\n  node_id = 2;\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _));\n  EXPECT_CALL(*device_container, get_component_resources(_, _));\n  EXPECT_CALL(*device_container, create_component_factory(_))\n    .Times(1)\n    .WillOnce(Return(node_factory));\n  EXPECT_CALL(*node_factory, create_node_instance(_))\n    .Times(1)\n    .WillOnce(Return(driver_node_instance));\n  EXPECT_CALL(*driver_node, is_lifecycle()).Times(1).WillOnce(Return(false));\n  device_container->load_component(package, driver_name, node_id, driver_node_name, params);\n\n  const std::shared_ptr<rmw_request_id_t> request_header(nullptr);\n  auto request = std::make_shared<composition_interfaces::srv::ListNodes::Request>();\n  auto response = std::make_shared<composition_interfaces::srv::ListNodes::Response>();\n\n  device_container->on_list_nodes(request_header, request, response);\n\n  for (size_t i = 0; i < response->full_node_names.size(); i++)\n  {\n    if (response->full_node_names[i].compare(std::string(\"/\").append(master_node_name)) == 0)\n    {\n      EXPECT_EQ(response->unique_ids[i], 1U);\n    }\n    else if (response->full_node_names[i].compare(std::string(\"/\").append(driver_node_name)) == 0)\n    {\n      EXPECT_EQ(response->unique_ids[i], 2U);\n    }\n    else if (response->full_node_names[i].compare(std::string(\"/\").append(driver_node_name)) == 0)\n    {\n      EXPECT_EQ(response->unique_ids[i], 256U);\n    }\n    else\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"TEST\"), response->full_node_names[i].c_str());\n      FAIL();\n    }\n  }\n}\n\nTEST_F(DeviceContainerTest, test_load_master_good)\n{\n  std::string file_name(\"bus_configs/good_master.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto can_master = std::make_shared<MockCanopenMaster>(\"master\");\n\n  EXPECT_CALL(*device_container, load_master());\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _))\n    .WillOnce(\n      [this, can_master](\n        std::string & package_name, std::string & driver_name, uint16_t node_id,\n        std::string & node_name, std::vector<rclcpp::Parameter> & params) -> bool\n      {\n        device_container->can_master_ =\n          std::static_pointer_cast<ros2_canopen::CanopenMasterInterface>(can_master);\n        return true;\n      });\n  EXPECT_CALL(*device_container, add_node_to_executor(_));\n  EXPECT_CALL(*can_master, init());\n  EXPECT_CALL(*can_master, is_lifecycle());\n  EXPECT_TRUE(device_container->load_master());\n}\n\nTEST_F(DeviceContainerTest, test_load_master_load_component_fail)\n{\n  std::string file_name(\"bus_configs/good_master.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto can_master = std::make_shared<MockCanopenMaster>(\"master\");\n\n  EXPECT_CALL(*device_container, load_master());\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _)).WillOnce(Return(false));\n  EXPECT_FALSE(device_container->load_master());\n}\n\nTEST_F(DeviceContainerTest, test_load_master_bad_no_driver)\n{\n  std::string file_name(\"bus_configs/bad_master_no_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto can_master = std::make_shared<MockCanopenMaster>(\"master\");\n\n  EXPECT_CALL(*device_container, load_master());\n  EXPECT_FALSE(device_container->load_master());\n}\n\nTEST_F(DeviceContainerTest, test_load_master_bad_no_id)\n{\n  std::string file_name(\"bus_configs/bad_master_no_id.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto can_master = std::make_shared<MockCanopenMaster>(\"master\");\n\n  EXPECT_CALL(*device_container, load_master());\n  EXPECT_FALSE(device_container->load_master());\n}\n\nTEST_F(DeviceContainerTest, test_load_master_bad_no_package)\n{\n  std::string file_name(\"bus_configs/bad_master_no_package.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto can_master = std::make_shared<MockCanopenMaster>(\"master\");\n\n  EXPECT_CALL(*device_container, load_master());\n  EXPECT_FALSE(device_container->load_master());\n}\n\nTEST_F(DeviceContainerTest, test_load_driver_good)\n{\n  std::string file_name(\"bus_configs/good_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto driver = std::make_shared<MockCanopenDriver>(\"driver\");\n\n  EXPECT_CALL(*device_container, load_drivers());\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _))\n    .WillOnce(\n      [this, driver](\n        std::string & package_name, std::string & driver_name, uint16_t node_id,\n        std::string & node_name, std::vector<rclcpp::Parameter> & params) -> bool\n      {\n        device_container->registered_drivers_[2] =\n          std::static_pointer_cast<ros2_canopen::CanopenDriverInterface>(driver);\n        return true;\n      });\n  EXPECT_CALL(*device_container, add_node_to_executor(_));\n  EXPECT_CALL(*driver, init());\n  EXPECT_TRUE(device_container->load_drivers());\n}\n\nTEST_F(DeviceContainerTest, test_load_driver_load_component_fail)\n{\n  std::string file_name(\"bus_configs/good_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n  auto driver = std::make_shared<MockCanopenDriver>(\"driver\");\n\n  EXPECT_CALL(*device_container, load_drivers());\n  EXPECT_CALL(*device_container, load_component(_, _, _, _, _)).WillOnce(Return(false));\n  EXPECT_FALSE(device_container->load_drivers());\n}\n\nTEST_F(DeviceContainerTest, test_load_driver_bad_no_id)\n{\n  std::string file_name(\"bus_configs/bad_driver_no_id.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n\n  EXPECT_CALL(*device_container, load_drivers());\n  EXPECT_FALSE(device_container->load_drivers());\n}\n\nTEST_F(DeviceContainerTest, test_load_driver_bad_no_driver)\n{\n  std::string file_name(\"bus_configs/bad_driver_no_driver.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n\n  EXPECT_CALL(*device_container, load_drivers());\n  EXPECT_FALSE(device_container->load_drivers());\n}\n\nTEST_F(DeviceContainerTest, test_load_driver_bad_no_package)\n{\n  std::string file_name(\"bus_configs/bad_driver_no_package.yml\");\n  device_container->config_ = std::make_shared<ConfigurationManager>(file_name);\n  device_container->config_->init_config();\n\n  EXPECT_CALL(*device_container, load_drivers());\n  EXPECT_FALSE(device_container->load_drivers());\n}\n\nTEST_F(DeviceContainerTest, test_load_manager_no_lifecycle)\n{\n  device_container->lifecycle_operation_ = false;\n  EXPECT_CALL(*device_container, load_manager());\n  EXPECT_TRUE(device_container->load_manager());\n  EXPECT_FALSE(device_container->lifecycle_manager_);\n}\n\nTEST_F(DeviceContainerTest, test_load_manager_lifecycle)\n{\n  device_container->lifecycle_operation_ = true;\n  EXPECT_CALL(*device_container, load_manager());\n  EXPECT_CALL(*device_container, add_node_to_executor(_));\n  EXPECT_TRUE(device_container->load_manager());\n  EXPECT_TRUE(device_container->lifecycle_manager_);\n}\n\nTEST_F(DeviceContainerTest, test_configure_good)\n{\n  device_container->set_parameter(rclcpp::Parameter(\"can_interface_name\", \"vcan0\"));\n  device_container->set_parameter(rclcpp::Parameter(\"master_config\", \"master.dcf\"));\n  device_container->set_parameter(\n    rclcpp::Parameter(\"bus_config\", \"bus_configs/good_master_and_two_driver.yml\"));\n\n  EXPECT_CALL(*device_container, configure());\n  EXPECT_NO_THROW(device_container->configure());\n}\n\nTEST_F(DeviceContainerTest, test_init)\n{\n  device_container->set_parameter(rclcpp::Parameter(\"can_interface_name\", \"vcan0\"));\n  device_container->set_parameter(rclcpp::Parameter(\"master_config\", \"master.dcf\"));\n  device_container->set_parameter(\n    rclcpp::Parameter(\"bus_config\", \"bus_configs/good_master_and_two_driver.yml\"));\n\n  EXPECT_CALL(*device_container, configure()).WillOnce(Return());\n  EXPECT_CALL(*device_container, load_master()).WillOnce(Return(true));\n  EXPECT_CALL(*device_container, load_drivers()).WillOnce(Return(true));\n  EXPECT_CALL(*device_container, load_manager()).WillOnce(Return(true));\n  EXPECT_NO_THROW(device_container->init());\n}\n\nTEST_F(DeviceContainerTest, test_init_with_fparam)\n{\n  EXPECT_CALL(*device_container, load_master()).WillOnce(Return(true));\n  EXPECT_CALL(*device_container, load_drivers()).WillOnce(Return(true));\n  EXPECT_CALL(*device_container, load_manager()).WillOnce(Return(true));\n  EXPECT_NO_THROW(device_container->init(\n    \"vcan0\", \"master.dcf\", \"bus_configs/good_master_and_two_driver.yml\", \"\"));\n}\n\n// TEST(ComponentLoad, test_device_container_configure)\n// {\n//     rclcpp::init(0, nullptr);\n//     auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n//     auto device_container = std::make_shared<DeviceContainer>(exec);\n//     exec->add_node(device_container);\n\n//     device_container->set_parameter(Parameter(\"bus_config\", \"bus.yml\"));\n//     device_container->set_parameter(Parameter(\"master_config\", \"master.dcf\"));\n//     device_container->set_parameter(Parameter(\"can_interface_name\", \"can0\"));\n\n//     exec->spin_some(100ms);\n\n//     device_container->configure();\n\n//     auto time_now = std::chrono::steady_clock::now();\n//     auto time_future = time_now + 100ms;\n//     while (time_future > std::chrono::steady_clock::now())\n//     {\n//         exec->spin_some(100ms);\n//     }\n//     rclcpp::shutdown();\n// }\n\n// TEST(ComponentLoad, test_load_master)\n// {\n//     rclcpp::init(0, nullptr);\n//     auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n//     auto device_container = std::make_shared<DeviceContainer>(exec);\n//     exec->add_node(device_container);\n\n//     device_container->set_parameter(Parameter(\"bus_config\", \"bus.yml\"));\n//     device_container->set_parameter(Parameter(\"master_config\", \"master.dcf\"));\n//     device_container->set_parameter(Parameter(\"can_interface_name\", \"vcan0\"));\n\n//     exec->spin_some(100ms);\n\n//     device_container->configure();\n//     device_container->load_master();\n\n//     std::thread spinner(\n//         [exec]()\n//         {\n//             exec->spin();\n//             RCLCPP_INFO(rclcpp::get_logger(\"test\"), \"Executor done.\");\n//         });\n//     std::this_thread::sleep_for(500ms);\n//     device_container->shutdown();\n//     rclcpp::shutdown();\n//     spinner.join();\n//     RCLCPP_INFO(rclcpp::get_logger(\"test\"), \"rclcpp::shutdown\");\n// }\n\n// TEST(ComponentLoad, test_load_component_2)\n// {\n//     rclcpp::init(0, nullptr);\n//     auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n//     auto device_container = std::make_shared<DeviceContainer>(exec);\n//     exec->add_node(device_container);\n\n//     device_container->set_parameter(Parameter(\"bus_config\", \"bus.yml\"));\n//     device_container->set_parameter(Parameter(\"master_config\", \"master.dcf\"));\n//     device_container->set_parameter(Parameter(\"can_interface_name\", \"vcan0\"));\n\n//     std::thread spinner (\n//         [exec](){\n//             exec->spin();\n//             RCLCPP_INFO(rclcpp::get_logger(\"test\"), \"Executor done.\");\n//         }\n//     );\n//     device_container->configure();\n//     device_container->load_master();\n//     EXPECT_THROW(device_container->load_drivers(), std::system_error);\n//     std::this_thread::sleep_for(500ms);\n//     device_container->shutdown();\n//     rclcpp::shutdown();\n//     spinner.join();\n\n// }\n"
  },
  {
    "path": "canopen_core/test/test_errors.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/device_container_error.hpp\"\n#include \"canopen_core/driver_error.hpp\"\n#include \"canopen_core/master_error.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nTEST(DriverErrorTest, test_what)\n{\n  DriverException test_obj(\"hello\");\n  EXPECT_TRUE(std::string(\"hello\").compare(test_obj.what()) == 0);\n}\n\nTEST(MasterErrorTest, test_what)\n{\n  MasterException test_obj(\"hello\");\n  EXPECT_TRUE(std::string(\"hello\").compare(test_obj.what()) == 0);\n}\n\nTEST(DeviceContainerErrorTest, test_what)\n{\n  DeviceContainerException test_obj(\"hello\");\n  EXPECT_TRUE(std::string(\"hello\").compare(test_obj.what()) == 0);\n}\n"
  },
  {
    "path": "canopen_core/test/test_lifecycle_canopen_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/driver_node.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockNodeCanopenMaster : public ros2_canopen::node_interfaces::NodeCanopenDriverInterface\n{\npublic:\n  MOCK_METHOD(\n    void, set_master,\n    (std::shared_ptr<lely::ev::Executor> exec, std::shared_ptr<lely::canopen::AsyncMaster> master),\n    (override));\n  MOCK_METHOD(void, demand_set_master, (), (override));\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(void, configure, (), (override));\n  MOCK_METHOD(void, activate, (), (override));\n  MOCK_METHOD(void, deactivate, (), (override));\n  MOCK_METHOD(void, cleanup, (), (override));\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(void, add_to_master, (), (override));\n  MOCK_METHOD(void, remove_from_master, (), (override));\n};\n\nclass MockCanopenMaster : public LifecycleCanopenDriver\n{\n  friend class CanopenDriverTest;\n  FRIEND_TEST(CanopenDriverTest, test_init);\n};\n\nclass CanopenDriverTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockCanopenMaster> canopen_driver;\n  std::shared_ptr<MockNodeCanopenMaster> node_canopen_driver;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenDriverTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    canopen_driver = std::make_shared<MockCanopenMaster>();\n    node_canopen_driver = std::make_shared<MockNodeCanopenMaster>();\n    canopen_driver->node_canopen_driver_ =\n      std::static_pointer_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface>(\n        node_canopen_driver);\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenDriverTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(CanopenDriverTest, test_init)\n{\n  EXPECT_CALL(*node_canopen_driver, init()).Times(1);\n  canopen_driver->init();\n}\n\nTEST_F(CanopenDriverTest, test_set_master)\n{\n  std::shared_ptr<lely::ev::Executor> exec;\n  std::shared_ptr<lely::canopen::AsyncMaster> master;\n\n  EXPECT_CALL(*node_canopen_driver, set_master(_, _)).Times(1);\n  EXPECT_NO_THROW(canopen_driver->set_master(exec, master));\n}\n\nTEST_F(CanopenDriverTest, test_get_node_base_interface)\n{\n  auto base_iface = canopen_driver->get_node_base_interface();\n  EXPECT_TRUE(base_iface);\n}\n\nTEST_F(CanopenDriverTest, test_shutdown)\n{\n  EXPECT_CALL(*node_canopen_driver, shutdown());\n  EXPECT_NO_THROW(canopen_driver->shutdown());\n}\n\nTEST_F(CanopenDriverTest, test_is_lifecycle) { EXPECT_TRUE(canopen_driver->is_lifecycle()); }\n\nTEST_F(CanopenDriverTest, test_get_node_canopen_driver_interface)\n{\n  EXPECT_TRUE(canopen_driver->get_node_canopen_driver_interface() == node_canopen_driver);\n}\n\nTEST_F(CanopenDriverTest, test_on_configure)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_driver, configure());\n  EXPECT_CALL(*node_canopen_driver, demand_set_master());\n  canopen_driver->on_configure(state);\n}\n\nTEST_F(CanopenDriverTest, test_on_activate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_driver, activate());\n  canopen_driver->on_activate(state);\n}\n\nTEST_F(CanopenDriverTest, test_on_deactivate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_driver, deactivate());\n  canopen_driver->on_deactivate(state);\n}\n\nTEST_F(CanopenDriverTest, test_on_cleanup)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_driver, cleanup());\n  canopen_driver->on_cleanup(state);\n}\n\nTEST_F(CanopenDriverTest, test_on_shutdown)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_driver, shutdown());\n  canopen_driver->on_shutdown(state);\n}\n"
  },
  {
    "path": "canopen_core/test/test_lifecycle_canopen_master.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/master_node.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockNodeCanopenMaster : public ros2_canopen::node_interfaces::NodeCanopenMasterInterface\n{\npublic:\n  MOCK_METHOD(void, init, (), (override));\n  MOCK_METHOD(void, configure, (), (override));\n  MOCK_METHOD(void, activate, (), (override));\n  MOCK_METHOD(void, deactivate, (), (override));\n  MOCK_METHOD(void, cleanup, (), (override));\n  MOCK_METHOD(void, shutdown, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::canopen::AsyncMaster>, get_master, (), (override));\n  MOCK_METHOD(std::shared_ptr<lely::ev::Executor>, get_executor, (), (override));\n};\n\nclass MockCanopenMaster : public LifecycleCanopenMaster\n{\n  friend class CanopenMasterTest;\n  FRIEND_TEST(CanopenMasterTest, test_init);\n};\n\nclass CanopenMasterTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockCanopenMaster> canopen_master;\n  std::shared_ptr<MockNodeCanopenMaster> node_canopen_master;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    canopen_master = std::make_shared<MockCanopenMaster>();\n    node_canopen_master = std::make_shared<MockNodeCanopenMaster>();\n    canopen_master->node_canopen_master_ =\n      std::static_pointer_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface>(\n        node_canopen_master);\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(CanopenMasterTest, test_init)\n{\n  EXPECT_CALL(*node_canopen_master, init()).Times(1);\n  canopen_master->init();\n}\n\nTEST_F(CanopenMasterTest, test_get_node_base_interface)\n{\n  auto base_iface = canopen_master->get_node_base_interface();\n  EXPECT_TRUE(base_iface);\n}\n\nTEST_F(CanopenMasterTest, test_shutdown)\n{\n  EXPECT_CALL(*node_canopen_master, shutdown());\n  EXPECT_NO_THROW(canopen_master->shutdown());\n}\n\nTEST_F(CanopenMasterTest, test_is_lifecycle) { EXPECT_TRUE(canopen_master->is_lifecycle()); }\n\nTEST_F(CanopenMasterTest, test_get_master)\n{\n  EXPECT_CALL(*node_canopen_master, get_master());\n  EXPECT_NO_THROW(canopen_master->get_master());\n}\n\nTEST_F(CanopenMasterTest, test_get_executor)\n{\n  EXPECT_CALL(*node_canopen_master, get_executor());\n  EXPECT_NO_THROW(canopen_master->get_executor());\n}\n\nTEST_F(CanopenMasterTest, test_on_configure)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_master, configure());\n  canopen_master->on_configure(state);\n}\n\nTEST_F(CanopenMasterTest, test_on_activate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_master, activate());\n  canopen_master->on_activate(state);\n}\n\nTEST_F(CanopenMasterTest, test_on_deactivate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_master, deactivate());\n  canopen_master->on_deactivate(state);\n}\n\nTEST_F(CanopenMasterTest, test_on_cleanup)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_master, cleanup());\n  canopen_master->on_cleanup(state);\n}\n\nTEST_F(CanopenMasterTest, test_on_shutdown)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*node_canopen_master, shutdown());\n  canopen_master->on_shutdown(state);\n}\n"
  },
  {
    "path": "canopen_core/test/test_lifecycle_manager.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <chrono>\n#include \"canopen_core/lifecycle_manager.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\nusing namespace std::chrono_literals;\nusing namespace ros2_canopen;\nusing namespace testing;\n\nclass MockLifecycleManager : public LifecycleManager\n{\npublic:\n  FRIEND_TEST(LifecycleManagerTest, test_constructor);\n  FRIEND_TEST(LifecycleManagerTest, test_init);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_master);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_master_false_initial_state);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_master_failed_activate);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_master_failed_configure);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_master);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_master_false_state);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_driver);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_driver_false_state_master);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_driver_false_state_driver);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_driver_fail_configure);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_driver_fail_activate);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_driver);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_driver_failed);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_all);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_all_fail_master);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_up_all_fail_driver);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_all);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_all_fail_master);\n  FRIEND_TEST(LifecycleManagerTest, test_bring_down_all_fail_driver);\n  FRIEND_TEST(LifecycleManagerTest, test_on_configure);\n  FRIEND_TEST(LifecycleManagerTest, test_on_configure_fail);\n  FRIEND_TEST(LifecycleManagerTest, test_on_activate);\n  FRIEND_TEST(LifecycleManagerTest, test_on_activate_fail);\n  FRIEND_TEST(LifecycleManagerTest, test_on_deactivate);\n  FRIEND_TEST(LifecycleManagerTest, test_on_deactivate_fail);\n  FRIEND_TEST(LifecycleManagerTest, test_on_cleanup);\n  FRIEND_TEST(LifecycleManagerTest, test_on_shutdown);\n\n  MockLifecycleManager() : LifecycleManager(rclcpp::NodeOptions()) {}\n  MOCK_METHOD(unsigned int, get_state, (uint8_t node_id, std::chrono::seconds time_out));\n  MOCK_METHOD(\n    bool, change_state, (uint8_t node_id, uint8_t transition, std::chrono::seconds time_out));\n  MOCK_METHOD(bool, bring_up_master, (), (override));\n  MOCK_METHOD(bool, bring_down_master, (), (override));\n  MOCK_METHOD(bool, bring_up_driver, (std::string device_name), (override));\n  MOCK_METHOD(bool, bring_down_driver, (std::string device_name), (override));\n  MOCK_METHOD(bool, load_from_config, (), (override));\n  MOCK_METHOD(bool, bring_up_all, (), (override));\n  MOCK_METHOD(bool, bring_down_all, (), (override));\n\n  void DelegateToBase()\n  {\n    ON_CALL(*this, get_state)\n      .WillByDefault(\n        [this](uint8_t node_id, std::chrono::seconds time_out) -> unsigned int\n        { return LifecycleManager::get_state(node_id, time_out); });\n    ON_CALL(*this, change_state)\n      .WillByDefault(\n        [this](uint8_t node_id, uint8_t transition, std::chrono::seconds time_out) -> unsigned int\n        { return LifecycleManager::change_state(node_id, transition, time_out); });\n    ON_CALL(*this, bring_up_master)\n      .WillByDefault([this]() -> bool { return LifecycleManager::bring_up_master(); });\n    ON_CALL(*this, bring_down_master)\n      .WillByDefault([this]() -> bool { return LifecycleManager::bring_down_master(); });\n    ON_CALL(*this, bring_up_driver)\n      .WillByDefault(\n        [this](std::string device_name) -> bool\n        { return LifecycleManager::bring_up_driver(device_name); });\n    ON_CALL(*this, bring_down_driver)\n      .WillByDefault(\n        [this](std::string device_name) -> bool\n        { return LifecycleManager::bring_down_driver(device_name); });\n    ON_CALL(*this, load_from_config)\n      .WillByDefault([this]() -> bool { return LifecycleManager::load_from_config(); });\n    ON_CALL(*this, bring_up_all)\n      .WillByDefault([this]() -> bool { return LifecycleManager::bring_up_all(); });\n    ON_CALL(*this, bring_down_all)\n      .WillByDefault([this]() -> bool { return LifecycleManager::bring_down_all(); });\n  }\n};\n\nclass LifecycleManagerTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockLifecycleManager> lifecycle_manager;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    lifecycle_manager = std::make_shared<MockLifecycleManager>();\n    lifecycle_manager->DelegateToBase();\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n\n  void SetUpConfigurationManager()\n  {\n    std::string file_name(\"bus_configs/good_master_and_two_driver.yml\");\n    auto cmanager = std::make_shared<ConfigurationManager>(file_name);\n    cmanager->init_config();\n    lifecycle_manager->init(cmanager);\n    EXPECT_CALL(*lifecycle_manager, load_from_config());\n    lifecycle_manager->load_from_config();\n  }\n};\n\nTEST_F(LifecycleManagerTest, test_constructor)\n{\n  EXPECT_TRUE(lifecycle_manager->has_parameter(\"container_name\"));\n  EXPECT_TRUE(lifecycle_manager->cbg_clients);\n}\n\nTEST_F(LifecycleManagerTest, test_init)\n{\n  std::string file_name(\"bus_configs/good_master_and_two_driver.yml\");\n  auto cmanager = std::make_shared<ConfigurationManager>(file_name);\n  cmanager->init_config();\n  lifecycle_manager->init(cmanager);\n  EXPECT_TRUE(lifecycle_manager->config_);\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_master)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_up_master());\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _)).Times(1).WillOnce(Return(1U));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_TRUE(lifecycle_manager->bring_up_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_master_false_initial_state)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_up_master());\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _)).Times(1).WillOnce(Return(0U));\n  EXPECT_FALSE(lifecycle_manager->bring_up_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_master_failed_configure)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_up_master());\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _)).Times(1).WillOnce(Return(1U));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(1).WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_master_failed_activate)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_up_master());\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _)).Times(1).WillOnce(Return(1U));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _))\n    .Times(2)\n    .WillOnce(Return(true))\n    .WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_master)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_down_master());\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(1)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_TRUE(lifecycle_manager->bring_down_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_master_false_state)\n{\n  EXPECT_CALL(*lifecycle_manager, bring_down_master());\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(1)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE));\n  EXPECT_FALSE(lifecycle_manager->bring_down_master());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_driver)\n{\n  SetUpConfigurationManager();\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(2)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE))\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_TRUE(lifecycle_manager->bring_up_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_driver_false_state_master)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(1)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_FALSE(lifecycle_manager->bring_up_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_driver_false_state_driver)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(2)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE))\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE));\n  EXPECT_FALSE(lifecycle_manager->bring_up_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_driver_fail_configure)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(2)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE))\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _)).Times(1).WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_driver_fail_activate)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(2)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE))\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _))\n    .Times(2)\n    .WillOnce(Return(true))\n    .WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_driver)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_down_driver(_));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _))\n    .Times(2)\n    .WillOnce(Return(true))\n    .WillOnce(Return(true));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(1)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED));\n  EXPECT_TRUE(lifecycle_manager->bring_down_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_driver_failed)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_down_driver(_));\n  EXPECT_CALL(*lifecycle_manager, change_state(_, _, _))\n    .Times(2)\n    .WillOnce(Return(true))\n    .WillOnce(Return(true));\n  EXPECT_CALL(*lifecycle_manager, get_state(_, _))\n    .Times(1)\n    .WillOnce(Return(lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE));\n  EXPECT_FALSE(lifecycle_manager->bring_down_driver(\"proxy_device_2\"));\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_all)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_all);\n  EXPECT_CALL(*lifecycle_manager, bring_up_master()).Times(1).WillOnce(Return(true));\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_TRUE(lifecycle_manager->bring_up_all());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_all_fail_master)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_all);\n  EXPECT_CALL(*lifecycle_manager, bring_up_master()).Times(1).WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_all());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_up_all_fail_driver)\n{\n  SetUpConfigurationManager();\n\n  EXPECT_CALL(*lifecycle_manager, bring_up_all);\n  EXPECT_CALL(*lifecycle_manager, bring_up_master()).Times(1).WillOnce(Return(true));\n  EXPECT_CALL(*lifecycle_manager, bring_up_driver(_)).Times(1).WillRepeatedly(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_up_all());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_all)\n{\n  SetUpConfigurationManager();\n  EXPECT_CALL(*lifecycle_manager, bring_down_all);\n  EXPECT_CALL(*lifecycle_manager, bring_down_driver(_)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_CALL(*lifecycle_manager, bring_down_master()).Times(1).WillOnce(Return(true));\n  EXPECT_TRUE(lifecycle_manager->bring_down_all());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_all_fail_driver)\n{\n  SetUpConfigurationManager();\n  EXPECT_CALL(*lifecycle_manager, bring_down_all);\n  EXPECT_CALL(*lifecycle_manager, bring_down_driver(_)).Times(1).WillRepeatedly(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_down_all());\n}\n\nTEST_F(LifecycleManagerTest, test_bring_down_all_fail_master)\n{\n  SetUpConfigurationManager();\n  EXPECT_CALL(*lifecycle_manager, bring_down_all);\n  EXPECT_CALL(*lifecycle_manager, bring_down_driver(_)).Times(2).WillRepeatedly(Return(true));\n  EXPECT_CALL(*lifecycle_manager, bring_down_master()).Times(1).WillOnce(Return(false));\n  EXPECT_FALSE(lifecycle_manager->bring_down_all());\n}\n\nTEST_F(LifecycleManagerTest, test_on_configure)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, load_from_config()).Times(1).WillOnce(Return(true));\n  EXPECT_EQ(\n    lifecycle_manager->on_configure(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS);\n}\n\nTEST_F(LifecycleManagerTest, test_on_configure_fail)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, load_from_config()).Times(1).WillOnce(Return(false));\n  EXPECT_EQ(\n    lifecycle_manager->on_configure(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR);\n}\n\nTEST_F(LifecycleManagerTest, test_on_activate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, bring_up_all()).Times(1).WillOnce(Return(true));\n  EXPECT_EQ(\n    lifecycle_manager->on_activate(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS);\n}\n\nTEST_F(LifecycleManagerTest, test_on_activate_fail)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, bring_up_all()).Times(1).WillOnce(Return(false));\n  EXPECT_EQ(\n    lifecycle_manager->on_activate(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR);\n}\n\nTEST_F(LifecycleManagerTest, test_on_deactivate)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, bring_down_all()).Times(1).WillOnce(Return(true));\n  EXPECT_EQ(\n    lifecycle_manager->on_deactivate(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS);\n}\n\nTEST_F(LifecycleManagerTest, test_on_deactivate_fail)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_CALL(*lifecycle_manager, bring_down_all()).Times(1).WillOnce(Return(false));\n  EXPECT_EQ(\n    lifecycle_manager->on_deactivate(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR);\n}\n\nTEST_F(LifecycleManagerTest, test_on_cleanup)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_EQ(\n    lifecycle_manager->on_cleanup(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS);\n}\n\nTEST_F(LifecycleManagerTest, test_on_shutdown)\n{\n  rclcpp_lifecycle::State state;\n  EXPECT_EQ(\n    lifecycle_manager->on_shutdown(state),\n    rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS);\n}\n"
  },
  {
    "path": "canopen_core/test/test_node_canopen_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/driver_node.hpp\"\n#include \"canopen_core/node_interfaces/node_canopen_driver.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\n\nusing namespace ros2_canopen;\nusing namespace ros2_canopen::node_interfaces;\nusing namespace testing;\ntemplate <class NODETYPE>\nclass MockNodeCanopenDriver : public NodeCanopenDriver<NODETYPE>\n{\npublic:\n  FRIEND_TEST(NodeCanopenDriverTest, test_construct);\n  FRIEND_TEST(NodeCanopenDriverTest, test_init);\n  FRIEND_TEST(NodeCanopenDriverTest, test_init_fail_configured);\n  FRIEND_TEST(NodeCanopenDriverTest, test_init_fail_activated);\n  FRIEND_TEST(NodeCanopenDriverTest, test_set_master);\n  FRIEND_TEST(NodeCanopenDriverTest, test_configure);\n  FRIEND_TEST(NodeCanopenDriverTest, test_configure_fail_not_initialsed);\n  FRIEND_TEST(NodeCanopenDriverTest, test_configure_fail_configured);\n  FRIEND_TEST(NodeCanopenDriverTest, test_configure_fail_activated);\n  FRIEND_TEST(NodeCanopenDriverTest, test_activate);\n  FRIEND_TEST(NodeCanopenDriverTest, test_activate_failures);\n  FRIEND_TEST(NodeCanopenDriverTest, test_deactivate);\n  FRIEND_TEST(NodeCanopenDriverTest, test_deactivate_failures);\n  FRIEND_TEST(NodeCanopenDriverTest, test_cleanup);\n  FRIEND_TEST(NodeCanopenDriverTest, test_cleanup_failures);\n  FRIEND_TEST(NodeCanopenDriverTest, test_shutdown);\n\n  MockNodeCanopenDriver(rclcpp::Node * node) : NodeCanopenDriver<NODETYPE>(node) {}\n  MOCK_METHOD0_T(add_to_master, void());\n  MOCK_METHOD0_T(remove_from_master, void());\n\n  void DelegateToBase()\n  {\n    // ON_CALL(*this, load_component)\n    //     .WillByDefault(\n    //         [this](\n    //             std::string & package_name, std::string & driver_name, uint16_t node_id,\n    //             std::string & node_name, std::vector<rclcpp::Parameter> & params) -> bool\n    //         { return DeviceContainer::load_component(package_name, driver_name, node_id,\n    //         node_name, params); });\n  }\n};\n\nclass NodeCanopenDriverTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockNodeCanopenDriver<rclcpp::Node>> node_canopen_driver;\n  rclcpp::Node::SharedPtr node;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    node = std::make_shared<rclcpp::Node>(\"driver\");\n    node_canopen_driver = std::make_shared<MockNodeCanopenDriver<rclcpp::Node>>(node.get());\n    node_canopen_driver->DelegateToBase();\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(NodeCanopenDriverTest, test_construct) { EXPECT_EQ(node.get(), node_canopen_driver->node_); }\n\nTEST_F(NodeCanopenDriverTest, test_init)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  node_canopen_driver->init();\n  EXPECT_TRUE(node_canopen_driver->initialised_.load());\n  EXPECT_TRUE(node->has_parameter(\"container_name\"));\n  EXPECT_TRUE(node->has_parameter(\"node_id\"));\n  EXPECT_TRUE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_TRUE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenDriverTest, test_init_fail_configured)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->init(), DriverException);\n  EXPECT_FALSE(node_canopen_driver->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenDriverTest, test_init_fail_activated)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->init(), DriverException);\n  EXPECT_FALSE(node_canopen_driver->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenDriverTest, test_set_master)\n{\n  std::shared_ptr<lely::ev::Executor> exec;\n  std::shared_ptr<lely::canopen::AsyncMaster> master;\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n\n  node_canopen_driver->set_master(exec, master);\n  EXPECT_TRUE(node_canopen_driver->master_set_.load());\n\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n\n  EXPECT_THROW(node_canopen_driver->set_master(exec, master), DriverException);\n\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n\n  EXPECT_THROW(node_canopen_driver->set_master(exec, master), DriverException);\n}\n\nTEST_F(NodeCanopenDriverTest, test_configure)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  node_canopen_driver->init();\n  node->set_parameter(rclcpp::Parameter(\n    \"config\",\n    \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage: \\\"canopen_core\\\"\\ndcf: \"\n    \"\\\"simple.eds\\\"\\ndcf_path: \\\"\\\"\\n\"));\n  std::cout << node->get_parameter(\"config\").as_string() << std::endl;\n  node_canopen_driver->configure();\n  EXPECT_TRUE(node_canopen_driver->configured_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_configure_fail_not_initialsed)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->configure(), DriverException);\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_configure_fail_configured)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  node_canopen_driver->init();\n  node_canopen_driver->configured_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_driver->configure(), DriverException);\n}\n\nTEST_F(NodeCanopenDriverTest, test_configure_fail_activated)\n{\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  node_canopen_driver->init();\n  node_canopen_driver->activated_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_driver->configure(), DriverException);\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_activate)\n{\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_CALL(*node_canopen_driver, add_to_master()).Times(1).WillOnce(Return());\n  node_canopen_driver->activate();\n  EXPECT_TRUE(node_canopen_driver->activated_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_activate_failures)\n{\n  node_canopen_driver->initialised_.store(false);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->activate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(false);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->activate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->activate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->activate(), DriverException);\n}\n\nTEST_F(NodeCanopenDriverTest, test_deactivate)\n{\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_CALL(*node_canopen_driver, remove_from_master()).Times(1).WillOnce(Return());\n  node_canopen_driver->deactivate();\n  EXPECT_FALSE(node_canopen_driver->activated_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_deactivate_failures)\n{\n  node_canopen_driver->initialised_.store(false);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->deactivate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(false);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->deactivate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->deactivate(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->deactivate(), DriverException);\n}\n\nTEST_F(NodeCanopenDriverTest, test_cleanup)\n{\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  node_canopen_driver->cleanup();\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n}\n\nTEST_F(NodeCanopenDriverTest, test_cleanup_failures)\n{\n  node_canopen_driver->initialised_.store(false);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->cleanup(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_THROW(node_canopen_driver->cleanup(), DriverException);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_THROW(node_canopen_driver->cleanup(), DriverException);\n}\n\nTEST_F(NodeCanopenDriverTest, test_shutdown)\n{\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(true);\n  EXPECT_CALL(*node_canopen_driver, remove_from_master()).Times(1).WillOnce(Return());\n  EXPECT_NO_THROW(node_canopen_driver->shutdown());\n  EXPECT_FALSE(node_canopen_driver->master_set_.load());\n  EXPECT_FALSE(node_canopen_driver->initialised_.load());\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n  EXPECT_FALSE(node_canopen_driver->activated_.load());\n\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(true);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_NO_THROW(node_canopen_driver->shutdown());\n  EXPECT_FALSE(node_canopen_driver->master_set_.load());\n  EXPECT_FALSE(node_canopen_driver->initialised_.load());\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n  EXPECT_FALSE(node_canopen_driver->activated_.load());\n\n  node_canopen_driver->master_set_.store(true);\n  node_canopen_driver->initialised_.store(true);\n  node_canopen_driver->configured_.store(false);\n  node_canopen_driver->activated_.store(false);\n  EXPECT_NO_THROW(node_canopen_driver->shutdown());\n  EXPECT_FALSE(node_canopen_driver->master_set_.load());\n  EXPECT_FALSE(node_canopen_driver->initialised_.load());\n  EXPECT_FALSE(node_canopen_driver->configured_.load());\n  EXPECT_FALSE(node_canopen_driver->activated_.load());\n}\n"
  },
  {
    "path": "canopen_core/test/test_node_canopen_master.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_core/master_node.hpp\"\n#include \"canopen_core/node_interfaces/node_canopen_master.hpp\"\n#include \"gmock/gmock.h\"\n#include \"gtest/gtest.h\"\n\nusing namespace ros2_canopen;\nusing namespace ros2_canopen::node_interfaces;\nusing namespace testing;\ntemplate <class NODETYPE>\nclass MockNodeCanopenMaster : public NodeCanopenMaster<NODETYPE>\n{\npublic:\n  FRIEND_TEST(NodeCanopenMasterTest, test_construct);\n  FRIEND_TEST(NodeCanopenMasterTest, test_init);\n  FRIEND_TEST(NodeCanopenMasterTest, test_init_fail_configured);\n  FRIEND_TEST(NodeCanopenMasterTest, test_init_fail_activated);\n  FRIEND_TEST(NodeCanopenMasterTest, test_set_master);\n  FRIEND_TEST(NodeCanopenMasterTest, test_configure);\n  FRIEND_TEST(NodeCanopenMasterTest, test_configure_fail_not_initialsed);\n  FRIEND_TEST(NodeCanopenMasterTest, test_configure_fail_configured);\n  FRIEND_TEST(NodeCanopenMasterTest, test_configure_fail_activated);\n  FRIEND_TEST(NodeCanopenMasterTest, test_activate);\n  FRIEND_TEST(NodeCanopenMasterTest, test_activate_failures);\n  FRIEND_TEST(NodeCanopenMasterTest, test_deactivate);\n  FRIEND_TEST(NodeCanopenMasterTest, test_deactivate_failures);\n  FRIEND_TEST(NodeCanopenMasterTest, test_cleanup);\n  FRIEND_TEST(NodeCanopenMasterTest, test_cleanup_failures);\n  FRIEND_TEST(NodeCanopenMasterTest, test_shutdown);\n  FRIEND_TEST(NodeCanopenMasterTest, test_get_master);\n  FRIEND_TEST(NodeCanopenMasterTest, test_get_executor);\n\n  FRIEND_TEST(NodeCanopenLMasterTest, test_construct);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_init);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_init_fail_configured);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_init_fail_activated);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_set_master);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_configure);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_configure_fail_not_initialsed);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_configure_fail_configured);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_configure_fail_activated);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_activate);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_activate_failures);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_deactivate);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_deactivate_failures);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_cleanup);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_cleanup_failures);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_shutdown);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_get_master);\n  FRIEND_TEST(NodeCanopenLMasterTest, test_get_executor);\n\n  MockNodeCanopenMaster(NODETYPE * node) : NodeCanopenMaster<NODETYPE>(node) {}\n\n  void DelegateToBase()\n  {\n    // ON_CALL(*this, load_component)\n    //     .WillByDefault(\n    //         [this](\n    //             std::string & package_name, std::string & driver_name, uint16_t node_id,\n    //             std::string & node_name, std::vector<rclcpp::Parameter> & params) -> bool\n    //         { return DeviceContainer::load_component(package_name, driver_name, node_id,\n    //         node_name, params); });\n  }\n};\n\nclass NodeCanopenMasterTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockNodeCanopenMaster<rclcpp::Node>> node_canopen_master;\n  rclcpp::Node::SharedPtr node;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    node = std::make_shared<rclcpp::Node>(\"driver\");\n    node_canopen_master = std::make_shared<MockNodeCanopenMaster<rclcpp::Node>>(node.get());\n    node_canopen_master->DelegateToBase();\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(NodeCanopenMasterTest, test_construct) { EXPECT_EQ(node.get(), node_canopen_master->node_); }\n\nTEST_F(NodeCanopenMasterTest, test_init)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  EXPECT_TRUE(node_canopen_master->initialised_.load());\n  EXPECT_TRUE(node->has_parameter(\"container_name\"));\n  EXPECT_TRUE(node->has_parameter(\"node_id\"));\n  EXPECT_TRUE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_TRUE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenMasterTest, test_init_fail_configured)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->init(), MasterException);\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenMasterTest, test_init_fail_activated)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->init(), MasterException);\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenMasterTest, test_configure)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenMaster\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  node_canopen_master->configure();\n  EXPECT_TRUE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenMasterTest, test_configure_fail_not_initialsed)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenMasterTest, test_configure_fail_configured)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node_canopen_master->configured_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n}\n\nTEST_F(NodeCanopenMasterTest, test_configure_fail_activated)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node_canopen_master->activated_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenMasterTest, test_activate_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n}\n\nTEST_F(NodeCanopenMasterTest, test_deactivate_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n}\n\nTEST_F(NodeCanopenMasterTest, test_cleanup)\n{\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->cleanup();\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenMasterTest, test_cleanup_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n}\n\nTEST_F(NodeCanopenMasterTest, test_shutdown)\n{\n  node_canopen_master->master_set_.store(true);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_NO_THROW(node_canopen_master->shutdown());\n  EXPECT_FALSE(node_canopen_master->master_set_.load());\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n  EXPECT_FALSE(node_canopen_master->activated_.load());\n}\n\nTEST_F(NodeCanopenMasterTest, test_get_master)\n{\n  node_canopen_master->master_set_.store(true);\n  EXPECT_NO_THROW(node_canopen_master->get_master());\n\n  node_canopen_master->master_set_.store(false);\n  EXPECT_ANY_THROW(node_canopen_master->get_master());\n}\n\nTEST_F(NodeCanopenMasterTest, test_get_executor)\n{\n  node_canopen_master->master_set_.store(true);\n  EXPECT_NO_THROW(node_canopen_master->get_executor());\n\n  node_canopen_master->master_set_.store(false);\n  EXPECT_ANY_THROW(node_canopen_master->get_executor());\n}\n\nclass NodeCanopenLMasterTest : public testing::Test\n{\npublic:\n  std::shared_ptr<MockNodeCanopenMaster<rclcpp_lifecycle::LifecycleNode>> node_canopen_master;\n  rclcpp_lifecycle::LifecycleNode::SharedPtr node;\n  void SetUp() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"SetUp\");\n    rclcpp::init(0, nullptr);\n    node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(\"driver\");\n    node_canopen_master =\n      std::make_shared<MockNodeCanopenMaster<rclcpp_lifecycle::LifecycleNode>>(node.get());\n    node_canopen_master->DelegateToBase();\n  }\n\n  void TearDown() override\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"CanopenMasterTest\"), \"TearDown\");\n    rclcpp::shutdown();\n  }\n};\n\nTEST_F(NodeCanopenLMasterTest, test_construct)\n{\n  EXPECT_EQ(node.get(), node_canopen_master->node_);\n}\n\nTEST_F(NodeCanopenLMasterTest, test_init)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  EXPECT_TRUE(node_canopen_master->initialised_.load());\n  EXPECT_TRUE(node->has_parameter(\"container_name\"));\n  EXPECT_TRUE(node->has_parameter(\"node_id\"));\n  EXPECT_TRUE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_TRUE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenLMasterTest, test_init_fail_configured)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->init(), MasterException);\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenLMasterTest, test_init_fail_activated)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->init(), MasterException);\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node->has_parameter(\"container_name\"));\n  EXPECT_FALSE(node->has_parameter(\"node_id\"));\n  EXPECT_FALSE(node->has_parameter(\"non_transmit_timeout\"));\n  EXPECT_FALSE(node->has_parameter(\"config\"));\n}\n\nTEST_F(NodeCanopenLMasterTest, test_configure)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenMaster\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  node_canopen_master->configure();\n  EXPECT_TRUE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_configure_fail_not_initialsed)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_configure_fail_configured)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node_canopen_master->configured_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n}\n\nTEST_F(NodeCanopenLMasterTest, test_configure_fail_activated)\n{\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->init();\n  node_canopen_master->activated_.store(true);\n  node->set_parameter(rclcpp::Parameter(\n    \"config\", \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage:\\\"canopen_core\\\"\\n\"));\n  EXPECT_THROW(node_canopen_master->configure(), MasterException);\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_activate_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->activate(), MasterException);\n}\n\nTEST_F(NodeCanopenLMasterTest, test_deactivate_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->deactivate(), MasterException);\n}\n\nTEST_F(NodeCanopenLMasterTest, test_cleanup)\n{\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  node_canopen_master->cleanup();\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_cleanup_failures)\n{\n  node_canopen_master->initialised_.store(false);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(true);\n  node_canopen_master->activated_.store(true);\n  EXPECT_THROW(node_canopen_master->cleanup(), MasterException);\n}\n\nTEST_F(NodeCanopenLMasterTest, test_shutdown)\n{\n  node_canopen_master->master_set_.store(true);\n  node_canopen_master->initialised_.store(true);\n  node_canopen_master->configured_.store(false);\n  node_canopen_master->activated_.store(false);\n  EXPECT_NO_THROW(node_canopen_master->shutdown());\n  EXPECT_FALSE(node_canopen_master->master_set_.load());\n  EXPECT_FALSE(node_canopen_master->initialised_.load());\n  EXPECT_FALSE(node_canopen_master->configured_.load());\n  EXPECT_FALSE(node_canopen_master->activated_.load());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_get_master)\n{\n  node_canopen_master->master_set_.store(true);\n  EXPECT_NO_THROW(node_canopen_master->get_master());\n\n  node_canopen_master->master_set_.store(false);\n  EXPECT_ANY_THROW(node_canopen_master->get_master());\n}\n\nTEST_F(NodeCanopenLMasterTest, test_get_executor)\n{\n  node_canopen_master->master_set_.store(true);\n  EXPECT_NO_THROW(node_canopen_master->get_executor());\n\n  node_canopen_master->master_set_.store(false);\n  EXPECT_ANY_THROW(node_canopen_master->get_executor());\n}\n"
  },
  {
    "path": "canopen_fake_slaves/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_fake_slaves\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* `#400 <https://github.com/ros-industrial/ros2_canopen/issues/400>`_: Update controllers for ROS Rolling API changes and fix fake slave type handling\n* Refactor GetValue method to use std::type_index for type comparisons\n* `motion_generator` as shared library (`#295 <https://github.com/ros-industrial/ros2_canopen/issues/295>`_)\n* Enhance SimpleSlave class with vendor ID parsing and adjust bus configuration timeouts\n* Multiple SDO types for slaves (`#278 <https://github.com/ros-industrial/ros2_canopen/issues/278>`_)\n  Co-authored-by: Kurtis Thrush <kthrush@jlg.com>\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n* Contributors: Christoph Hellmann Santos, Patrick Roncagliolo, Vishnuprasad Prachandabhanu\n\n0.2.9 (2024-04-16)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n* Add boot timeout and retry\n* Add suported modes to `canopen_fake_slaves` README (`#337 <https://github.com/ros-industrial/ros2_canopen/issues/337>`_)\n* Contributors: Gerry Salinas, Patrick Roncagliolo, Vishnuprasad Prachandabhanu\n\n0.3.0 (2024-12-12)\n------------------\n* fix loop timer for run_velocity_mode\n* Fix clang format\n* Add comments for the fake slave function\n* Fix the thread issue.\n* Apply suggestions from code review\n  Co-authored-by: Dr. Denis <denis@stoglrobotics.de>\n* Working version.\n* Periodic messages sent, but not received properly.\n* Working logic. Still have to work on the edf file.\n* Put the periodic messages in OnWrite\n* Extend fake_slaves to publish messages via rpdo\n\n0.2.12 (2024-04-22)\n-------------------\n* Merge pull request `#265 <https://github.com/ros-industrial/ros2_canopen/issues/265>`_ from kurtist123/feature/expose-fake-slave-includes\n  build: export include directories\n* build: export include directories\n* 0.2.9\n* forthcoming\n* Contributors: Kurtis Thrush, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n* Add fake profile velocity (`#230 <https://github.com/ros-industrial/ros2_canopen/issues/230>`_)\n  * Add simple sequence homing emulation\n  * Add fake velocity mode\n  * Formatting\n* Add simple sequence homing emulation (`#229 <https://github.com/ros-industrial/ros2_canopen/issues/229>`_)\n* Contributors: Christoph Hellmann Santos\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix fake slave for PDOs\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, James Ward, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_fake_slaves/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_fake_slaves)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(lely_core_libraries REQUIRED)\nfind_package(lifecycle_msgs REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\n\nadd_library(\n  motion_generator\n  SHARED\n  \"src/motion_generator.cpp\"\n)\ntarget_compile_features(motion_generator  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_include_directories(motion_generator  PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\n\nadd_executable(\n  basic_slave_node\n  \"src/basic_slave.cpp\"\n)\n\ntarget_compile_features(basic_slave_node  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_include_directories(basic_slave_node  PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(basic_slave_node PUBLIC\n  ${lely_core_libraries_LIBRARIES}\n  ${lifecycle_msgs_TARGETS}\n  rclcpp::rclcpp\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n\nadd_executable(\n  cia402_slave_node\n  \"src/cia402_slave.cpp\"\n)\ntarget_compile_features(cia402_slave_node  PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_include_directories(cia402_slave_node  PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(cia402_slave_node PUBLIC\n  ${lely_core_libraries_LIBRARIES}\n  ${lifecycle_msgs_TARGETS}\n  motion_generator\n  rclcpp::rclcpp\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\ninstall(TARGETS motion_generator\nDESTINATION lib/${PROJECT_NAME})\n\ninstall(TARGETS basic_slave_node\n  DESTINATION lib/${PROJECT_NAME})\n\ninstall(TARGETS cia402_slave_node\nDESTINATION lib/${PROJECT_NAME})\n\ninstall(DIRECTORY\n  launch/\n  DESTINATION share/${PROJECT_NAME}/launch/\n)\n\ninstall(DIRECTORY\n  config/\n  DESTINATION share/${PROJECT_NAME}/config/\n)\n\ninstall(DIRECTORY\n  include/\n  DESTINATION include\n)\n\nif(BUILD_TESTING)\n  find_package(ament_lint_auto REQUIRED)\n  # the following line skips the linter which checks for copyrights\n  # comment the line when a copyright and license is added to all source files\n  set(ament_cmake_copyright_FOUND TRUE)\n  # the following line skips cpplint (only works in a git repo)\n  # comment the line when this package is in a git repo and when\n  # a copyright and license is added to all source files\n  set(ament_cmake_cpplint_FOUND TRUE)\n  ament_lint_auto_find_test_dependencies()\nendif()\n\nament_export_include_directories(\n  include\n)\n\nament_export_dependencies(\n  lely_core_libraries\n  lifecycle_msgs\n  rclcpp\n  rclcpp_lifecycle\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_fake_slaves/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_fake_slaves/Readme.md",
    "content": "# CANopen Mock Slaves\n\n## Motion Controller Slaves\n\nSupported modes:\n* Cyclic Position\n* Profiled Position (Thanks to motion generator https://github.com/EFeru/MotionGenerator)\n* Interpolated Position\n* Homing\n* Profiled Velocity\n"
  },
  {
    "path": "canopen_fake_slaves/config/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0xC0000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0xC0000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_fake_slaves/config/simple_slave.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=11\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1A00\n\n[ManufacturerObjects]\nSupportedObjects=2\n1=0x4000\n2=0x4001\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n"
  },
  {
    "path": "canopen_fake_slaves/include/canopen_fake_slaves/base_slave.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef SLAVE_HPP\n#define SLAVE_HPP\n#include <atomic>\n#include \"rclcpp_lifecycle/lifecycle_node.hpp\"\n\nnamespace ros2_canopen\n{\nclass BaseSlave : public rclcpp_lifecycle::LifecycleNode\n{\npublic:\n  explicit BaseSlave(const std::string & node_name, bool intra_process_comms = false)\n  : rclcpp_lifecycle::LifecycleNode(\n      node_name, rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms))\n  {\n    this->declare_parameter(\"node_id\", 2);\n    this->declare_parameter(\"slave_config\", \"slave.eds\");\n    this->declare_parameter(\"can_interface_name\", \"vcan0\");\n    this->activated.store(false);\n  }\n\n  virtual ~BaseSlave()\n  {\n    if (this->run_thread.joinable())\n    {\n      run_thread.join();\n    }\n  }\n\n  virtual void run() = 0;\n\nprotected:\n  std::thread run_thread;\n  int node_id_;\n  std::string slave_config_;\n  std::string can_interface_name_;\n  std::atomic<bool> activated;\n\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State &)\n  {\n    this->activated.store(false);\n    RCLCPP_INFO(this->get_logger(), \"Reaching inactive state.\");\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n  }\n\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State &)\n  {\n    this->activated.store(true);\n    get_parameter(\"node_id\", node_id_);\n    get_parameter(\"slave_config\", slave_config_);\n    get_parameter(\"can_interface_name\", can_interface_name_);\n    run_thread = std::thread(std::bind(&BaseSlave::run, this));\n    RCLCPP_INFO(this->get_logger(), \"Reaching active state.\");\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n  }\n\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State &)\n  {\n    this->activated.store(false);\n    RCLCPP_INFO(this->get_logger(), \"Reaching inactive state.\");\n    if (run_thread.joinable())\n    {\n      run_thread.join();\n    }\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n  }\n\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State &)\n  {\n    this->activated.store(false);\n    RCLCPP_INFO(this->get_logger(), \"Reaching unconfigured state.\");\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n  }\n\n  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State &)\n  {\n    RCLCPP_INFO(this->get_logger(), \"Shutdown\");\n    return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;\n  }\n};\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_fake_slaves/include/canopen_fake_slaves/basic_slave.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef BASIC_SLAVE_HPP\n#define BASIC_SLAVE_HPP\n#include <lely/coapp/sdo_error.hpp>\n#include <lely/coapp/slave.hpp>\n#include <lely/ev/co_task.hpp>\n#include <lely/ev/loop.hpp>\n#include <lely/io2/linux/can.hpp>\n#include <lely/io2/posix/poll.hpp>\n#include <lely/io2/sys/io.hpp>\n#include <lely/io2/sys/sigset.hpp>\n#include <lely/io2/sys/timer.hpp>\n\n#include <fstream>\n#include <system_error>\n#include <thread>\n#include <typeindex>\n#include <typeinfo>\n\n#include \"canopen_fake_slaves/base_slave.hpp\"\n#include \"lifecycle_msgs/msg/state.hpp\"\n\nusing namespace lely;\nusing namespace std::chrono_literals;\nnamespace ros2_canopen\n{\nclass SimpleSlave : public canopen::BasicSlave\n{\npublic:\n  SimpleSlave(\n    io::TimerBase & timer, io::CanChannelBase & chan, const std::string & slave_config,\n    const std::string & slave_bin, uint8_t node_id)\n  : canopen::BasicSlave(timer, chan, slave_config, slave_bin, node_id)\n  {\n    const auto vendor_id = parse_vendor_id(slave_config);\n    if (vendor_id != 0)\n    {\n      try\n      {\n        this->OnRead<uint32_t>(\n          0x1018, 0x01,\n          [vendor_id](uint16_t, uint8_t, uint32_t & value) -> std::error_code\n          {\n            value = vendor_id;\n            return {};\n          });\n      }\n      catch (const lely::canopen::SdoError &)\n      {\n        // Leave the dictionary untouched if the callback cannot be registered.\n      }\n    }\n  }\n\n  SimpleSlave(\n    io::TimerBase & timer, io::CanChannelBase & chan, const std::string & slave_config,\n    uint8_t node_id)\n  : SimpleSlave(timer, chan, slave_config, \"\", node_id)\n  {\n  }\n\n  ~SimpleSlave()\n  {\n    if (message_thread.joinable())\n    {\n      message_thread.join();\n    }\n  }\n\nprotected:\n  std::thread message_thread;\n  static uint32_t parse_vendor_id(const std::string & slave_config)\n  {\n    std::ifstream stream(slave_config);\n    if (!stream.is_open())\n    {\n      return 0;\n    }\n\n    std::string line;\n    while (std::getline(stream, line))\n    {\n      auto pos = line.find(\"VendorNumber=\");\n      if (pos == std::string::npos)\n      {\n        continue;\n      }\n\n      auto value_part = line.substr(pos + std::string(\"VendorNumber=\").length());\n      try\n      {\n        return static_cast<uint32_t>(std::stoul(value_part, nullptr, 0));\n      }\n      catch (const std::exception &)\n      {\n        return 0;\n      }\n    }\n\n    return 0;\n  }\n  /**\n   * @brief This function gets an object value through the typed interface.\n   * Only supports object types that can fit in a 32-bit container.\n   * @param idx The index of the PDO.\n   * @param subidx The subindex of the PDO.\n   * @return value of object stored in a 32-bit container\n   */\n  uint32_t GetValue(const uint16_t idx, const uint8_t subidx) const noexcept\n  {\n    const std::type_index type((*this)[idx][subidx].Type());\n\n    uint32_t value{0};\n\n    if (type == std::type_index(typeid(bool)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<bool>());\n    }\n    else if (type == std::type_index(typeid(int8_t)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<int8_t>());\n    }\n    else if (type == std::type_index(typeid(int16_t)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<int16_t>());\n    }\n    else if (type == std::type_index(typeid(int32_t)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<int32_t>());\n    }\n    else if (type == std::type_index(typeid(float)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<float>());\n    }\n    else if (type == std::type_index(typeid(uint8_t)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<uint8_t>());\n    }\n    else if (type == std::type_index(typeid(uint16_t)))\n    {\n      value = static_cast<uint32_t>((*this)[idx][subidx].Get<uint16_t>());\n    }\n    else if (type == std::type_index(typeid(uint32_t)))\n    {\n      value = (*this)[idx][subidx].Get<uint32_t>();\n    }\n    else\n    {\n      value = (*this)[idx][subidx].Get<uint32_t>();\n    }\n\n    return value;\n  }\n\n  /**\n   * @brief This function is called when a value is written to the local object dictionary by an SDO\n   * or RPDO. Also copies the RPDO value to TPDO. A function from the class Device\n   * @param idx The index of the PDO.\n   * @param subidx The subindex of the PDO.\n   */\n  void OnWrite(uint16_t idx, uint8_t subidx) noexcept override\n  {\n    (*this)[0x4001][0] = this->GetValue(idx, subidx);\n    this->TpdoEvent(0);\n\n    // Publish periodic message\n    if (!message_thread.joinable())\n    {\n      message_thread = std::thread(std::bind(&SimpleSlave::fake_periodic_messages, this));\n    }\n  }\n\n  /**\n   * @brief This function is attached to a thread and sends periodic messages\n   * via 0x4004\n   */\n  void fake_periodic_messages()\n  {\n    // If ros is running, send messages\n    while (rclcpp::ok())\n    {\n      uint32_t val = 0x1122;\n      (*this)[0x4001][0] = val;  // refresh TPDO-mapped UNSIGNED32 without touching config entries\n      this->TpdoEvent(0);\n      // 100 ms sleep - 10 Hz\n      std::this_thread::sleep_for(std::chrono::milliseconds(100));\n    }\n  }\n};\n\nclass BasicSlave : public BaseSlave\n{\npublic:\n  explicit BasicSlave(const std::string & node_name, bool intra_process_comms = false)\n  : BaseSlave(node_name, intra_process_comms)\n  {\n  }\n\nprotected:\n  class ActiveCheckTask : public ev::CoTask\n  {\n  public:\n    ActiveCheckTask(io::Context * ctx, ev::Executor * exec, BasicSlave * slave) : CoTask(*exec)\n    {\n      slave_ = slave;\n      exec_ = exec;\n      ctx_ = ctx;\n    }\n\n  protected:\n    BasicSlave * slave_;\n    ev::Executor * exec_;\n    io::Context * ctx_;\n    virtual void operator()() noexcept\n    {\n      if (slave_->activated.load())\n      {\n      }\n      ctx_->shutdown();\n    }\n  };\n\n  void run() override\n  {\n    io::IoGuard io_guard;\n    io::Context ctx;\n    io::Poll poll(ctx);\n    ev::Loop loop(poll.get_poll());\n    auto exec = loop.get_executor();\n    io::Timer timer(poll, exec, CLOCK_MONOTONIC);\n    io::CanController ctrl(can_interface_name_.c_str());\n    io::CanChannel chan(poll, exec);\n    chan.open(ctrl);\n\n    auto sigset_ = lely::io::SignalSet(poll, exec);\n    // Watch for Ctrl+C or process termination.\n    sigset_.insert(SIGHUP);\n    sigset_.insert(SIGINT);\n    sigset_.insert(SIGTERM);\n\n    sigset_.submit_wait(\n      [&](int /*signo*/)\n      {\n        // If the signal is raised again, terminate immediately.\n        sigset_.clear();\n\n        // Perform a clean shutdown.\n        ctx.shutdown();\n      });\n\n    SimpleSlave slave(timer, chan, slave_config_.c_str(), \"\", node_id_);\n    slave.Reset();\n    ActiveCheckTask checktask(&ctx, &exec, this);\n\n    // timer.submit_wait()\n    RCLCPP_INFO(this->get_logger(), \"Created slave for node_id %i.\", node_id_);\n    loop.run();\n    ctx.shutdown();\n    RCLCPP_INFO(this->get_logger(), \"Stopped CANopen Event Loop.\");\n    rclcpp::shutdown();\n  }\n};\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_fake_slaves/include/canopen_fake_slaves/cia402_slave.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CIA402_SLAVE_HPP\n#define CIA402_SLAVE_HPP\n#include <lely/coapp/slave.hpp>\n#include <lely/ev/co_task.hpp>\n#include <lely/ev/loop.hpp>\n#include <lely/io2/linux/can.hpp>\n#include <lely/io2/posix/poll.hpp>\n#include <lely/io2/sys/io.hpp>\n#include <lely/io2/sys/sigset.hpp>\n#include <lely/io2/sys/timer.hpp>\n\n#include <atomic>\n#include <mutex>\n#include <thread>\n\n#include \"canopen_fake_slaves/base_slave.hpp\"\n#include \"canopen_fake_slaves/motion_generator.hpp\"\n#include \"lifecycle_msgs/msg/state.hpp\"\n\nusing namespace lely;\nusing namespace std::chrono_literals;\n\nnamespace ros2_canopen\n{\n\nclass CIA402MockSlave : public canopen::BasicSlave\n{\npublic:\n  explicit CIA402MockSlave(\n    io::TimerBase & timer, io::CanChannelBase & chan, const ::std::string & dcf_txt,\n    const ::std::string & dcf_bin = \"\", uint8_t id = 0xff)\n  : canopen::BasicSlave(timer, chan, dcf_txt, dcf_bin, id)\n  {\n    state.store(InternalState::Not_Ready_To_Switch_On);\n    status_word = 0x0;\n    operation_mode.store(No_Mode);\n    control_cycle_period = 0.01;\n    actual_position = 0.0;\n  }\n\n  virtual ~CIA402MockSlave()\n  {\n    if (profiled_position_mode.joinable())\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined profiled_position_mode thread.\");\n      profiled_position_mode.join();\n    }\n    if (cyclic_position_mode.joinable())\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined cyclic_position_mode thread.\");\n      cyclic_position_mode.join();\n    }\n    if (interpolated_position_mode.joinable())\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n      interpolated_position_mode.join();\n    }\n    if (homing_mode.joinable())\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n      homing_mode.join();\n    }\n    if (profiled_velocity_mode.joinable())\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n      profiled_velocity_mode.join();\n    }\n  }\n\nprotected:\n  enum InternalState\n  {\n    Unknown = 0,\n    Start = 0,\n    Not_Ready_To_Switch_On = 1,\n    Switch_On_Disabled = 2,\n    Ready_To_Switch_On = 3,\n    Switched_On = 4,\n    Operation_Enable = 5,\n    Quick_Stop_Active = 6,\n    Fault_Reaction_Active = 7,\n    Fault = 8,\n  };\n\n  enum StatusWord\n  {\n    SW_Ready_To_Switch_On = 0,\n    SW_Switched_On = 1,\n    SW_Operation_enabled = 2,\n    SW_Fault = 3,\n    SW_Voltage_enabled = 4,\n    SW_Quick_stop = 5,\n    SW_Switch_on_disabled = 6,\n    SW_Warning = 7,\n    SW_Manufacturer_specific0 = 8,\n    SW_Remote = 9,\n    SW_Target_reached = 10,\n    SW_Internal_limit = 11,\n    SW_Operation_mode_specific0 = 12,\n    SW_Operation_mode_specific1 = 13,\n    SW_Manufacturer_specific1 = 14,\n    SW_Manufacturer_specific2 = 15\n  };\n  enum ControlWord\n  {\n    CW_Switch_On = 0,\n    CW_Enable_Voltage = 1,\n    CW_Quick_Stop = 2,\n    CW_Enable_Operation = 3,\n    CW_Operation_mode_specific0 = 4,\n    CW_Operation_mode_specific1 = 5,\n    CW_Operation_mode_specific2 = 6,\n    CW_Fault_Reset = 7,\n    CW_Halt = 8,\n    CW_Operation_mode_specific3 = 9,\n    // CW_Reserved1=10,\n    CW_Manufacturer_specific0 = 11,\n    CW_Manufacturer_specific1 = 12,\n    CW_Manufacturer_specific2 = 13,\n    CW_Manufacturer_specific3 = 14,\n    CW_Manufacturer_specific4 = 15,\n  };\n\n  enum OperationMode\n  {\n    No_Mode = 0,\n    Profiled_Position = 1,\n    Velocity = 2,\n    Profiled_Velocity = 3,\n    Profiled_Torque = 4,\n    Reserved = 5,\n    Homing = 6,\n    Interpolated_Position = 7,\n    Cyclic_Synchronous_Position = 8,\n    Cyclic_Synchronous_Velocity = 9,\n    Cyclic_Synchronous_Torque = 10,\n  };\n\n  enum CiaRegister : uint16_t\n  {\n    ControlWord = 0x6040,\n    StatusWord = 0x6041,\n    OperationMode = 0x6060,\n    ModeOfOperationDisplay = 0x6061,\n    ActualPosition = 0x6064,\n    ActualVelocity = 0x606C,\n    TargetPosition = 0x607A,\n    SoftwarePositionLimits = 0x607D,\n    ProfileVelocity = 0x6081,\n    ProfileAcceleration = 0x6083,\n    InterpolationDataRecord = 0x60C1,\n    InterpolationTimePeriod = 0x60C2,\n    PositionOffset = 0x60B0,\n    TargetVelocity = 0x60FF,\n  };\n\n  std::atomic<bool> is_relative;\n  std::atomic<bool> is_running;\n  std::atomic<bool> is_halt;\n  std::atomic<bool> is_new_set_point;\n  std::atomic<int8_t> operation_mode;\n  std::atomic<int8_t> old_operation_mode;\n\n  std::mutex w_mutex;\n  uint16_t status_word;\n  uint16_t control_word;\n  std::atomic<InternalState> state;\n\n  std::thread profiled_position_mode;\n  std::thread profiled_velocity_mode;\n  std::thread cyclic_position_mode;\n  std::thread cyclic_velocity_mode;\n  std::thread interpolated_position_mode;\n  std::thread homing_mode;\n\n  double cycle_time;\n\n  std::mutex in_mode_mutex;\n  double actual_position;\n  double actual_speed;\n  double acceleration;\n  double control_cycle_period;\n\n  void run_profiled_position_mode()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"run_profiled_position_mode\");\n    double profile_speed =\n      static_cast<double>(((uint32_t)(*this)[CiaRegister::ProfileVelocity][0])) / 1000;\n    double profile_accerlation =\n      static_cast<double>(((uint32_t)(*this)[CiaRegister::ProfileAcceleration][0])) / 1000;\n    double actual_position =\n      static_cast<double>(((int32_t)(*this)[CiaRegister::ActualPosition][0])) / 1000.0;\n    double target_position =\n      static_cast<double>(((int32_t)(*this)[CiaRegister::TargetPosition][0])) / 1000.0;\n    double actual_speed =\n      static_cast<double>(((int32_t)(*this)[CiaRegister::ActualVelocity][0])) / 1000.0;\n    RCLCPP_INFO(\n      rclcpp::get_logger(\"cia402_slave\"), \"Profile_Speed %f, Profile Acceleration: %f\",\n      profile_speed, profile_accerlation);\n\n    while ((state.load() == InternalState::Operation_Enable) &&\n           (operation_mode.load() == Profiled_Position) && (rclcpp::ok()))\n    {\n      std::this_thread::sleep_for(std::chrono::milliseconds(10));\n      target_position =\n        static_cast<double>(((int32_t)(*this)[CiaRegister::TargetPosition][0])) / 1000.0;\n      clear_status_bit(SW_Operation_mode_specific0);\n      set_status_bit(SW_Voltage_enabled);\n      set_status_bit(SW_Remote);\n      if (target_position != actual_position)\n      {\n        clear_status_bit(SW_Operation_mode_specific0);\n        clear_status_bit(SW_Target_reached);\n        {\n          std::scoped_lock<std::mutex> lock(w_mutex);\n          (*this)[CiaRegister::StatusWord][0] = status_word;\n          this->TpdoEvent(1);\n        }\n        is_new_set_point.store(false);\n        RCLCPP_INFO(\n          rclcpp::get_logger(\"cia402_slave\"), \"Move from %f to %f\", actual_position,\n          target_position);\n        {\n          MotionGenerator gen(profile_accerlation, profile_speed, actual_position);\n\n          while (!gen.getFinished())\n          {\n            std::this_thread::sleep_for(std::chrono::milliseconds(10));\n            actual_position = gen.update(target_position);\n            actual_speed = gen.getVelocity();\n            (*this)[CiaRegister::ActualPosition][0] = (int32_t)(actual_position * 1000);\n            (*this)[CiaRegister::ActualVelocity][0] = (int32_t)(actual_speed * 1000);\n          }\n        }\n        RCLCPP_INFO(\n          rclcpp::get_logger(\"cia402_slave\"), \"Reached target position %f\", actual_position);\n        clear_status_bit(SW_Operation_mode_specific0);\n        set_status_bit(SW_Target_reached);\n        {\n          std::scoped_lock<std::mutex> lock(w_mutex);\n          (*this)[CiaRegister::StatusWord][0] = status_word;\n          this->TpdoEvent(1);\n        }\n      }\n    }\n  }\n  void run_cyclic_position_mode()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"run_cyclic_position_mode\");\n    int32_t min_pos = (int32_t)(*this)[CiaRegister::SoftwarePositionLimits][1];\n    int32_t max_pos = (int32_t)(*this)[CiaRegister::SoftwarePositionLimits][2];\n    uint8_t int_period = (*this)[CiaRegister::InterpolationTimePeriod][1];\n    int32_t offset = (*this)[CiaRegister::PositionOffset][0];\n    int8_t index = (*this)[CiaRegister::InterpolationTimePeriod][2];\n\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Lower Software Limit: %d\", min_pos);\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Upper Software Limit: %d\", max_pos);\n    RCLCPP_INFO(\n      rclcpp::get_logger(\"cia402_slave\"), \"Control Cycle: %hhu + 10^%hhd\", int_period, index);\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Offset: %d\", offset);\n\n    double cp_min_position = min_pos / 1000;\n    double cp_max_position = max_pos / 1000;\n    double cp_interpolation_period = int_period * std::pow(10.0, index);\n    double cp_offset = (double)(offset / 1000.0);\n    int ccp_millis = (int)(control_cycle_period * std::pow(10.0, 3));\n    int32_t act_pos;\n    while ((state.load() == InternalState::Operation_Enable) &&\n           (operation_mode.load() == Cyclic_Synchronous_Position) && (rclcpp::ok()))\n    {\n      act_pos = (*this)[CiaRegister::TargetPosition][0];\n      double target_position = (act_pos) / 1000 - cp_offset;      // m\n      double position_delta = target_position - actual_position;  // m\n      double speed = position_delta / cp_interpolation_period;    // m/s\n      double increment = control_cycle_period * speed;            // m\n      (*this)[CiaRegister::ActualVelocity][0] = (int32_t)speed * 1000;\n      if (\n        (target_position < cp_max_position) && (target_position > cp_min_position) &&\n        (std::abs(position_delta) > 0.001))\n      {\n        while ((std::abs(actual_position - target_position) > 0.001) && (rclcpp::ok()))\n        {\n          std::this_thread::sleep_for(std::chrono::milliseconds(ccp_millis));\n          actual_position += increment;\n          (*this)[CiaRegister::ActualPosition][0] = (int32_t)actual_position * 1000;\n          if (std::abs(actual_position - target_position) < 0.001)\n          {\n            RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Reached Target %f\", target_position);\n          }\n        }\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(ccp_millis));\n    }\n  }\n\n  void run_interpolated_position_mode()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"run_interpolated_position_mode\");\n    // Retrieve parameters from the object dictionary\n    double interpolation_period =\n      static_cast<double>((uint8_t)(*this)[CiaRegister::InterpolationTimePeriod][1]);\n    double target_position =\n      static_cast<double>((int32_t)(*this)[CiaRegister::InterpolationDataRecord][1]);\n\n    // int32_t offset = (*this)[CiaRegister::PositionOffset][0];\n\n    // Convert parameters to SI units\n    interpolation_period *=\n      std::pow(10.0, static_cast<double>((int8_t)(*this)[CiaRegister::InterpolationTimePeriod][2]));\n    target_position /= 1000.0;\n    double actual_position =\n      static_cast<double>((int32_t)(*this)[CiaRegister::ActualPosition][0]) / 1000.0;\n\n    RCLCPP_INFO(\n      rclcpp::get_logger(\"cia402_slave\"), \"Interpolation Period: %f\", interpolation_period);\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Target position: %f\", target_position);\n\n    while ((state.load() == InternalState::Operation_Enable) &&\n           (operation_mode.load() == Interpolated_Position) && (rclcpp::ok()))\n    {\n      std::this_thread::sleep_for(\n        std::chrono::milliseconds(static_cast<int>(interpolation_period * 1000)));\n\n      target_position =\n        static_cast<double>((int32_t)(*this)[CiaRegister::InterpolationDataRecord][1]) / 1000.0;\n\n      if (target_position != actual_position)\n      {\n        double position_delta = target_position - actual_position;\n        double position_increment = position_delta / 20;\n        clear_status_bit(SW_Operation_mode_specific0);\n        clear_status_bit(SW_Target_reached);\n        {\n          std::scoped_lock<std::mutex> lock(w_mutex);\n          (*this)[CiaRegister::StatusWord][0] = status_word;\n          this->TpdoEvent(1);\n        }\n\n        while ((std::abs(actual_position - target_position) > 0.001) && (rclcpp::ok()))\n        {\n          std::this_thread::sleep_for(std::chrono::milliseconds(1));\n          actual_position += position_increment;\n          (*this)[CiaRegister::ActualPosition][0] = static_cast<int32_t>(actual_position * 1000);\n          (*this)[CiaRegister::ActualVelocity][0] = static_cast<int32_t>(position_increment * 1000);\n        }\n\n        actual_position = target_position;\n\n        RCLCPP_DEBUG(rclcpp::get_logger(\"cia402_slave\"), \"Reached target: %f\", actual_position);\n        clear_status_bit(SW_Operation_mode_specific0);\n        set_status_bit(SW_Target_reached);\n        {\n          std::lock_guard<std::mutex> lock(w_mutex);\n          (*this)[CiaRegister::StatusWord][0] = status_word;\n          this->TpdoEvent(1);\n        }\n      }\n    }\n  }\n\n  void run_profile_velocity_mode()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"run_profile_velocity_mode\");\n    double actual_position =\n      static_cast<double>(((int32_t)(*this)[CiaRegister::ActualPosition][0])) / 1000.0;\n    double target_velocity =\n      static_cast<double>(((int32_t)(*this)[CiaRegister::TargetVelocity][0])) / 1000.0;\n    double old_target = target_velocity;\n    double control_cycle_period_d = 0.01;\n    while ((state.load() == InternalState::Operation_Enable) &&\n           (operation_mode.load() == Profiled_Velocity) && (rclcpp::ok()))\n    {\n      actual_position =\n        static_cast<double>(((int32_t)(*this)[CiaRegister::ActualPosition][0])) / 1000.0;\n      target_velocity =\n        static_cast<double>(((int32_t)(*this)[CiaRegister::TargetVelocity][0])) / 1000.0;\n      if (old_target != target_velocity)\n      {\n        old_target = target_velocity;\n        RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"New target velocity: %f\", target_velocity);\n      }\n      (*this)[CiaRegister::ActualVelocity][0] = (int32_t)(target_velocity * 1000);\n      (*this)[CiaRegister::ActualPosition][0] =\n        (int32_t)((actual_position + target_velocity * control_cycle_period_d) * 1000.0);\n      std::this_thread::sleep_for(\n        std::chrono::milliseconds(((int32_t)(control_cycle_period_d * 1000.0))));\n    }\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Leaving run_profile_velocity_mode\");\n  }\n\n  void run_homing_mode()\n  {\n    bool homed = false;\n    while ((state.load() == InternalState::Operation_Enable) && (operation_mode.load() == Homing) &&\n           (rclcpp::ok()))\n    {\n      bool start_homing = control_word & CW_Operation_mode_specific0;\n\n      if (start_homing && !homed)\n      {\n        set_status_bit(SW_Manufacturer_specific1);  // Motor active\n      }\n      else\n      {\n        homed = false;\n        continue;\n      }\n      {\n        std::lock_guard<std::mutex> lock(w_mutex);\n        (*this)[CiaRegister::StatusWord][0] = status_word;\n        this->TpdoEvent(1);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(100));\n\n      if (start_homing)\n      {\n        clear_status_bit(SW_Manufacturer_specific1);  // Motor inactive\n        set_status_bit(SW_Target_reached);            // Homing complete\n        set_status_bit(SW_Operation_mode_specific0);  // Homing attained\n        (*this)[CiaRegister::StatusWord][0] = status_word;\n        (*this)[CiaRegister::ActualPosition][0] = static_cast<int32_t>(0);\n        (*this)[CiaRegister::ActualVelocity][0] = static_cast<int32_t>(0);\n        homed = true;\n      }\n    }\n  }\n\n  void set_new_status_word_and_state()\n  {\n    switch (state.load())\n    {\n      case InternalState::Not_Ready_To_Switch_On:\n        on_not_ready_to_switch_on();\n        break;\n      case InternalState::Switch_On_Disabled:\n        on_switch_on_disabled();\n        break;\n      case InternalState::Ready_To_Switch_On:\n        on_ready_to_switch_on();\n        break;\n      case InternalState::Switched_On:\n        on_switched_on();\n        break;\n      case InternalState::Operation_Enable:\n        on_operation_enabled();\n        break;\n      case InternalState::Quick_Stop_Active:\n        on_quickstop_active();\n        break;\n      case InternalState::Fault_Reaction_Active:\n        break;\n      case InternalState::Fault:\n        RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Fault\");\n        break;\n      default:\n        break;\n    }\n  }\n\n  void set_status_bit(int bit)\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    status_word |= 1UL << bit;\n  }\n\n  void clear_status_bit(int bit)\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    status_word &= ~(1UL << bit);\n  }\n\n  void set_switch_on_disabled()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Switch_On_Disabled\");\n    state.store(InternalState::Switch_On_Disabled);\n    clear_status_bit(SW_Ready_To_Switch_On);\n    clear_status_bit(SW_Switched_On);\n    clear_status_bit(SW_Operation_enabled);\n    clear_status_bit(SW_Fault);\n    set_status_bit(SW_Switch_on_disabled);\n  }\n\n  void set_ready_to_switch_on()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Ready_To_Switch_On\");\n    state.store(InternalState::Ready_To_Switch_On);\n    set_status_bit(SW_Ready_To_Switch_On);\n    clear_status_bit(SW_Switched_On);\n    clear_status_bit(SW_Operation_enabled);\n    clear_status_bit(SW_Fault);\n    set_status_bit(SW_Quick_stop);\n    clear_status_bit(SW_Switch_on_disabled);\n  }\n\n  void set_switch_on()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Switched_On\");\n    state.store(InternalState::Switched_On);\n    set_status_bit(SW_Ready_To_Switch_On);\n    set_status_bit(SW_Switched_On);\n    clear_status_bit(SW_Operation_enabled);\n    clear_status_bit(SW_Fault);\n    set_status_bit(SW_Quick_stop);\n    clear_status_bit(SW_Switch_on_disabled);\n  }\n\n  void set_operation_enabled()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Operation_Enable\");\n    state.store(InternalState::Operation_Enable);\n    set_status_bit(SW_Ready_To_Switch_On);\n    set_status_bit(SW_Switched_On);\n    set_status_bit(SW_Operation_enabled);\n    clear_status_bit(SW_Fault);\n    set_status_bit(SW_Quick_stop);\n    clear_status_bit(SW_Switch_on_disabled);\n  }\n\n  void set_quick_stop()\n  {\n    RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Quick_Stop_Active\");\n    state.store(InternalState::Quick_Stop_Active);\n    set_status_bit(SW_Ready_To_Switch_On);\n    set_status_bit(SW_Switched_On);\n    set_status_bit(SW_Operation_enabled);\n    clear_status_bit(SW_Fault);\n    clear_status_bit(SW_Quick_stop);\n    clear_status_bit(SW_Switch_on_disabled);\n  }\n\n  void on_not_ready_to_switch_on() { set_switch_on_disabled(); }\n\n  void on_switch_on_disabled()\n  {\n    if (is_shutdown())\n    {\n      set_ready_to_switch_on();\n    }\n  }\n\n  void on_ready_to_switch_on()\n  {\n    if (is_disable_voltage())\n    {\n      set_switch_on_disabled();\n    }\n    if (is_switch_on())\n    {\n      set_switch_on();\n    }\n    if (is_faul_reset())\n    {\n      set_ready_to_switch_on();\n    }\n  }\n\n  void on_switched_on()\n  {\n    if (is_disable_voltage())\n    {\n      set_switch_on_disabled();\n    }\n    if (is_shutdown())\n    {\n      set_ready_to_switch_on();\n    }\n    if (is_enable_operation())\n    {\n      set_operation_enabled();\n    }\n  }\n\n  void on_operation_enabled()\n  {\n    if (is_disable_voltage())\n    {\n      set_switch_on_disabled();\n    }\n    if (is_shutdown())\n    {\n      set_ready_to_switch_on();\n    }\n    if (is_switch_on())\n    {\n      set_switch_on();\n    }\n    if (is_quickstop())\n    {\n      set_quick_stop();\n    }\n    {\n      std::scoped_lock<std::mutex> lock(w_mutex);\n      is_relative.store(((control_word >> 6) & 1U) == 1U);\n      is_halt.store(((control_word >> 8) & 1U) == 1U);\n      is_new_set_point.store(((control_word >> 4) & 1U) == 1U);\n    }\n\n    if (old_operation_mode.load() != operation_mode.load())\n    {\n      // Clear homing-related/ack bits on mode change so new targets are accepted\n      clear_status_bit(SW_Operation_mode_specific0);\n      clear_status_bit(SW_Target_reached);\n      {\n        std::scoped_lock<std::mutex> lock(w_mutex);\n        (*this)[0x6041][0] = status_word;\n        this->TpdoEvent(1);\n      }\n      if (profiled_position_mode.joinable())\n      {\n        RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined profiled_position_mode thread.\");\n        profiled_position_mode.join();\n      }\n      if (cyclic_position_mode.joinable())\n      {\n        RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Joined cyclic_position_mode thread.\");\n        cyclic_position_mode.join();\n      }\n      if (interpolated_position_mode.joinable())\n      {\n        RCLCPP_INFO(\n          rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n        interpolated_position_mode.join();\n      }\n      if (homing_mode.joinable())\n      {\n        RCLCPP_INFO(\n          rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n        homing_mode.join();\n      }\n      if (profiled_velocity_mode.joinable())\n      {\n        RCLCPP_INFO(\n          rclcpp::get_logger(\"cia402_slave\"), \"Joined interpolated_position_mode thread.\");\n        profiled_velocity_mode.join();\n      }\n      old_operation_mode.store(operation_mode.load());\n      switch (operation_mode.load())\n      {\n        case Cyclic_Synchronous_Position:\n          start_sync_pos_mode();\n          break;\n        case Profiled_Position:\n          start_profile_pos_mode();\n          break;\n        case Interpolated_Position:\n          start_interpolated_pos_mode();\n          break;\n        case Homing:\n          start_homing_mode();\n          break;\n        case Profiled_Velocity:\n          start_profile_velocity_mode();\n          break;\n        default:\n          break;\n      }\n    }\n  }\n\n  void start_sync_pos_mode()\n  {\n    cyclic_position_mode = std::thread(std::bind(&CIA402MockSlave::run_cyclic_position_mode, this));\n  }\n\n  void start_profile_pos_mode()\n  {\n    profiled_position_mode =\n      std::thread(std::bind(&CIA402MockSlave::run_profiled_position_mode, this));\n  }\n\n  void start_interpolated_pos_mode()\n  {\n    interpolated_position_mode =\n      std::thread(std::bind(&CIA402MockSlave::run_interpolated_position_mode, this));\n  }\n\n  void start_homing_mode()\n  {\n    homing_mode = std::thread(std::bind(&CIA402MockSlave::run_homing_mode, this));\n  }\n\n  void start_profile_velocity_mode()\n  {\n    profiled_velocity_mode =\n      std::thread(std::bind(&CIA402MockSlave::run_profile_velocity_mode, this));\n  }\n\n  void on_quickstop_active()\n  {\n    if (is_enable_operation())\n    {\n      set_operation_enabled();\n    }\n    if (is_disable_voltage())\n    {\n      set_switch_on_disabled();\n    }\n  }\n\n  bool is_shutdown()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_unset = ((control_word >> CW_Fault_Reset) & 1U) == 0U;\n    bool qs_set = ((control_word >> CW_Quick_Stop) & 1U) == 1U;\n    bool ev_set = ((control_word >> CW_Enable_Voltage) & 1U) == 1U;\n    bool so_unset = ((control_word >> CW_Switch_On) & 1U) == 0U;\n\n    if (fr_unset && qs_set && ev_set && so_unset)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Shutdown.\");\n      return true;\n    }\n    return false;\n  }\n\n  bool is_disable_voltage()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_unset = ((control_word >> CW_Fault_Reset) & 1U) == 0U;\n    bool ev_unset = ((control_word >> CW_Enable_Voltage) & 1U) == 0U;\n\n    if (fr_unset && ev_unset)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Disable Voltage.\");\n      return true;\n    }\n    return false;\n  }\n\n  bool is_switch_on()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_unset = ((control_word >> CW_Fault_Reset) & 1U) == 0U;\n    bool eo_unset = ((control_word >> CW_Enable_Operation) & 1U) == 0U;\n    bool qs_set = ((control_word >> CW_Quick_Stop) & 1U) == 1U;\n    bool ev_set = ((control_word >> CW_Enable_Voltage) & 1U) == 1U;\n    bool so_set = ((control_word >> CW_Switch_On) & 1U) == 1U;\n    if (fr_unset && eo_unset && qs_set && ev_set && so_set)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Switch On.\");\n      return true;\n    }\n    return false;\n  }\n\n  bool is_enable_operation()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_unset = ((control_word >> CW_Fault_Reset) & 1U) == 0U;\n    bool eo_set = ((control_word >> CW_Enable_Operation) & 1U) == 1U;\n    bool qs_set = ((control_word >> CW_Quick_Stop) & 1U) == 1U;\n    bool ev_set = ((control_word >> CW_Enable_Voltage) & 1U) == 1U;\n    bool so_set = ((control_word >> CW_Switch_On) & 1U) == 1U;\n    if (fr_unset && eo_set && qs_set && ev_set && so_set)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Enable Operation.\");\n      return true;\n    }\n    return false;\n  }\n\n  bool is_quickstop()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_unset = ((control_word >> CW_Fault_Reset) & 1U) == 0U;\n    bool qs_unset = ((control_word >> CW_Quick_Stop) & 1U) == 0U;\n    bool ev_set = ((control_word >> CW_Enable_Voltage) & 1U) == 1U;\n    if (fr_unset && qs_unset && ev_set)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Quick Stop.\");\n      return true;\n    }\n    return false;\n  }\n\n  bool is_faul_reset()\n  {\n    std::scoped_lock<std::mutex> lock(w_mutex);\n    bool fr_set = ((control_word >> CW_Fault_Reset) & 1U) == 1U;\n    if (fr_set)\n    {\n      RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Received Fault Reset.\");\n      return true;\n    }\n    return false;\n  }\n  // This function gets called every time a value is written to the local object\n  // dictionary by an SDO or RPDO.\n  void OnWrite(uint16_t idx, uint8_t subidx) noexcept override\n  {\n    // System State\n    if (idx == CiaRegister::ControlWord && subidx == 0)\n    {\n      {\n        std::scoped_lock<std::mutex> lock(w_mutex);\n        control_word = (*this)[CiaRegister::ControlWord][0];\n      }\n      set_new_status_word_and_state();\n      {\n        std::scoped_lock<std::mutex> lock(w_mutex);\n        (*this)[CiaRegister::StatusWord][0] = status_word;\n        this->TpdoEvent(1);\n      }\n    }\n    // Operation Mode\n    if (idx == CiaRegister::OperationMode && subidx == 0)\n    {\n      int8_t mode = (*this)[CiaRegister::OperationMode][0];\n      switch (mode)\n      {\n        case No_Mode:\n        case Profiled_Position:\n        case Velocity:\n        case Profiled_Velocity:\n        case Profiled_Torque:\n        case Reserved:\n        case Homing:\n        case Interpolated_Position:\n        case Cyclic_Synchronous_Position:\n        case Cyclic_Synchronous_Velocity:\n        case Cyclic_Synchronous_Torque:\n          operation_mode.store(mode);\n          break;\n        default:\n          std::cout << \"Error: Master tried to set unknown operation mode.\" << std::endl;\n      }\n      // RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Switched to mode %hhi.\", mode);\n      (*this)[CiaRegister::ModeOfOperationDisplay][0] = (int8_t)(mode);\n      this->TpdoEvent(1);\n    }\n  }\n};\n\nclass DelayedBootSlave : public ros2_canopen::CIA402MockSlave\n{\npublic:\n  using ros2_canopen::CIA402MockSlave::CIA402MockSlave;\n\n  void DelayedReset()\n  {\n    RCLCPP_WARN(rclcpp::get_logger(\"cia402_slave\"), \"Delaying CANopen Boot-Up Frame...\");\n    std::thread(\n      [this]()\n      {\n        std::this_thread::sleep_for(std::chrono::seconds(1));\n        RCLCPP_INFO(rclcpp::get_logger(\"cia402_slave\"), \"Now sending Boot-Up frame...\");\n        this->canopen::BasicSlave::Reset();\n      })\n      .detach();\n  }\n};\n\nclass CIA402Slave : public BaseSlave\n{\npublic:\n  explicit CIA402Slave(const std::string & node_name, bool intra_process_comms = false)\n  : BaseSlave(node_name, intra_process_comms)\n  {\n  }\n\n  void run() override\n  {\n    io::IoGuard io_guard;\n    io::Context ctx;\n    io::Poll poll(ctx);\n    ev::Loop loop(poll.get_poll());\n    auto exec = loop.get_executor();\n    io::Timer timer(poll, exec, CLOCK_MONOTONIC);\n    io::CanController ctrl(can_interface_name_.c_str());\n    io::CanChannel chan(poll, exec);\n    chan.open(ctrl);\n\n    auto sigset_ = lely::io::SignalSet(poll, exec);\n    // Watch for Ctrl+C or process termination.\n    sigset_.insert(SIGHUP);\n    sigset_.insert(SIGINT);\n    sigset_.insert(SIGTERM);\n\n    sigset_.submit_wait(\n      [&](int /*signo*/)\n      {\n        // If the signal is raised again, terminate immediately.\n        sigset_.clear();\n\n        // Perform a clean shutdown.\n        ctx.shutdown();\n      });\n\n    DelayedBootSlave slave(timer, chan, slave_config_.c_str(), \"\", node_id_);\n    slave.DelayedReset();\n\n    RCLCPP_INFO(this->get_logger(), \"Created cia402 slave for node_id %i.\", node_id_);\n\n    loop.run();\n    ctx.shutdown();\n    RCLCPP_INFO(this->get_logger(), \"Stopped CANopen Event Loop.\");\n    rclcpp::shutdown();\n  }\n};\n}  // namespace ros2_canopen\n#endif\n"
  },
  {
    "path": "canopen_fake_slaves/include/canopen_fake_slaves/motion_generator.hpp",
    "content": "// Copyright 2023 ROS-Industrial\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef __MOTIONGENERATOR_H__\n#define __MOTIONGENERATOR_H__\n\n// Copyright (c) 2016 AerDronix, https://aerdronix.wordpress.com/\n//\n// Permission is hereby granted, free of charge, to any person obtaining a copy\n// of this software and associated documentation files (the \"Software\"), to deal\n// in the Software without restriction, including without limitation the rights\n// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell\n// copies of the Software, and to permit persons to whom the Software is\n// furnished to do so, subject to the following conditions:\n//\n// The above copyright notice and this permission notice shall be included in all\n// copies or substantial portions of the Software.\n//\n// THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\n// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\n// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\n// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\n// SOFTWARE.\n\n#include <chrono>\n/**\n * Generates the analytical solution for the trapezoidal motion.\n *\n * <p>\n * Usage:\n * // Includes\n * #include \"MotionGenerator.h\"\n *\n * Initialization\n *\n * @param int aVelMax maximum velocity (units/s)\n * @param int aAccMax maximum acceleration (units/s^2)\n * @param int aInitPos initial position (units)\n *\n // Define the MotionGenerator object\n MotionGenerator *trapezoidalProfile = new MotionGenerator(100, 400, 0);\n // Retrieve calculated position\n double positionRef = 1000;\n double position = trapezoidalProfile->update(positionRef)\n // Retrieve current velocity\n double velocity = trapezoidalProfile->getVelocity();\n // Retrieve current acceleration\n double acceleration = trapezoidalProfile->getAcceleration();\n // Check if profile is finished\n if (trapezoidalProfile->getFinished()) {};\n // Reset internal state\n trapezoidalProfile->reset();\n *\n * @author      AerDronix <aerdronix@gmail.com>\n * @web\t\thttps://aerdronix.wordpress.com/\n * @version     1.0\n * @since       2016-12-22\n */\n\nclass MotionGenerator\n{\npublic:\n  /**\n   * Constructor\n   *\n   * @param int aVelocityMax maximum velocity\n   * @param int aAccelerationMax maximum acceleration\n   */\n  MotionGenerator(double aMaxVel, double aMaxAcc, double aInitPos);\n\n  void init();\n\n  /**\n   * Updates the state, generating new setpoints\n   *\n   * @param aSetpoint The current setpoint.\n   */\n  double update(double aPosRef);\n  double getVelocity();\n  double getAcceleration();\n\n  bool getFinished();\n  void setMaxVelocity(double aMaxVel);\n  void setMaxAcceleration(double aMaxAcc);\n  void setInitPosition(double aInitPos);\n  void reset();\n\nprivate:\n  /**\n   * Increments the state number.\n   *\n   * @see\n    currentState\n   */\n  void calculateTrapezoidalProfile(double);\n  short int sign(double aVal);\n\n  double maxVel;\n  double maxAcc;\n  double initPos;\n  double pos;\n  double vel;\n  double acc;\n  double oldPos;\n  double oldPosRef;\n  double oldVel;\n\n  double dBrk;\n  double dAcc;\n  double dVel;\n  double dDec;\n  double dTot;\n\n  double tBrk;\n  double tAcc;\n  double tVel;\n  double tDec;\n\n  double velSt;\n\n  std::chrono::time_point<std::chrono::high_resolution_clock> oldTime;\n  std::chrono::time_point<std::chrono::high_resolution_clock> lastTime;\n  std::chrono::duration<double> deltaTime;\n\n  short int signM;  // 1 = positive change, -1 = negative change\n  bool shape;       // true = trapezoidal, false = triangular\n\n  bool isFinished;\n};\n#endif\n"
  },
  {
    "path": "canopen_fake_slaves/launch/basic_slave.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nimport sys\n\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\"))  # noqa\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\", \"..\", \"launch\"))  # noqa\n\nimport launch\nimport launch.actions\nimport launch.events\nfrom launch.substitutions import LaunchConfiguration, PythonExpression, TextSubstitution\nfrom launch.actions import DeclareLaunchArgument\n\nimport launch_ros\nimport launch_ros.events\nimport launch_ros.events.lifecycle\n\nimport lifecycle_msgs.msg\n\n\ndef generate_launch_description():\n    path_to_test = os.path.dirname(__file__)\n\n    node_id_arg = DeclareLaunchArgument(\n        \"node_id\",\n        default_value=TextSubstitution(text=\"2\"),\n        description=\"CANopen node id the mock slave shall have.\",\n    )\n\n    slave_config_arg = DeclareLaunchArgument(\n        \"slave_config\",\n        default_value=TextSubstitution(\n            text=os.path.join(path_to_test, \"..\", \"config\", \"simple_slave.eds\")\n        ),\n        description=\"Path to eds file to be used for the slave.\",\n    )\n\n    can_interface_name_arg = DeclareLaunchArgument(\n        \"can_interface_name\",\n        default_value=TextSubstitution(text=\"vcan0\"),\n        description=\"CAN interface to be used by mock slave.\",\n    )\n\n    node_name_arg = DeclareLaunchArgument(\n        \"node_name\",\n        default_value=TextSubstitution(text=\"basic_slave_node\"),\n        description=\"Name of the node.\",\n    )\n\n    slave_node = launch_ros.actions.LifecycleNode(\n        name=LaunchConfiguration(\"node_name\"),\n        namespace=\"\",\n        package=\"canopen_fake_slaves\",\n        output=\"screen\",\n        executable=\"basic_slave_node\",\n        parameters=[\n            {\n                \"slave_config\": LaunchConfiguration(\"slave_config\"),\n                \"node_id\": LaunchConfiguration(\"node_id\"),\n                \"can_interface_name\": LaunchConfiguration(\"can_interface_name\"),\n            }\n        ],\n    )\n    slave_inactive_state_handler = launch.actions.RegisterEventHandler(\n        launch_ros.event_handlers.OnStateTransition(\n            target_lifecycle_node=slave_node,\n            goal_state=\"inactive\",\n            handle_once=True,\n            entities=[\n                launch.actions.LogInfo(\n                    msg=\"node 'basic_slave_node' reached the 'inactive' state, 'activating'.\"\n                ),\n                launch.actions.EmitEvent(\n                    event=launch_ros.events.lifecycle.ChangeState(\n                        lifecycle_node_matcher=launch.events.matches_action(slave_node),\n                        transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE,\n                    )\n                ),\n            ],\n        ),\n    )\n    slave_configure = launch.actions.EmitEvent(\n        event=launch_ros.events.lifecycle.ChangeState(\n            lifecycle_node_matcher=launch.events.matches_action(slave_node),\n            transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,\n        )\n    )\n    ld = launch.LaunchDescription()\n    ld.add_action(node_id_arg)\n    ld.add_action(slave_config_arg)\n    ld.add_action(can_interface_name_arg)\n    ld.add_action(node_name_arg)\n    ld.add_action(slave_inactive_state_handler)\n    ld.add_action(slave_node)\n    ld.add_action(slave_configure)\n    return ld\n"
  },
  {
    "path": "canopen_fake_slaves/launch/cia402_slave.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nimport sys\n\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\"))  # noqa\nsys.path.insert(0, os.path.join(os.path.dirname(__file__), \"..\", \"..\", \"launch\"))  # noqa\n\nimport launch\nimport launch.actions\nimport launch.events\nfrom launch.substitutions import LaunchConfiguration, PythonExpression, TextSubstitution\nfrom launch.actions import DeclareLaunchArgument\n\nimport launch_ros\nimport launch_ros.events\nimport launch_ros.events.lifecycle\n\nimport lifecycle_msgs.msg\n\n\ndef generate_launch_description():\n    path_to_test = os.path.dirname(__file__)\n\n    node_id_arg = DeclareLaunchArgument(\n        \"node_id\",\n        default_value=TextSubstitution(text=\"2\"),\n        description=\"CANopen node id the mock slave shall have.\",\n    )\n\n    slave_config_arg = DeclareLaunchArgument(\n        \"slave_config\",\n        default_value=TextSubstitution(\n            text=os.path.join(path_to_test, \"..\", \"config\", \"cia402_slave.eds\")\n        ),\n        description=\"Path to eds file to be used for the slave.\",\n    )\n\n    can_interface_name_arg = DeclareLaunchArgument(\n        \"can_interface_name\",\n        default_value=TextSubstitution(text=\"vcan0\"),\n        description=\"CAN interface to be used by mock slave.\",\n    )\n\n    node_name_arg = DeclareLaunchArgument(\n        \"node_name\",\n        default_value=TextSubstitution(text=\"basic_slave_node\"),\n        description=\"Name of the node.\",\n    )\n\n    slave_node = launch_ros.actions.LifecycleNode(\n        name=LaunchConfiguration(\"node_name\"),\n        namespace=\"\",\n        package=\"canopen_fake_slaves\",\n        output=\"screen\",\n        executable=\"cia402_slave_node\",\n        parameters=[\n            {\n                \"slave_config\": LaunchConfiguration(\"slave_config\"),\n                \"node_id\": LaunchConfiguration(\"node_id\"),\n                \"can_interface_name\": LaunchConfiguration(\"can_interface_name\"),\n            }\n        ],\n    )\n    slave_inactive_state_handler = launch.actions.RegisterEventHandler(\n        launch_ros.event_handlers.OnStateTransition(\n            target_lifecycle_node=slave_node,\n            goal_state=\"inactive\",\n            handle_once=True,\n            entities=[\n                launch.actions.LogInfo(\n                    msg=\"node 'basic_slave_node' reached the 'inactive' state, 'activating'.\"\n                ),\n                launch.actions.EmitEvent(\n                    event=launch_ros.events.lifecycle.ChangeState(\n                        lifecycle_node_matcher=launch.events.matches_action(slave_node),\n                        transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE,\n                    )\n                ),\n            ],\n        ),\n    )\n    slave_configure = launch.actions.EmitEvent(\n        event=launch_ros.events.lifecycle.ChangeState(\n            lifecycle_node_matcher=launch.events.matches_action(slave_node),\n            transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,\n        )\n    )\n    ld = launch.LaunchDescription()\n    ld.add_action(node_id_arg)\n    ld.add_action(slave_config_arg)\n    ld.add_action(can_interface_name_arg)\n    ld.add_action(node_name_arg)\n    ld.add_action(slave_inactive_state_handler)\n    ld.add_action(slave_node)\n    ld.add_action(slave_configure)\n    return ld\n"
  },
  {
    "path": "canopen_fake_slaves/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_fake_slaves</name>\n  <version>0.3.2</version>\n  <description>Package with mock canopen slave</description>\n  <maintainer email=\"cmh@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <depend>lely_core_libraries</depend>\n  <depend>lifecycle_msgs</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_lifecycle</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_fake_slaves/src/basic_slave.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_fake_slaves/basic_slave.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n\nint main(int argc, char * argv[])\n{\n  rclcpp::InitOptions options;\n  options.shutdown_on_signal = true;\n  rclcpp::init(argc, argv, options, rclcpp::SignalHandlerOptions::All);\n  rclcpp::executors::SingleThreadedExecutor executor;\n  auto canopen_slave = std::make_shared<ros2_canopen::BasicSlave>(\"basic_slave\");\n  executor.add_node(canopen_slave->get_node_base_interface());\n  executor.spin();\n  return 0;\n}\n"
  },
  {
    "path": "canopen_fake_slaves/src/cia402_slave.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_fake_slaves/cia402_slave.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n\nint main(int argc, char * argv[])\n{\n  rclcpp::init(argc, argv);\n  rclcpp::executors::SingleThreadedExecutor executor;\n  auto canopen_slave = std::make_shared<ros2_canopen::CIA402Slave>(\"cia402_slave\");\n  executor.add_node(canopen_slave->get_node_base_interface());\n  executor.spin();\n  rclcpp::shutdown();\n  return 0;\n}\n"
  },
  {
    "path": "canopen_fake_slaves/src/motion_generator.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_fake_slaves/motion_generator.hpp\"\n#include <cmath>\n#include <iostream>\n\nMotionGenerator::MotionGenerator(double aMaxVel, double aMaxAcc, double aInitPos)\n: maxVel(aMaxVel), maxAcc(aMaxAcc), initPos(aInitPos), oldPosRef(aInitPos)\n{\n  init();\n}\n\nvoid MotionGenerator::init()\n{\n  // Time variables\n  oldTime = std::chrono::high_resolution_clock::now();\n  lastTime = oldTime;\n  deltaTime = std::chrono::milliseconds(0);\n\n  // State variables\n  reset();\n\n  // Misc\n  signM = 1;     // 1 = positive change, -1 = negative change\n  shape = true;  // true = trapezoidal, false = triangular\n  isFinished = false;\n}\n\ndouble MotionGenerator::update(double posRef)\n{\n  if (oldPosRef != posRef)  // reference changed\n  {\n    isFinished = false;\n    // Shift state variables\n    oldPosRef = posRef;\n    oldPos = pos;\n    oldVel = vel;\n    oldTime = lastTime;\n\n    // Calculate braking time and distance (in case is needed)\n    tBrk = abs(oldVel) / maxAcc;\n    dBrk = tBrk * abs(oldVel) / 2;\n\n    // Calculate Sign of motion\n    signM = sign(posRef - (oldPos + sign(oldVel) * dBrk));\n\n    if (signM != sign(oldVel))  // means brake is needed\n    {\n      tAcc = (maxVel / maxAcc);\n      dAcc = tAcc * (maxVel / 2);\n    }\n    else\n    {\n      tBrk = 0;\n      dBrk = 0;\n      tAcc = (maxVel - abs(oldVel)) / maxAcc;\n      dAcc = tAcc * (maxVel + abs(oldVel)) / 2;\n    }\n\n    // Calculate total distance to go after braking\n    dTot = abs(posRef - oldPos + signM * dBrk);\n\n    tDec = maxVel / maxAcc;\n    dDec = tDec * (maxVel) / 2;\n    dVel = dTot - (dAcc + dDec);\n    tVel = dVel / maxVel;\n\n    if (tVel > 0)  // trapezoidal shape\n      shape = true;\n    else  // triangular shape\n    {\n      shape = false;\n      // Recalculate distances and periods\n      if (signM != sign(oldVel))  // means brake is needed\n      {\n        velSt = sqrt(maxAcc * (dTot));\n        tAcc = (velSt / maxAcc);\n        dAcc = tAcc * (velSt / 2);\n      }\n      else\n      {\n        tBrk = 0;\n        dBrk = 0;\n        dTot = abs(posRef - oldPos);  // recalculate total distance\n        velSt = sqrt(0.5 * oldVel * oldVel + maxAcc * dTot);\n        tAcc = (velSt - abs(oldVel)) / maxAcc;\n        dAcc = tAcc * (velSt + abs(oldVel)) / 2;\n      }\n      tDec = velSt / maxAcc;\n      dDec = tDec * (velSt) / 2;\n    }\n  }\n\n  auto time = std::chrono::high_resolution_clock::now();  // current time\n  // Calculate time since last set-point change\n  deltaTime = (time - oldTime);\n  // Calculate new setpoint\n  calculateTrapezoidalProfile(posRef);\n  // Update last time\n  lastTime = time;\n\n  // calculateTrapezoidalProfile(setpoint);\n  return pos;\n}\n\nvoid MotionGenerator::calculateTrapezoidalProfile(double posRef)\n{\n  double t = deltaTime.count();  // conversion from milliseconds to seconds\n\n  if (shape)  // trapezoidal shape\n  {\n    if (t <= (tBrk + tAcc))\n    {\n      pos = oldPos + oldVel * t + signM * 0.5 * maxAcc * t * t;\n      vel = oldVel + signM * maxAcc * t;\n      acc = signM * maxAcc;\n    }\n    else if (t > (tBrk + tAcc) && t < (tBrk + tAcc + tVel))\n    {\n      pos = oldPos + signM * (-dBrk + dAcc + maxVel * (t - tBrk - tAcc));\n      vel = signM * maxVel;\n      acc = 0;\n    }\n    else if (t >= (tBrk + tAcc + tVel) && t < (tBrk + tAcc + tVel + tDec))\n    {\n      pos = oldPos + signM * (-dBrk + dAcc + dVel + maxVel * (t - tBrk - tAcc - tVel) -\n                              0.5 * maxAcc * (t - tBrk - tAcc - tVel) * (t - tBrk - tAcc - tVel));\n      vel = signM * (maxVel - maxAcc * (t - tBrk - tAcc - tVel));\n      acc = -signM * maxAcc;\n    }\n    else\n    {\n      pos = posRef;\n      vel = 0;\n      acc = 0;\n      isFinished = true;\n    }\n  }\n  else  // triangular shape\n  {\n    if (t <= (tBrk + tAcc))\n    {\n      pos = oldPos + oldVel * t + signM * 0.5 * maxAcc * t * t;\n      vel = oldVel + signM * maxAcc * t;\n      acc = signM * maxAcc;\n    }\n    else if (t > (tBrk + tAcc) && t < (tBrk + tAcc + tDec))\n    {\n      pos = oldPos + signM * (-dBrk + dAcc + velSt * (t - tBrk - tAcc) -\n                              0.5 * maxAcc * (t - tBrk - tAcc) * (t - tBrk - tAcc));\n      vel = signM * (velSt - maxAcc * (t - tBrk - tAcc));\n      acc = -signM * maxAcc;\n    }\n    else\n    {\n      pos = posRef;\n      vel = 0;\n      acc = 0;\n      isFinished = true;\n    }\n  }\n}\n\n// Getters and setters\nbool MotionGenerator::getFinished() { return isFinished; }\n\ndouble MotionGenerator::getVelocity() { return vel; }\n\ndouble MotionGenerator::getAcceleration() { return acc; }\n\nvoid MotionGenerator::setMaxVelocity(double aMaxVel) { maxVel = aMaxVel; }\n\nvoid MotionGenerator::setMaxAcceleration(double aMaxAcc) { maxAcc = aMaxAcc; }\n\nvoid MotionGenerator::setInitPosition(double aInitPos)\n{\n  initPos = aInitPos;\n  pos = aInitPos;\n  oldPos = aInitPos;\n  oldPosRef = aInitPos;\n}\n\nshort int MotionGenerator::sign(double aVal)\n{\n  if (aVal < 0)\n    return -1;\n  else if (aVal > 0)\n    return 1;\n  else\n  {\n    return 0;\n  }\n}\n\nvoid MotionGenerator::reset()\n{\n  // Reset all state variables\n\n  pos = initPos;\n  oldPos = initPos;\n  oldPosRef = initPos;\n  vel = 0;\n  acc = 0;\n  oldVel = 0;\n\n  dBrk = 0;\n  dAcc = 0;\n  dVel = 0;\n  dDec = 0;\n  dTot = 0;\n\n  tBrk = 0;\n  tAcc = 0;\n  tVel = 0;\n  tDec = 0;\n\n  velSt = 0;\n}\n"
  },
  {
    "path": "canopen_interfaces/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_interfaces\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n\n0.2.9 (2024-04-16)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Contributors: ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Lovro\n"
  },
  {
    "path": "canopen_interfaces/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_interfaces)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(rosidl_default_generators REQUIRED)\n# uncomment the following section in order to fill in\n# further dependencies manually.\n# find_package(<dependency> REQUIRED)\n\nrosidl_generate_interfaces(${PROJECT_NAME}\n  \"srv/COHeartbeatID.srv\"\n  \"srv/CONmtID.srv\"\n  \"srv/CORead.srv\"\n  \"srv/COReadID.srv\"\n  \"srv/COWrite.srv\"\n  \"srv/COWriteID.srv\"\n  \"srv/COTargetDouble.srv\"\n  \"srv/CONode.srv\"\n  \"msg/COData.msg\"\n)\n\n\nif(BUILD_TESTING)\n  find_package(ament_lint_auto REQUIRED)\n  # the following line skips the linter which checks for copyrights\n  # uncomment the line when a copyright and license is not present in all source files\n  #set(ament_cmake_copyright_FOUND TRUE)\n  # the following line skips cpplint (only works in a git repo)\n  # uncomment the line when this package is not in a git repo\n  #set(ament_cmake_cpplint_FOUND TRUE)\n  ament_lint_auto_find_test_dependencies()\nendif()\n\nament_package()\n"
  },
  {
    "path": "canopen_interfaces/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_interfaces/msg/COData.msg",
    "content": "uint16 index\nuint8 subindex\nuint32 data\n"
  },
  {
    "path": "canopen_interfaces/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_interfaces</name>\n  <version>0.3.2</version>\n  <description>Services and Messages for ros2_canopen stack</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n  <test_depend>ament_lint_common</test_depend>\n  <build_depend>rosidl_default_generators</build_depend>\n  <exec_depend>rosidl_default_runtime</exec_depend>\n  <member_of_group>rosidl_interface_packages</member_of_group>\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_interfaces/srv/COHeartbeatID.srv",
    "content": "uint8 nodeid\nuint16  heartbeat #ms\n---\nbool success\n"
  },
  {
    "path": "canopen_interfaces/srv/CONmtID.srv",
    "content": "uint8 nmtcommand\nuint8 nodeid\n---\nbool success\n"
  },
  {
    "path": "canopen_interfaces/srv/CONode.srv",
    "content": "uint8 nodeid\n---\nbool success\n"
  },
  {
    "path": "canopen_interfaces/srv/CORead.srv",
    "content": "uint16 index\nuint8 subindex\n---\nbool success\nuint32 data\n"
  },
  {
    "path": "canopen_interfaces/srv/COReadID.srv",
    "content": "uint8 CANOPEN_DATATYPE_INT8 = 0x02\nuint8 CANOPEN_DATATYPE_INT16 = 0x03\nuint8 CANOPEN_DATATYPE_INT32 = 0x04\nuint8 CANOPEN_DATATYPE_UINT8 = 0x05\nuint8 CANOPEN_DATATYPE_UINT16 = 0x06\nuint8 CANOPEN_DATATYPE_UINT32 = 0x07\n\nuint8 nodeid\nuint16 index\nuint8 subindex\n# 8 = uint8_t, 16 = uint16_t, 32 = uint32_t\nuint8 canopen_datatype\n---\nbool success\nuint32 data\n"
  },
  {
    "path": "canopen_interfaces/srv/COTargetDouble.srv",
    "content": "float64 target\n---\nbool success\n"
  },
  {
    "path": "canopen_interfaces/srv/COWrite.srv",
    "content": "uint16 index\nuint8 subindex\nuint32 data\n---\nbool success\n"
  },
  {
    "path": "canopen_interfaces/srv/COWriteID.srv",
    "content": "uint8 CANOPEN_DATATYPE_INT8 = 0x02\nuint8 CANOPEN_DATATYPE_INT16 = 0x03\nuint8 CANOPEN_DATATYPE_INT32 = 0x04\nuint8 CANOPEN_DATATYPE_UINT8 = 0x05\nuint8 CANOPEN_DATATYPE_UINT16 = 0x06\nuint8 CANOPEN_DATATYPE_UINT32 = 0x07\n\nint8 nodeid\nuint16 index\nuint8 subindex\nuint32 data\n# 8 = uint8_t, 16 = uint16_t, 32 = uint32_t\nuint8 canopen_datatype\n---\nbool success\n"
  },
  {
    "path": "canopen_master_driver/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_master_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.2.9 (2024-04-16)\n------------------\n* Add timeouts\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.3.2 (2025-12-05)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Merge pull request `#220 <https://github.com/ros-industrial/ros2_canopen/issues/220>`_ from ipa-vsp/feature/timeout-config\n  Add timeouts\n* Revert timeout change to master since I'm not providing a way to set that timeout.\n* Make 20ms a default argument of the master & driver bridges.\n* timeout for booting slave\n* Contributors: Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix master lifecycle\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos\n"
  },
  {
    "path": "canopen_master_driver/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_master_driver)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_ros REQUIRED)\nfind_package(canopen_core REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(lely_core_libraries REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\n\nadd_library(lely_master_bridge\n  src/lely_master_bridge.cpp\n)\ntarget_compile_features(lely_master_bridge PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lely_master_bridge PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lely_master_bridge PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>\n  ${lely_core_libraries_INCLUDE_DIRS}\n)\ntarget_link_libraries(lely_master_bridge PUBLIC\n  ${lely_core_libraries_LIBRARIES}\n  canopen_core::node_canopen_master\n)\n\n\nadd_library(node_canopen_basic_master\n  src/node_interfaces/node_canopen_basic_master.cpp\n)\ntarget_compile_features(node_canopen_basic_master PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_basic_master PUBLIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_basic_master PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\ntarget_link_libraries(node_canopen_basic_master PUBLIC\n  ${canopen_interfaces_TARGETS}\n  canopen_core::node_canopen_master\n  lely_master_bridge\n)\n\n\n\nadd_library(lifecycle_master_driver\n  src/lifecycle_master_driver.cpp\n)\ntarget_compile_features(lifecycle_master_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lifecycle_master_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lifecycle_master_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(lifecycle_master_driver PUBLIC\n  canopen_core::node_canopen_master\n  node_canopen_basic_master\n  rclcpp_components::component\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(lifecycle_master_driver PRIVATE \"CANOPEN_MASTER_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(lifecycle_master_driver \"ros2_canopen::LifecycleMasterDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::LifecycleMasterDriver;$<TARGET_FILE:lifecycle_master_driver >\\n\")\n\n\n\n\nadd_library(master_driver\n  src/master_driver.cpp\n)\ntarget_compile_features(master_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(master_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(master_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(master_driver PUBLIC\n  canopen_core::node_canopen_master\n  node_canopen_basic_master\n  rclcpp_components::component\n)\n\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(master_driver PRIVATE \"CANOPEN_MASTER_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(master_driver \"ros2_canopen::MasterDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::MasterDriver;$<TARGET_FILE:master_driver >\\n\")\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\ninstall(\n  TARGETS lifecycle_master_driver master_driver node_canopen_basic_master lely_master_bridge\n  EXPORT export_${PROJECT_NAME}\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  RUNTIME DESTINATION bin\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_gtest REQUIRED)\n  add_subdirectory(test)\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  master_driver\n  lifecycle_master_driver\n  node_canopen_basic_master\n  lely_master_bridge\n)\n\nament_export_targets(\n  export_${PROJECT_NAME}\n)\n\nament_export_dependencies(\n  canopen_core\n  canopen_interfaces\n  lely_core_libraries\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_master_driver/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/lely_master_bridge.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef LELY_MASTER_BRIDGE_HPP\n#define LELY_MASTER_BRIDGE_HPP\n\n#include <lely/ev/loop.hpp>\n#include <lely/io2/posix/poll.hpp>\n#include \"lely/coapp/master.hpp\"\n\n#include <chrono>\n#include <condition_variable>\n#include <future>\n#include <memory>\n#include <mutex>\n#include \"canopen_core/exchange.hpp\"\n\nusing namespace std::literals::chrono_literals;\nnamespace ros2_canopen\n{\n/**\n * @brief Lely Master Bridge\n *\n * Creates services to pass values between the CANopen executor and ROS executor.\n * This is important because certain functions can only be called from within\n * the thread of the CANopen executor.\n *\n */\nclass LelyMasterBridge : public lely::canopen::AsyncMaster\n{\n  std::shared_ptr<std::promise<COData>>\n    sdo_read_data_promise;  ///< Pointer to Promise for read service calls.\n  std::shared_ptr<std::promise<bool>>\n    sdo_write_data_promise;          ///< Pointer to Promise for write service calls\n  std::promise<bool> nmt_promise;    ///< Pointer to Promise for nmt service calls\n  std::mutex sdo_mutex;              ///< Mutex to guard sdo objects\n  bool running;                      ///< Bool to indicate whether an sdo call is running\n  std::condition_variable sdo_cond;  ///< Condition variable to sync service calls (one at a time)\n  uint8_t node_id;                   ///< Node id of the master\n\npublic:\n  /**\n   * @brief Construct a new Lely Master Bridge object\n   *\n   * @param [in] exec         Pointer to the executor\n   * @param [in] timer        Pointer to the timer\n   * @param [in] chan         Pointer to the channel\n   * @param [in] dcf_txt      Path to the DCF file\n   * @param [in] dcf_bin      Path to the DCF bin file\n   * @param [in] id           CANopen node id of the master\n   */\n  LelyMasterBridge(\n    ev_exec_t * exec, lely::io::TimerBase & timer, lely::io::CanChannelBase & chan,\n    const std::string & dcf_txt, const std::string & dcf_bin = \"\", uint8_t id = (uint8_t)255U)\n  : lely::canopen::AsyncMaster(exec, timer, chan, dcf_txt, dcf_bin, id), node_id(id)\n  {\n  }\n\n  /**\n   * @brief Asynchronous call for writing to an SDO\n   *\n   * @param [in] id               CANopen node id of the target device\n   * @param [in] data             Data to write\n   * @param [in] datatype         Datatype of the data to write\n   * @return std::future<bool>    A future that indicates if the\n   * write Operation was successful.\n   */\n  std::future<bool> async_write_sdo(uint8_t id, COData data, uint8_t datatype);\n\n  /**\n   * @brief\n   *\n   * @param [in] id               CANopen node id of the target device\n   * @param [in] data             Data to read, value is disregarded\n   * @param [in] datatype         Datatype of the data to read\n   * @return std::future<COData>  A future that returns the read result\n   * once the process finished.\n   */\n  std::future<COData> async_read_sdo(uint8_t id, COData data, uint8_t datatype);\n\n  /**\n   * @brief async_write_nmt\n   *\n   * @param id\n   * @param command\n   * @return std::future<bool>\n   *\n   */\n  std::future<bool> async_write_nmt(uint8_t id, uint8_t command);\n\n  template <typename T>\n  void submit_write_sdo(uint8_t id, uint16_t idx, uint8_t subidx, T value)\n  {\n    this->SubmitWrite(\n      this->GetExecutor(), id, idx, subidx, value,\n      [this](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec) mutable\n      {\n        if (ec)\n        {\n          this->sdo_write_data_promise->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncDownload\"));\n        }\n        else\n        {\n          this->sdo_write_data_promise->set_value(true);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      20ms);\n  }\n\n  template <typename T>\n  void submit_read_sdo(uint8_t id, uint16_t idx, uint8_t subidx)\n  {\n    this->SubmitRead<T>(\n      this->GetExecutor(), id, idx, subidx,\n      [this](uint8_t id, uint16_t idx, uint8_t subidx, ::std::error_code ec, T value) mutable\n      {\n        if (ec)\n        {\n          this->sdo_read_data_promise->set_exception(\n            lely::canopen::make_sdo_exception_ptr(id, idx, subidx, ec, \"AsyncUpload\"));\n        }\n        else\n        {\n          COData codata = {idx, subidx, 0U};\n          std::memcpy(&codata.data_, &value, sizeof(T));\n          this->sdo_read_data_promise->set_value(codata);\n        }\n        std::unique_lock<std::mutex> lck(this->sdo_mutex);\n        this->running = false;\n        this->sdo_cond.notify_one();\n      },\n      20ms);\n  }\n};\n\n}  // namespace ros2_canopen\n\n#endif  // LELY_MASTER_BRIDGE_HPP\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/lifecycle_master_driver.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef LIFECYCLE_MASTER_DRIVER_HPP\n#define LIFECYCLE_MASTER_DRIVER_HPP\n\n#include <atomic>\n#include <memory>\n#include <thread>\n\n#include \"canopen_core/master_node.hpp\"\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle Master Node\n *\n * This class implements the Lifecycle master interface.\n * It uses the Lely Master Bridge and exposes a ROS node\n * interface.\n *\n */\nclass LifecycleMasterDriver : public ros2_canopen::LifecycleCanopenMaster\n{\n  std::shared_ptr<node_interfaces::NodeCanopenBasicMaster<rclcpp_lifecycle::LifecycleNode>>\n    node_canopen_basic_master_;\n\npublic:\n  explicit LifecycleMasterDriver(const rclcpp::NodeOptions & node_options);\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/master_driver.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef MASTER_DRIVER_HPP\n#define MASTER_DRIVER_HPP\n\n#include \"canopen_core/master_node.hpp\"\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Master Node\n *\n * This class implements the Lifecycle master interface.\n * It uses the Lely Master Bridge and exposes a ROS node\n * interface.\n *\n */\nclass MasterDriver : public ros2_canopen::CanopenMaster\n{\n  std::shared_ptr<node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>> node_canopen_basic_master_;\n\npublic:\n  explicit MasterDriver(const rclcpp::NodeOptions & node_options);\n};\n\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_BASIC_MASTER_HPP_\n#define NODE_CANOPEN_BASIC_MASTER_HPP_\n\n#include \"canopen_core/node_interfaces/node_canopen_master.hpp\"\n#include \"canopen_interfaces/srv/co_read_id.hpp\"\n#include \"canopen_interfaces/srv/co_write_id.hpp\"\n#include \"canopen_master_driver/lely_master_bridge.hpp\"\n\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\ntemplate <class NODETYPE>\nclass NodeCanopenBasicMaster : public ros2_canopen::node_interfaces::NodeCanopenMaster<NODETYPE>\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  std::shared_ptr<LelyMasterBridge> master_bridge_;\n  rclcpp::Service<canopen_interfaces::srv::COReadID>::SharedPtr sdo_read_service;\n  rclcpp::Service<canopen_interfaces::srv::COWriteID>::SharedPtr sdo_write_service;\n\npublic:\n  NodeCanopenBasicMaster(NODETYPE * node)\n  : ros2_canopen::node_interfaces::NodeCanopenMaster<NODETYPE>(node)\n  {\n    this->activated_.load();\n    RCLCPP_INFO(this->node_->get_logger(), \"NodeCanopenBasicMaster\");\n  }\n  virtual ~NodeCanopenBasicMaster() {}\n\n  virtual void activate(bool called_from_base) override;\n  virtual void deactivate(bool called_from_base) override;\n  virtual void init(bool called_from_base) override;\n\n  /**\n   * @brief Read Service Data Object\n   *\n   * This Service is only available when the node is in active lifecycle state.\n   * It will return with success false in any other lifecycle state and log an\n   * RCLCPP_ERROR.\n   *\n   * @param request\n   * @param response\n   */\n  void on_sdo_read(\n    const std::shared_ptr<canopen_interfaces::srv::COReadID::Request> request,\n    std::shared_ptr<canopen_interfaces::srv::COReadID::Response> response);\n\n  /**\n   * @brief Write Service Data Object\n   *\n   * This service is only available when the node is in active lifecycle state.\n   * It will return with success false in any other lifecycle state and log an\n   * RCLCPP_ERROR.\n   *\n   * @param request\n   * @param response\n   */\n  void on_sdo_write(\n    const std::shared_ptr<canopen_interfaces::srv::COWriteID::Request> request,\n    std::shared_ptr<canopen_interfaces::srv::COWriteID::Response> response);\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/node_interfaces/node_canopen_basic_master_impl.hpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_BASIC_MASTER_IMPL_HPP_\n#define NODE_CANOPEN_BASIC_MASTER_IMPL_HPP_\n\n#include \"canopen_master_driver/lely_master_bridge.hpp\"\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBasicMaster<NODETYPE>::activate(bool called_from_base)\n{\n  master_bridge_ = std::make_shared<LelyMasterBridge>(\n    *(this->exec_), *(this->timer_), *(this->chan_), this->master_dcf_, this->master_bin_,\n    this->node_id_);\n  master_bridge_->SetTimeout(std::chrono::milliseconds(this->timeout_));\n  this->master_ = std::static_pointer_cast<lely::canopen::AsyncMaster>(master_bridge_);\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBasicMaster<NODETYPE>::deactivate(bool called_from_base)\n{\n  master_bridge_.reset();\n  this->master_.reset();\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBasicMaster<NODETYPE>::on_sdo_read(\n  const std::shared_ptr<canopen_interfaces::srv::COReadID::Request> request,\n  std::shared_ptr<canopen_interfaces::srv::COReadID::Response> response)\n{\n  if (this->activated_.load())\n  {\n    ros2_canopen::COData data = {request->index, request->subindex, 0U};\n    std::future<ros2_canopen::COData> f =\n      this->master_bridge_->async_read_sdo(request->nodeid, data, request->canopen_datatype);\n    f.wait();\n    try\n    {\n      response->data = f.get().data_;\n      response->success = true;\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(this->node_->get_logger(), e.what());\n      response->success = false;\n    }\n  }\n  else\n  {\n    RCLCPP_ERROR(\n      this->node_->get_logger(),\n      \"LifecycleMasterNode is not in active state. SDO read service is not available.\");\n    response->success = false;\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenBasicMaster<NODETYPE>::on_sdo_write(\n  const std::shared_ptr<canopen_interfaces::srv::COWriteID::Request> request,\n  std::shared_ptr<canopen_interfaces::srv::COWriteID::Response> response)\n{\n  if (this->activated_.load())\n  {\n    ros2_canopen::COData data = {request->index, request->subindex, request->data};\n    std::future<bool> f =\n      this->master_bridge_->async_write_sdo(request->nodeid, data, request->canopen_datatype);\n    f.wait();\n    try\n    {\n      response->success = f.get();\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(this->node_->get_logger(), e.what());\n      response->success = false;\n    }\n  }\n  else\n  {\n    RCLCPP_ERROR(\n      this->node_->get_logger(),\n      \"LifecycleMasterNode is not in active state. SDO write service is not available.\");\n    response->success = false;\n  }\n}\n\ntemplate <>\nvoid NodeCanopenBasicMaster<rclcpp::Node>::init(bool called_from_base)\n{\n  // declare services\n  sdo_read_service = this->node_->create_service<canopen_interfaces::srv::COReadID>(\n    std::string(this->node_->get_name()).append(\"/sdo_read\").c_str(),\n    std::bind(\n      &ros2_canopen::node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>::on_sdo_read, this,\n      std::placeholders::_1, std::placeholders::_2));\n\n  sdo_write_service = this->node_->create_service<canopen_interfaces::srv::COWriteID>(\n    std::string(this->node_->get_name()).append(\"/sdo_write\").c_str(),\n    std::bind(\n      &ros2_canopen::node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>::on_sdo_write, this,\n      std::placeholders::_1, std::placeholders::_2));\n}\n\ntemplate <>\nvoid NodeCanopenBasicMaster<rclcpp_lifecycle::LifecycleNode>::init(bool called_from_base)\n{\n  // declare services\n  sdo_read_service = this->node_->create_service<canopen_interfaces::srv::COReadID>(\n    std::string(this->node_->get_name()).append(\"/sdo_read\").c_str(),\n    std::bind(\n      &ros2_canopen::node_interfaces::NodeCanopenBasicMaster<\n        rclcpp_lifecycle::LifecycleNode>::on_sdo_read,\n      this, std::placeholders::_1, std::placeholders::_2));\n\n  sdo_write_service = this->node_->create_service<canopen_interfaces::srv::COWriteID>(\n    std::string(this->node_->get_name()).append(\"/sdo_write\").c_str(),\n    std::bind(\n      &ros2_canopen::node_interfaces::NodeCanopenBasicMaster<\n        rclcpp_lifecycle::LifecycleNode>::on_sdo_write,\n      this, std::placeholders::_1, std::placeholders::_2));\n}\n\n#endif\n"
  },
  {
    "path": "canopen_master_driver/include/canopen_master_driver/visibility_control.h",
    "content": "// Copyright 2023 ROS-Industrial\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_MASTER_DRIVER__VISIBILITY_CONTROL_H_\n#define CANOPEN_MASTER_DRIVER__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_MASTER_DRIVER_EXPORT __attribute__((dllexport))\n#define CANOPEN_MASTER_DRIVER_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_MASTER_DRIVER_EXPORT __declspec(dllexport)\n#define CANOPEN_MASTER_DRIVER_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_MASTER_DRIVER_BUILDING_LIBRARY\n#define CANOPEN_MASTER_DRIVER_PUBLIC CANOPEN_MASTER_DRIVER_EXPORT\n#else\n#define CANOPEN_MASTER_DRIVER_PUBLIC CANOPEN_MASTER_DRIVER_IMPORT\n#endif\n#define CANOPEN_MASTER_DRIVER_PUBLIC_TYPE CANOPEN_MASTER_DRIVER_PUBLIC\n#define CANOPEN_MASTER_DRIVER_LOCAL\n#else\n#define CANOPEN_MASTER_DRIVER_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_MASTER_DRIVER_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_MASTER_DRIVER_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_MASTER_DRIVER_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_MASTER_DRIVER_PUBLIC\n#define CANOPEN_MASTER_DRIVER_LOCAL\n#endif\n#define CANOPEN_MASTER_DRIVER_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_MASTER_DRIVER__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_master_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_master_driver</name>\n  <version>0.3.2</version>\n  <description>Basic canopen master implementation</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake_ros</buildtool_depend>\n\n  <depend>canopen_core</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>lely_core_libraries</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n  <test_depend>ament_lint_common</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_master_driver/src/lely_master_bridge.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#include \"canopen_master_driver/lely_master_bridge.hpp\"\n#include <chrono>\n#include <lely/co/dcf.hpp>\n\nusing namespace std::literals::chrono_literals;\n\nnamespace ros2_canopen /* constant-expression */\n{\nstd::future<bool> LelyMasterBridge::async_write_sdo(uint8_t id, COData data, uint8_t datatype)\n{\n  std::unique_lock<std::mutex> lck(sdo_mutex);\n  if (running)\n  {\n    sdo_cond.wait(lck);\n  }\n  running = true;\n\n  sdo_write_data_promise = std::make_shared<std::promise<bool>>();\n  try\n  {\n    switch (datatype)\n    {\n      case CO_DEFTYPE_INTEGER8:\n        submit_write_sdo<int8_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      case CO_DEFTYPE_INTEGER16:\n        submit_write_sdo<int16_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      case CO_DEFTYPE_INTEGER32:\n        submit_write_sdo<int32_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      case CO_DEFTYPE_UNSIGNED8:\n        submit_write_sdo<uint8_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      case CO_DEFTYPE_UNSIGNED16:\n        submit_write_sdo<uint16_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      case CO_DEFTYPE_UNSIGNED32:\n        submit_write_sdo<uint32_t>(id, data.index_, data.subindex_, data.data_);\n        break;\n      default:\n        throw lely::canopen::SdoError(\n          id, data.index_, data.subindex_, lely::canopen::SdoErrc::ERROR, \"Unknown datatype\");\n        break;\n    }\n  }\n  catch (...)\n  {\n    this->sdo_write_data_promise->set_exception(std::current_exception());\n    this->running = false;\n  }\n\n  return sdo_write_data_promise->get_future();\n}\n\nstd::future<COData> LelyMasterBridge::async_read_sdo(uint8_t id, COData data, uint8_t datatype)\n{\n  std::unique_lock<std::mutex> lck(sdo_mutex);\n  if (running)\n  {\n    sdo_cond.wait(lck);\n  }\n  running = true;\n\n  sdo_read_data_promise = std::make_shared<std::promise<COData>>();\n  try\n  {\n    switch (datatype)\n    {\n      case CO_DEFTYPE_INTEGER8:\n        submit_read_sdo<int8_t>(id, data.index_, data.subindex_);\n        break;\n      case CO_DEFTYPE_INTEGER16:\n        submit_read_sdo<int16_t>(id, data.index_, data.subindex_);\n        break;\n      case CO_DEFTYPE_INTEGER32:\n        submit_read_sdo<int32_t>(id, data.index_, data.subindex_);\n        break;\n      case CO_DEFTYPE_UNSIGNED8:\n        submit_read_sdo<uint8_t>(id, data.index_, data.subindex_);\n        break;\n      case CO_DEFTYPE_UNSIGNED16:\n        submit_read_sdo<uint16_t>(id, data.index_, data.subindex_);\n        break;\n      case CO_DEFTYPE_UNSIGNED32:\n        submit_read_sdo<uint32_t>(id, data.index_, data.subindex_);\n        break;\n      default:\n        throw lely::canopen::SdoError(\n          id, data.index_, data.subindex_, lely::canopen::SdoErrc::ERROR, \"Unknown datatype\");\n        break;\n    }\n  }\n  catch (...)\n  {\n    this->sdo_read_data_promise->set_exception(std::current_exception());\n    this->running = false;\n  }\n  return sdo_read_data_promise->get_future();\n}\n\nstd::future<bool> LelyMasterBridge::async_write_nmt(uint8_t id, uint8_t command)\n{\n  lely::canopen::NmtCommand command_ = static_cast<lely::canopen::NmtCommand>(command);\n  switch (command_)\n  {\n    case lely::canopen::NmtCommand::ENTER_PREOP:\n    case lely::canopen::NmtCommand::RESET_COMM:\n    case lely::canopen::NmtCommand::RESET_NODE:\n    case lely::canopen::NmtCommand::START:\n    case lely::canopen::NmtCommand::STOP:\n      this->Command(command_, id);\n      break;\n    default:\n      break;\n  }\n\n  nmt_promise.set_value(true);\n  return nmt_promise.get_future();\n}\n}  // namespace ros2_canopen\n"
  },
  {
    "path": "canopen_master_driver/src/lifecycle_master_driver.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_master_driver/lifecycle_master_driver.hpp\"\n\nnamespace ros2_canopen\n{\n\nros2_canopen::LifecycleMasterDriver::LifecycleMasterDriver(const rclcpp::NodeOptions & node_options)\n: LifecycleCanopenMaster(node_options)\n{\n  node_canopen_master_ =\n    std::make_shared<node_interfaces::NodeCanopenBasicMaster<rclcpp_lifecycle::LifecycleNode>>(\n      this);\n}\n\n}  // namespace ros2_canopen\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleMasterDriver)\n"
  },
  {
    "path": "canopen_master_driver/src/master_driver.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_master_driver/master_driver.hpp\"\n\nnamespace ros2_canopen\n{\n\nros2_canopen::MasterDriver::MasterDriver(const rclcpp::NodeOptions & node_options)\n: CanopenMaster(node_options)\n{\n  node_canopen_basic_master_ =\n    std::make_shared<node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>>(this);\n  node_canopen_master_ = std::static_pointer_cast<node_interfaces::NodeCanopenMasterInterface>(\n    node_canopen_basic_master_);\n}\n\n}  // namespace ros2_canopen\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::MasterDriver)\n"
  },
  {
    "path": "canopen_master_driver/src/node_interfaces/node_canopen_basic_master.cpp",
    "content": "//    Copyright 2022 Harshavadan Deshpande\n//                   Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master_impl.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopenBasicMaster<\n  rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_master_driver/test/CMakeLists.txt",
    "content": "ament_add_gtest(test_node_canopen_basic_driver\n  test_node_canopen_basic_master.cpp\n)\ntarget_include_directories(test_node_canopen_basic_driver PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_canopen_basic_driver\n  ${canopen_interfaces_TARGETS}\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  lely_master_bridge\n  master_driver\n  node_canopen_basic_master\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\nament_add_gtest(test_node_canopen_basic_driver_ros\ntest_node_canopen_basic_master_ros.cpp\n)\ntarget_include_directories(test_node_canopen_basic_driver_ros PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_canopen_basic_driver_ros\n  ${canopen_interfaces_TARGETS}\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  lely_master_bridge\n  master_driver\n  node_canopen_basic_master\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\nament_add_gtest(test_master_driver_component\ntest_master_driver_component.cpp\n)\ntarget_include_directories(test_master_driver_component PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_master_driver_component\n  ${canopen_interfaces_TARGETS}\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  lely_master_bridge\n  lifecycle_master_driver\n  master_driver\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\nfile(COPY ${CMAKE_CURRENT_SOURCE_DIR}/master.dcf DESTINATION ${CMAKE_CURRENT_BINARY_DIR})\n"
  },
  {
    "path": "canopen_master_driver/test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=2\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=32\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1A00\n20=0x1A01\n21=0x1F25\n22=0x1F55\n23=0x1F80\n24=0x1F81\n25=0x1F82\n26=0x1F84\n27=0x1F85\n28=0x1F86\n29=0x1F87\n30=0x1F88\n31=0x1F89\n32=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=12\n1=0x2000\n2=0x2001\n3=0x2200\n4=0x2201\n5=0x5800\n6=0x5801\n7=0x5A00\n8=0x5A01\n9=0x5C00\n10=0x5C01\n11=0x5E00\n12=0x5E01\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=2\n2=0x00000082\n3=0x00000083\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=2\n2=0x00000005\n3=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=2\n2=0x00000360\n3=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=proxy_device_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=proxy_device_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=proxy_device_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=proxy_device_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_master_driver/test/test_master_driver_component.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <rclcpp_components/component_manager.hpp>\n#include <rclcpp_components/node_factory.hpp>\n#include <rclcpp_components/node_instance_wrapper.hpp>\n#include <thread>\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n#include \"gtest/gtest.h\"\nusing namespace rclcpp_components;\n\nTEST(MasterDriverComponent, test_load_lifecycle_master_driver)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_master_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[0]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n\nTEST(MasterDriverComponent, test_load_master_driver)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_master_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[1]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_master_driver/test/test_node_canopen_basic_master.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n#include \"gtest/gtest.h\"\n\nclass RclCppFixture\n{\npublic:\n  RclCppFixture()\n  {\n    rclcpp::init(0, nullptr);\n    node = new rclcpp::Node(\"Node\");\n    interface = new ros2_canopen::node_interfaces::NodeCanopenBasicMaster<rclcpp::Node>(node);\n  }\n  virtual ~RclCppFixture()\n  {\n    rclcpp::shutdown();\n    delete (interface);\n    delete (node);\n  }\n\n  rclcpp::Node * node;\n  ros2_canopen::node_interfaces::NodeCanopenBasicMaster<rclcpp::Node> * interface;\n};\nRclCppFixture g_rclcppfixture;\n\nTEST(NodeCanopenBasicMaster, test_bad_sequence_configure)\n{\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface *>(\n    g_rclcppfixture.interface);\n  EXPECT_ANY_THROW(iface->configure());\n}\n\nTEST(NodeCanopenBasicMaster, test_bad_sequence_activate)\n{\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface *>(\n    g_rclcppfixture.interface);\n  EXPECT_ANY_THROW(iface->activate());\n}\n\nTEST(NodeCanopenBasicMaster, test_good_sequence)\n{\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface *>(\n    g_rclcppfixture.interface);\n  try\n  {\n    iface->init();\n  }\n  catch (const std::exception & e)\n  {\n    RCLCPP_ERROR(rclcpp::get_logger(\"test\"), e.what());\n  }\n  EXPECT_NO_THROW(iface->configure());\n}\n"
  },
  {
    "path": "canopen_master_driver/test/test_node_canopen_basic_master_ros.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <thread>\n#include \"canopen_master_driver/node_interfaces/node_canopen_basic_master.hpp\"\n#include \"gtest/gtest.h\"\n\nTEST(NodeCanopenBasicMaster, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp::Node * node = new rclcpp::Node(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenBasicMaster(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter master_dcf(\"master_dcf\", \"master.dcf\");\n  rclcpp::Parameter master_bin(\"master_bin\", \"\");\n  rclcpp::Parameter can_interface_name(\"can_interface_name\", \"vcan0\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\"config\", \"\");\n  node->set_parameter(container_name);\n  node->set_parameter(master_dcf);\n  node->set_parameter(master_bin);\n  node->set_parameter(can_interface_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n\nTEST(NodeCanopenBasicLifecycleMaster, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp_lifecycle::LifecycleNode * node = new rclcpp_lifecycle::LifecycleNode(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenBasicMaster(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenMasterInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter master_dcf(\"master_dcf\", \"master.dcf\");\n  rclcpp::Parameter master_bin(\"master_bin\", \"\");\n  rclcpp::Parameter can_interface_name(\"can_interface_name\", \"vcan0\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\"config\", \"\");\n  node->set_parameter(container_name);\n  node->set_parameter(master_dcf);\n  node->set_parameter(master_bin);\n  node->set_parameter(can_interface_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n"
  },
  {
    "path": "canopen_proxy_driver/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_proxy_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.2.9 (2024-04-16)\n------------------\n\n0.3.2 (2025-12-05)\n------------------\n* `#379 <https://github.com/ros-industrial/ros2_canopen/issues/379>`_: Fix data conversion in the Lely Bridge to enable more data types and proper handling of Emcy in ros2_control\n* Fixed types handling in canopen_ros2_control.\n* Optimize debug output.\n* Contributors: Dr. Denis Stogl, Vishnuprasad Prachandabhanu\n\n0.3.1 (2025-06-23)\n------------------\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Contributors: ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix maintainer naming\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Use consistenlty (uppercase) HEX output for NodeID and Index.\n* Contributors: Christoph Hellmann Santos, Denis Štogl\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Lovro, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_proxy_driver/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_proxy_driver)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wpedantic -Wextra -Wno-unused-parameter)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_ros REQUIRED)\nfind_package(canopen_base_driver REQUIRED)\nfind_package(canopen_core REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\n\nadd_library(node_canopen_proxy_driver\n  src/node_interfaces/node_canopen_proxy_driver.cpp\n)\ntarget_compile_features(node_canopen_proxy_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(node_canopen_proxy_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(node_canopen_proxy_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\ntarget_link_libraries(node_canopen_proxy_driver PUBLIC\n  canopen_base_driver::node_canopen_base_driver\n)\n\nadd_library(lifecycle_proxy_driver\n  src/lifecycle_proxy_driver.cpp\n)\ntarget_compile_features(lifecycle_proxy_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(lifecycle_proxy_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(lifecycle_proxy_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\n\ntarget_link_libraries(lifecycle_proxy_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_proxy_driver\n  rclcpp_components::component\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(lifecycle_proxy_driver PRIVATE \"CANOPEN_PROXY_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(lifecycle_proxy_driver \"ros2_canopen::LifecycleProxyDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::LifecycleProxyDriver;$<TARGET_FILE:lifecycle_proxy_driver >\\n\")\n\n\n\n\nadd_library(proxy_driver\n  src/proxy_driver.cpp\n)\ntarget_compile_features(proxy_driver PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(proxy_driver PUBLIC -Wl,--no-undefined)\ntarget_include_directories(proxy_driver PUBLIC\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include>)\ntarget_link_libraries(proxy_driver PUBLIC\n  canopen_core::node_canopen_driver\n  node_canopen_proxy_driver\n  rclcpp_components::component\n)\n\n# Causes the visibility macros to use dllexport rather than dllimport,\n# which is appropriate when building the dll but not consuming it.\ntarget_compile_definitions(proxy_driver PRIVATE \"CANOPEN_proxy_DRIVER_BUILDING_LIBRARY\")\n\nrclcpp_components_register_nodes(proxy_driver \"ros2_canopen::ProxyDriver\")\nset(node_plugins \"${node_plugins}ros2_canopen::ProxyDriver;$<TARGET_FILE:proxy_driver >\\n\")\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\ninstall(\n  TARGETS lifecycle_proxy_driver proxy_driver node_canopen_proxy_driver\n  EXPORT export_${PROJECT_NAME}\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  RUNTIME DESTINATION bin\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_gtest REQUIRED)\n  add_subdirectory(test)\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  lifecycle_proxy_driver\n  proxy_driver\n  node_canopen_proxy_driver\n)\nament_export_targets(\n  export_${PROJECT_NAME}\n)\nament_export_dependencies(\n  canopen_base_driver\n  canopen_core\n  canopen_interfaces\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_proxy_driver/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_proxy_driver/config/concurrency_test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=6\nNrOfTxPDO=6\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=48\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1402\n16=0x1403\n17=0x1404\n18=0x1405\n19=0x1600\n20=0x1601\n21=0x1602\n22=0x1603\n23=0x1604\n24=0x1605\n25=0x1800\n26=0x1801\n27=0x1802\n28=0x1803\n29=0x1804\n30=0x1805\n31=0x1A00\n32=0x1A01\n33=0x1A02\n34=0x1A03\n35=0x1A04\n36=0x1A05\n37=0x1F25\n38=0x1F55\n39=0x1F80\n40=0x1F81\n41=0x1F82\n42=0x1F84\n43=0x1F85\n44=0x1F86\n45=0x1F87\n46=0x1F88\n47=0x1F89\n48=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=36\n1=0x2000\n2=0x2001\n3=0x2002\n4=0x2003\n5=0x2004\n6=0x2005\n7=0x2200\n8=0x2201\n9=0x2202\n10=0x2203\n11=0x2204\n12=0x2205\n13=0x5800\n14=0x5801\n15=0x5802\n16=0x5803\n17=0x5804\n18=0x5805\n19=0x5A00\n20=0x5A01\n21=0x5A02\n22=0x5A03\n23=0x5A04\n24=0x5A05\n25=0x5C00\n26=0x5C01\n27=0x5C02\n28=0x5C03\n29=0x5C04\n30=0x5C05\n31=0x5E00\n32=0x5E01\n33=0x5E02\n34=0x5E03\n35=0x5E04\n36=0x5E05\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=6\n2=0x00000082\n3=0x00000083\n4=0x00000084\n5=0x00000085\n6=0x00000086\n7=0x00000087\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1402]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1402sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1402sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000184\n\n[1402sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1402sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1402sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1402sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1403]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1403sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1403sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000185\n\n[1403sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1403sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1403sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1403sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1404]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1404sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1404sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000186\n\n[1404sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1404sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1404sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1404sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1405]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1405sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1405sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000187\n\n[1405sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1405sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1405sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1405sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1602]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1602Value]\nNrOfEntries=1\n1=0x20020120\n\n[1603]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1603Value]\nNrOfEntries=1\n1=0x20030120\n\n[1604]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1604Value]\nNrOfEntries=1\n1=0x20040120\n\n[1605]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1605Value]\nNrOfEntries=1\n1=0x20050120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1802]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1802sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1802sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000204\n\n[1802sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1802sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1802sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1802sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1802sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1803]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1803sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1803sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000205\n\n[1803sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1803sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1803sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1803sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1803sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1804]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1804sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1804sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000206\n\n[1804sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1804sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1804sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1804sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1804sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1805]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1805sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1805sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000207\n\n[1805sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1805sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1805sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1805sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1805sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1A02]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A02Value]\nNrOfEntries=1\n1=0x22020120\n\n[1A03]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A03Value]\nNrOfEntries=1\n1=0x22030120\n\n[1A04]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A04Value]\nNrOfEntries=1\n1=0x22040120\n\n[1A05]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A05Value]\nNrOfEntries=1\n1=0x22050120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=6\n2=0x00000005\n3=0x00000005\n4=0x00000005\n5=0x00000005\n6=0x00000005\n7=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=6\n2=0x00000360\n3=0x00000360\n4=0x00000360\n5=0x00000360\n6=0x00000360\n7=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=motioncontroller_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=motioncontroller_3: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2002]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 3\nObjectType=0x09\n\n[2002sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2002sub1]\nParameterName=motioncontroller_4: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2003]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 4\nObjectType=0x09\n\n[2003sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2003sub1]\nParameterName=motioncontroller_5: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2004]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 5\nObjectType=0x09\n\n[2004sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2004sub1]\nParameterName=motioncontroller_6: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2005]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 6\nObjectType=0x09\n\n[2005sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2005sub1]\nParameterName=motioncontroller_7: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=motioncontroller_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=motioncontroller_3: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2202]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 3\nObjectType=0x09\n\n[2202sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2202sub1]\nParameterName=motioncontroller_4: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2203]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 4\nObjectType=0x09\n\n[2203sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2203sub1]\nParameterName=motioncontroller_5: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2204]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 5\nObjectType=0x09\n\n[2204sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2204sub1]\nParameterName=motioncontroller_6: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2205]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 6\nObjectType=0x09\n\n[2205sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2205sub1]\nParameterName=motioncontroller_7: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5802]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000104\n\n[5803]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000105\n\n[5804]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000106\n\n[5805]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000107\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A02]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A02Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A03]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A03Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A04]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A04Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A05]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A05Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5C02]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000104\n\n[5C03]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000105\n\n[5C04]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000106\n\n[5C05]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000107\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E02]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E02Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E03]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E03Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E04]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E04Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E05]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E05Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_proxy_driver/config/nmt_test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=28\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1600\n15=0x1800\n16=0x1A00\n17=0x1F25\n18=0x1F55\n19=0x1F80\n20=0x1F81\n21=0x1F82\n22=0x1F84\n23=0x1F85\n24=0x1F86\n25=0x1F87\n26=0x1F88\n27=0x1F89\n28=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=6\n1=0x2000\n2=0x2200\n3=0x5800\n4=0x5A00\n5=0x5C00\n6=0x5E00\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=1\n2=0x00000082\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=1\n2=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=1\n2=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=motioncontroller_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=motioncontroller_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_proxy_driver/config/pdo_test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=28\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1600\n15=0x1800\n16=0x1A00\n17=0x1F25\n18=0x1F55\n19=0x1F80\n20=0x1F81\n21=0x1F82\n22=0x1F84\n23=0x1F85\n24=0x1F86\n25=0x1F87\n26=0x1F88\n27=0x1F89\n28=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=6\n1=0x2000\n2=0x2200\n3=0x5800\n4=0x5A00\n5=0x5C00\n6=0x5E00\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=1\n2=0x00000082\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=1\n2=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=1\n2=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=motioncontroller_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=motioncontroller_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_proxy_driver/config/sdo_test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=28\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1600\n15=0x1800\n16=0x1A00\n17=0x1F25\n18=0x1F55\n19=0x1F80\n20=0x1F81\n21=0x1F82\n22=0x1F84\n23=0x1F85\n24=0x1F86\n25=0x1F87\n26=0x1F88\n27=0x1F89\n28=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=6\n1=0x2000\n2=0x2200\n3=0x5800\n4=0x5A00\n5=0x5C00\n6=0x5E00\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=1\n2=0x00000082\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=1\n2=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=1\n2=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=motioncontroller_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=motioncontroller_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_proxy_driver/include/canopen_proxy_driver/lifecycle_proxy_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CANOPEN_PROXY_DRIVER__CANOPEN_LIFECYCLE_PROXY_DRIVER_HPP_\n#define CANOPEN_PROXY_DRIVER__CANOPEN_LIFECYCLE_PROXY_DRIVER_HPP_\n\n#include \"canopen_core/driver_node.hpp\"\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Lifecycle Proxy Driver\n *\n * A very basic driver without any functionality.\n *\n */\nclass LifecycleProxyDriver : public ros2_canopen::LifecycleCanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>>\n    node_canopen_proxy_driver_;\n\npublic:\n  LifecycleProxyDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n  virtual bool reset_node_nmt_command()\n  {\n    return node_canopen_proxy_driver_->reset_node_nmt_command();\n  }\n\n  virtual bool start_node_nmt_command()\n  {\n    return node_canopen_proxy_driver_->start_node_nmt_command();\n  }\n\n  virtual bool tpdo_transmit(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->tpdo_transmit(data);\n  }\n\n  virtual bool sdo_write(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->sdo_write(data);\n  }\n\n  virtual bool sdo_read(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->sdo_read(data);\n  }\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_proxy_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_proxy_driver_->register_rpdo_cb(rpdo_cb);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_PROXY_DRIVER__CANOPEN_LIFECYCLE_PROXY_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_proxy_driver/include/canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_PROXY_DRIVER\n#define NODE_CANOPEN_PROXY_DRIVER\n\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\nnamespace ros2_canopen\n{\nnamespace node_interfaces\n{\n\ntemplate <class NODETYPE>\nclass NodeCanopenProxyDriver : public NodeCanopenBaseDriver<NODETYPE>\n{\n  static_assert(\n    std::is_base_of<rclcpp::Node, NODETYPE>::value ||\n      std::is_base_of<rclcpp_lifecycle::LifecycleNode, NODETYPE>::value,\n    \"NODETYPE must derive from rclcpp::Node or rclcpp_lifecycle::LifecycleNode\");\n\nprotected:\n  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr nmt_state_publisher;\n  rclcpp::Publisher<canopen_interfaces::msg::COData>::SharedPtr rpdo_publisher;\n  rclcpp::Subscription<canopen_interfaces::msg::COData>::SharedPtr tpdo_subscriber;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_reset_service;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr nmt_state_start_service;\n  rclcpp::Service<canopen_interfaces::srv::CORead>::SharedPtr sdo_read_service;\n  rclcpp::Service<canopen_interfaces::srv::COWrite>::SharedPtr sdo_write_service;\n\n  std::mutex sdo_mtex;\n\n  virtual void on_nmt(canopen::NmtState nmt_state) override;\n  virtual void on_rpdo(COData data) override;\n  virtual void on_tpdo(const canopen_interfaces::msg::COData::SharedPtr msg);\n  virtual void diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat) override;\n\n  void on_nmt_state_reset(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response);\n\n  void on_nmt_state_start(\n    const std_srvs::srv::Trigger::Request::SharedPtr request,\n    std_srvs::srv::Trigger::Response::SharedPtr response);\n\n  void on_sdo_read(\n    const canopen_interfaces::srv::CORead::Request::SharedPtr request,\n    canopen_interfaces::srv::CORead::Response::SharedPtr response);\n\n  void on_sdo_write(\n    const canopen_interfaces::srv::COWrite::Request::SharedPtr request,\n    canopen_interfaces::srv::COWrite::Response::SharedPtr response);\n\npublic:\n  NodeCanopenProxyDriver(NODETYPE * node);\n\n  virtual void init(bool called_from_base) override;\n\n  virtual bool reset_node_nmt_command();\n\n  virtual bool start_node_nmt_command();\n\n  virtual bool tpdo_transmit(COData & data);\n\n  virtual bool sdo_write(COData & data);\n\n  virtual bool sdo_read(COData & data);\n};\n}  // namespace node_interfaces\n}  // namespace ros2_canopen\n\n#endif\n"
  },
  {
    "path": "canopen_proxy_driver/include/canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver_impl.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef NODE_CANOPEN_PROXY_DRIVER_IMPL_HPP_\n#define NODE_CANOPEN_PROXY_DRIVER_IMPL_HPP_\n\n#include \"canopen_core/driver_error.hpp\"\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate <class NODETYPE>\nNodeCanopenProxyDriver<NODETYPE>::NodeCanopenProxyDriver(NODETYPE * node)\n: ros2_canopen::node_interfaces::NodeCanopenBaseDriver<NODETYPE>(node)\n{\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::init(bool called_from_base)\n{\n  RCLCPP_ERROR(this->node_->get_logger(), \"Not init implemented.\");\n}\n\ntemplate <>\nvoid NodeCanopenProxyDriver<rclcpp::Node>::init(bool called_from_base)\n{\n  nmt_state_publisher = this->node_->create_publisher<std_msgs::msg::String>(\n    std::string(this->node_->get_name()).append(\"/nmt_state\").c_str(), 10);\n  tpdo_subscriber = this->node_->create_subscription<canopen_interfaces::msg::COData>(\n    std::string(this->node_->get_name()).append(\"/tpdo\").c_str(), 10,\n    std::bind(&NodeCanopenProxyDriver<rclcpp::Node>::on_tpdo, this, std::placeholders::_1));\n\n  rpdo_publisher = this->node_->create_publisher<canopen_interfaces::msg::COData>(\n    std::string(this->node_->get_name()).append(\"/rpdo\").c_str(), 10);\n\n  nmt_state_reset_service = this->node_->create_service<std_srvs::srv::Trigger>(\n    std::string(this->node_->get_name()).append(\"/nmt_reset_node\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp::Node>::on_nmt_state_reset, this, std::placeholders::_1,\n      std::placeholders::_2));\n\n  nmt_state_start_service = this->node_->create_service<std_srvs::srv::Trigger>(\n    std::string(this->node_->get_name()).append(\"/nmt_start_node\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp::Node>::on_nmt_state_start, this, std::placeholders::_1,\n      std::placeholders::_2));\n\n  sdo_read_service = this->node_->create_service<canopen_interfaces::srv::CORead>(\n    std::string(this->node_->get_name()).append(\"/sdo_read\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp::Node>::on_sdo_read, this, std::placeholders::_1,\n      std::placeholders::_2));\n\n  sdo_write_service = this->node_->create_service<canopen_interfaces::srv::COWrite>(\n    std::string(this->node_->get_name()).append(\"/sdo_write\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp::Node>::on_sdo_write, this, std::placeholders::_1,\n      std::placeholders::_2));\n}\n\ntemplate <>\nvoid NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::init(bool called_from_base)\n{\n  nmt_state_publisher = this->node_->create_publisher<std_msgs::msg::String>(\n    std::string(this->node_->get_name()).append(\"/nmt_state\").c_str(), 10);\n  tpdo_subscriber = this->node_->create_subscription<canopen_interfaces::msg::COData>(\n    std::string(this->node_->get_name()).append(\"/tpdo\").c_str(), 10,\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::on_tpdo, this,\n      std::placeholders::_1));\n\n  rpdo_publisher = this->node_->create_publisher<canopen_interfaces::msg::COData>(\n    std::string(this->node_->get_name()).append(\"/rpdo\").c_str(), 10);\n\n  nmt_state_reset_service = this->node_->create_service<std_srvs::srv::Trigger>(\n    std::string(this->node_->get_name()).append(\"/nmt_reset_node\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::on_nmt_state_reset, this,\n      std::placeholders::_1, std::placeholders::_2));\n\n  nmt_state_start_service = this->node_->create_service<std_srvs::srv::Trigger>(\n    std::string(this->node_->get_name()).append(\"/nmt_start_node\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::on_nmt_state_start, this,\n      std::placeholders::_1, std::placeholders::_2));\n\n  sdo_read_service = this->node_->create_service<canopen_interfaces::srv::CORead>(\n    std::string(this->node_->get_name()).append(\"/sdo_read\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::on_sdo_read, this,\n      std::placeholders::_1, std::placeholders::_2));\n\n  sdo_write_service = this->node_->create_service<canopen_interfaces::srv::COWrite>(\n    std::string(this->node_->get_name()).append(\"/sdo_write\").c_str(),\n    std::bind(\n      &NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>::on_sdo_write, this,\n      std::placeholders::_1, std::placeholders::_2));\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_nmt(canopen::NmtState nmt_state)\n{\n  if (this->activated_.load())\n  {\n    auto message = std_msgs::msg::String();\n\n    switch (nmt_state)\n    {\n      case canopen::NmtState::BOOTUP:\n        message.data = \"BOOTUP\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::OK, \"NMT bootup\", \"NMT\", \"BOOTUP\");\n        break;\n      case canopen::NmtState::PREOP:\n        message.data = \"PREOP\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::OK, \"NMT preop\", \"NMT\", \"PREOP\");\n        break;\n      case canopen::NmtState::RESET_COMM:\n        message.data = \"RESET_COMM\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::WARN, \"NMT reset comm\", \"NMT\", \"RESET_COMM\");\n        break;\n      case canopen::NmtState::RESET_NODE:\n        message.data = \"RESET_NODE\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::WARN, \"NMT reset node\", \"NMT\", \"RESET_NODE\");\n        break;\n      case canopen::NmtState::START:\n        message.data = \"START\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::OK, \"NMT start\", \"NMT\", \"START\");\n        break;\n      case canopen::NmtState::STOP:\n        message.data = \"STOP\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::OK, \"NMT stop\", \"NMT\", \"STOP\");\n        break;\n      case canopen::NmtState::TOGGLE:\n        message.data = \"TOGGLE\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::OK, \"NMT toggle\", \"NMT\", \"TOGGLE\");\n        break;\n      default:\n        RCLCPP_ERROR(this->node_->get_logger(), \"Unknown NMT State.\");\n        message.data = \"ERROR\";\n        this->diagnostic_collector_->updateAll(\n          diagnostic_msgs::msg::DiagnosticStatus::ERROR, \"NMT unknown state\", \"NMT\", \"ERROR\");\n        break;\n    }\n    RCLCPP_INFO(\n      this->node_->get_logger(), \"Slave 0x%X: Switched NMT state to %s\",\n      this->lely_driver_->get_id(), message.data.c_str());\n\n    nmt_state_publisher->publish(message);\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_tpdo(const canopen_interfaces::msg::COData::SharedPtr msg)\n{\n  ros2_canopen::COData data = {msg->index, msg->subindex, msg->data};\n  if (!tpdo_transmit(data))\n  {\n    RCLCPP_ERROR(this->node_->get_logger(), \"Could transmit PDO because driver not activated.\");\n  }\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopenProxyDriver<NODETYPE>::tpdo_transmit(ros2_canopen::COData & data)\n{\n  if (this->activated_.load())\n  {\n    RCLCPP_DEBUG(\n      this->node_->get_logger(), \"Node ID 0x%X: Transmit PDO index %x, subindex %hhu, data %d\",\n      this->lely_driver_->get_id(), data.index_, data.subindex_, data.data_);\n    this->lely_driver_->tpdo_transmit(data);\n    return true;\n  }\n  return false;\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_rpdo(ros2_canopen::COData d)\n{\n  if (this->activated_.load())\n  {\n    // RCLCPP_DEBUG(\n    //   this->node_->get_logger(), \"Node ID 0x%X: Received PDO index %#04x, subindex %hhu, data\n    //   %x\", this->lely_driver_->get_id(), d.index_, d.subindex_, d.data_);\n    auto message = canopen_interfaces::msg::COData();\n    message.index = d.index_;\n    message.subindex = d.subindex_;\n    message.data = d.data_;\n    rpdo_publisher->publish(message);\n  }\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_nmt_state_reset(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response)\n{\n  response->success = reset_node_nmt_command();\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopenProxyDriver<NODETYPE>::reset_node_nmt_command()\n{\n  if (this->activated_.load())\n  {\n    this->lely_driver_->nmt_command(canopen::NmtCommand::RESET_NODE);\n    return true;\n  }\n  RCLCPP_ERROR(\n    this->node_->get_logger(), \"Could not reset device via NMT because driver not activated.\");\n  return false;\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_nmt_state_start(\n  const std_srvs::srv::Trigger::Request::SharedPtr request,\n  std_srvs::srv::Trigger::Response::SharedPtr response)\n{\n  response->success = start_node_nmt_command();\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopenProxyDriver<NODETYPE>::start_node_nmt_command()\n{\n  if (this->activated_.load())\n  {\n    this->lely_driver_->nmt_command(canopen::NmtCommand::START);\n    return true;\n  }\n  RCLCPP_ERROR(\n    this->node_->get_logger(), \"Could not start device via NMT because driver not activated.\");\n  return false;\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_sdo_read(\n  const canopen_interfaces::srv::CORead::Request::SharedPtr request,\n  canopen_interfaces::srv::CORead::Response::SharedPtr response)\n{\n  ros2_canopen::COData data = {request->index, request->subindex, 0U};\n  response->success = sdo_read(data);\n  response->data = data.data_;\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopenProxyDriver<NODETYPE>::sdo_read(ros2_canopen::COData & data)\n{\n  if (this->activated_.load())\n  {\n    RCLCPP_INFO(\n      this->node_->get_logger(), \"Slave 0x%X: SDO Read Call index=0x%X subindex=%hhu\",\n      this->lely_driver_->get_id(), data.index_, data.subindex_);\n\n    // Only allow one SDO request concurrently\n    std::scoped_lock<std::mutex> lk(sdo_mtex);\n    // Send read request\n    auto f = this->lely_driver_->async_sdo_read(data);\n    // Wait for response\n    f.wait();\n    // Process response\n    try\n    {\n      data.data_ = f.get().data_;\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(this->node_->get_logger(), e.what());\n      return false;\n    }\n    return true;\n  }\n  RCLCPP_ERROR(this->node_->get_logger(), \"Could not read from SDO because driver not activated.\");\n  return false;\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::on_sdo_write(\n  const canopen_interfaces::srv::COWrite::Request::SharedPtr request,\n  canopen_interfaces::srv::COWrite::Response::SharedPtr response)\n{\n  ros2_canopen::COData data = {request->index, request->subindex, request->data};\n  response->success = sdo_write(data);\n}\n\ntemplate <class NODETYPE>\nbool NodeCanopenProxyDriver<NODETYPE>::sdo_write(ros2_canopen::COData & data)\n{\n  if (this->activated_.load())\n  {\n    RCLCPP_INFO(\n      this->node_->get_logger(), \"Slave 0x%X: SDO Write Call index=0x%X subindex=%hhu data=%u\",\n      this->lely_driver_->get_id(), data.index_, data.subindex_, data.data_);\n\n    // Only allow one SDO request concurrently\n    std::scoped_lock<std::mutex> lk(sdo_mtex);\n\n    // Send write request\n    auto f = this->lely_driver_->async_sdo_write(data);\n    // Wait for request to complete\n    f.wait();\n\n    // Process response\n    try\n    {\n      return f.get();\n    }\n    catch (std::exception & e)\n    {\n      RCLCPP_ERROR(this->node_->get_logger(), e.what());\n      return false;\n    }\n    return true;\n  }\n  RCLCPP_ERROR(this->node_->get_logger(), \"Could not write to SDO because driver not activated.\");\n  return false;\n}\n\ntemplate <class NODETYPE>\nvoid NodeCanopenProxyDriver<NODETYPE>::diagnostic_callback(\n  diagnostic_updater::DiagnosticStatusWrapper & stat)\n{\n  stat.summary(this->diagnostic_collector_->getLevel(), this->diagnostic_collector_->getMessage());\n  stat.add(\"device_state\", this->diagnostic_collector_->getValue(\"DEVICE\"));\n  stat.add(\"nmt_state\", this->diagnostic_collector_->getValue(\"NMT\"));\n  stat.add(\"emcy_state\", this->diagnostic_collector_->getValue(\"EMCY\"));\n}\n\n#endif\n"
  },
  {
    "path": "canopen_proxy_driver/include/canopen_proxy_driver/proxy_driver.hpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#ifndef CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_\n#define CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_\n#include \"canopen_core/driver_node.hpp\"\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n\nnamespace ros2_canopen\n{\n/**\n * @brief Abstract Class for a CANopen Device Node\n *\n * This class provides the base functionality for creating a\n * CANopen device node. It provides callbacks for nmt and rpdo.\n */\nclass ProxyDriver : public ros2_canopen::CanopenDriver\n{\n  std::shared_ptr<node_interfaces::NodeCanopenProxyDriver<rclcpp::Node>> node_canopen_proxy_driver_;\n\npublic:\n  ProxyDriver(rclcpp::NodeOptions node_options = rclcpp::NodeOptions());\n\n  virtual bool reset_node_nmt_command()\n  {\n    return node_canopen_proxy_driver_->reset_node_nmt_command();\n  }\n\n  virtual bool start_node_nmt_command()\n  {\n    return node_canopen_proxy_driver_->start_node_nmt_command();\n  }\n\n  virtual bool tpdo_transmit(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->tpdo_transmit(data);\n  }\n\n  virtual bool sdo_write(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->sdo_write(data);\n  }\n\n  virtual bool sdo_read(ros2_canopen::COData & data)\n  {\n    return node_canopen_proxy_driver_->sdo_read(data);\n  }\n\n  void register_nmt_state_cb(std::function<void(canopen::NmtState, uint8_t)> nmt_state_cb)\n  {\n    node_canopen_proxy_driver_->register_nmt_state_cb(nmt_state_cb);\n  }\n\n  void register_rpdo_cb(std::function<void(COData, uint8_t)> rpdo_cb)\n  {\n    node_canopen_proxy_driver_->register_rpdo_cb(rpdo_cb);\n  }\n\n  void register_emcy_cb(std::function<void(COEmcy, uint8_t)> emcy_cb)\n  {\n    node_canopen_proxy_driver_->register_emcy_cb(emcy_cb);\n  }\n};\n}  // namespace ros2_canopen\n\n#endif  // CANOPEN_PROXY_DRIVER__CANOPEN_PROXY_DRIVER_HPP_\n"
  },
  {
    "path": "canopen_proxy_driver/include/canopen_proxy_driver/visibility_control.h",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#ifndef CANOPEN_PROXY_DRIVER__VISIBILITY_CONTROL_H_\n#define CANOPEN_PROXY_DRIVER__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_PROXY_DRIVER_EXPORT __attribute__((dllexport))\n#define CANOPEN_PROXY_DRIVER_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_PROXY_DRIVER_EXPORT __declspec(dllexport)\n#define CANOPEN_PROXY_DRIVER_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_PROXY_DRIVER_BUILDING_LIBRARY\n#define CANOPEN_PROXY_DRIVER_PUBLIC CANOPEN_PROXY_DRIVER_EXPORT\n#else\n#define CANOPEN_PROXY_DRIVER_PUBLIC CANOPEN_PROXY_DRIVER_IMPORT\n#endif\n#define CANOPEN_PROXY_DRIVER_PUBLIC_TYPE CANOPEN_PROXY_DRIVER_PUBLIC\n#define CANOPEN_PROXY_DRIVER_LOCAL\n#else\n#define CANOPEN_PROXY_DRIVER_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_PROXY_DRIVER_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_PROXY_DRIVER_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_PROXY_DRIVER_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_PROXY_DRIVER_PUBLIC\n#define CANOPEN_PROXY_DRIVER_LOCAL\n#endif\n#define CANOPEN_PROXY_DRIVER_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_PROXY_DRIVER__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_proxy_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_proxy_driver</name>\n  <version>0.3.2</version>\n  <description>Simple proxy driver for the ros2_canopen stack</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake_ros</buildtool_depend>\n\n  <depend>canopen_base_driver</depend>\n  <depend>canopen_core</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_proxy_driver/readme.md",
    "content": "# canopen_ros_proxy_driver\n\n## Testing\n```\ncolcon test --packages-select canopen_proxy_driver --event-handlers desktop_notification+ status+ summary- console_direct+ terminal_title+\n```\n"
  },
  {
    "path": "canopen_proxy_driver/src/lifecycle_proxy_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#include \"canopen_proxy_driver/lifecycle_proxy_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nLifecycleProxyDriver::LifecycleProxyDriver(rclcpp::NodeOptions node_options)\n: LifecycleCanopenDriver(node_options)\n{\n  node_canopen_proxy_driver_ =\n    std::make_shared<node_interfaces::NodeCanopenProxyDriver<rclcpp_lifecycle::LifecycleNode>>(\n      this);\n  node_canopen_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(\n    node_canopen_proxy_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::LifecycleProxyDriver)\n"
  },
  {
    "path": "canopen_proxy_driver/src/node_interfaces/node_canopen_proxy_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver_impl.hpp\"\n\nusing namespace ros2_canopen::node_interfaces;\n\ntemplate class ros2_canopen::node_interfaces::NodeCanopenProxyDriver<rclcpp::Node>;\ntemplate class ros2_canopen::node_interfaces::NodeCanopenProxyDriver<\n  rclcpp_lifecycle::LifecycleNode>;\n"
  },
  {
    "path": "canopen_proxy_driver/src/proxy_driver.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n#include \"canopen_proxy_driver/proxy_driver.hpp\"\n\nusing namespace ros2_canopen;\n\nProxyDriver::ProxyDriver(rclcpp::NodeOptions node_options) : CanopenDriver(node_options)\n{\n  node_canopen_proxy_driver_ =\n    std::make_shared<node_interfaces::NodeCanopenProxyDriver<rclcpp::Node>>(this);\n  node_canopen_driver_ = std::static_pointer_cast<node_interfaces::NodeCanopenDriverInterface>(\n    node_canopen_proxy_driver_);\n}\n\n#include \"rclcpp_components/register_node_macro.hpp\"\nRCLCPP_COMPONENTS_REGISTER_NODE(ros2_canopen::ProxyDriver)\n"
  },
  {
    "path": "canopen_proxy_driver/test/CMakeLists.txt",
    "content": "ament_add_gtest(test_node_interface\ntest_node_interface.cpp\n)\ntarget_include_directories(test_node_interface PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_node_interface\n  ${canopen_interfaces_TARGETS}\n  canopen_base_driver::base_driver\n  canopen_base_driver::lely_driver_bridge\n  canopen_base_driver::lifecycle_base_driver\n  canopen_base_driver::node_canopen_base_driver\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  node_canopen_proxy_driver\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n\n\n\nament_add_gtest(test_driver_component\ntest_driver_component.cpp\n)\ntarget_include_directories(test_driver_component PUBLIC\n    ${CMAKE_CURRENT_SOURCE_DIR}/../include/\n)\ntarget_link_libraries(test_driver_component\n  ${canopen_interfaces_TARGETS}\n  canopen_base_driver::base_driver\n  canopen_base_driver::lely_driver_bridge\n  canopen_base_driver::lifecycle_base_driver\n  canopen_base_driver::node_canopen_base_driver\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n\nfile(COPY ${CMAKE_CURRENT_SOURCE_DIR}/master.dcf DESTINATION ${CMAKE_CURRENT_BINARY_DIR})\n"
  },
  {
    "path": "canopen_proxy_driver/test/master.dcf",
    "content": "[DeviceComissioning]\nNodeID=1\nNodeName=\nNodeRefd=\nBaudrate=1000\nNetNumber=1\nNetworkName=\nNetRefd=\nCANopenManager=1\nLSS_SerialNumber=0x00000000\n\n[DeviceInfo]\nVendorName=\nVendorNumber=0x00000000\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=1\nSimpleBootUpSlave=0\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=2\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=32\n1=0x1003\n2=0x1005\n3=0x1006\n4=0x1007\n5=0x1014\n6=0x1015\n7=0x1016\n8=0x1017\n9=0x1019\n10=0x1028\n11=0x1029\n12=0x102A\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1A00\n20=0x1A01\n21=0x1F25\n22=0x1F55\n23=0x1F80\n24=0x1F81\n25=0x1F82\n26=0x1F84\n27=0x1F85\n28=0x1F86\n29=0x1F87\n30=0x1F88\n31=0x1F89\n32=0x1F8A\n\n[ManufacturerObjects]\nSupportedObjects=12\n1=0x2000\n2=0x2001\n3=0x2200\n4=0x2201\n5=0x5800\n6=0x5801\n7=0x5A00\n8=0x5A01\n9=0x5C00\n10=0x5C01\n11=0x5E00\n12=0x5E01\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x40000080\n\n[1006]\nParameterName=Communication cycle period\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1007]\nParameterName=Synchronous window length\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1016Value]\nNrOfEntries=0\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1018]\nSubNumber=5\nParameterName=Identity Object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1019]\nParameterName=Synchronous counter overflow value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1028]\nParameterName=Emergency consumer object\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x80000000\nCompactSubObj=127\n\n[1028Value]\nNrOfEntries=2\n2=0x00000082\n3=0x00000083\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=254\n\n[1029Value]\nNrOfEntries=1\n1=0x00\n\n[102A]\nParameterName=NMT inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000182\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1401]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1401sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1401sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000183\n\n[1401sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1401sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1401sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1401sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x20000120\n\n[1601]\nParameterName=RPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1601Value]\nNrOfEntries=1\n1=0x20010120\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000202\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000203\n\n[1801sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1801sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x22000120\n\n[1A01]\nParameterName=TPDO mapping parameter\nObjectType=0x09\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x22010120\n\n[1F25]\nParameterName=Configuration request\nObjectType=0x08\nDataType=0x0005\nAccessType=wo\nCompactSubObj=127\n\n[1F55]\nParameterName=Expected software identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F80]\nParameterName=NMT startup\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000001\n\n[1F81]\nParameterName=NMT slave assignment\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F81Value]\nNrOfEntries=2\n2=0x00000005\n3=0x00000005\n\n[1F82]\nParameterName=Request NMT\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F84]\nParameterName=Device type identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F84Value]\nNrOfEntries=0\n\n[1F85]\nParameterName=Vendor identification\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F85Value]\nNrOfEntries=2\n2=0x00000360\n3=0x00000360\n\n[1F86]\nParameterName=Product code\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F86Value]\nNrOfEntries=0\n\n[1F87]\nParameterName=Revision_number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F88]\nParameterName=Serial number\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=127\n\n[1F89]\nParameterName=Boot time\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\n\n[1F8A]\nParameterName=Restore configuration\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=127\n\n[1F8AValue]\nNrOfEntries=0\n\n[2000]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 1\nObjectType=0x09\n\n[2000sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2000sub1]\nParameterName=proxy_device_1: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2001]\nSubNumber=2\nParameterName=Mapped application objects for RPDO 2\nObjectType=0x09\n\n[2001sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2001sub1]\nParameterName=proxy_device_2: UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[2200]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 1\nObjectType=0x09\n\n[2200sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2200sub1]\nParameterName=proxy_device_1: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[2201]\nSubNumber=2\nParameterName=Mapped application objects for TPDO 2\nObjectType=0x09\n\n[2201sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=1\n\n[2201sub1]\nParameterName=proxy_device_2: UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[5800]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5801]\nParameterName=Remote TPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5A00]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[5A01]\nParameterName=Remote TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5A01Value]\nNrOfEntries=1\n1=0x40010020\n\n[5C00]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000102\n\n[5C01]\nParameterName=Remote RPDO number and node-ID\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000103\n\n[5E00]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E00Value]\nNrOfEntries=1\n1=0x40000020\n\n[5E01]\nParameterName=Remote RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[5E01Value]\nNrOfEntries=1\n1=0x40000020\n"
  },
  {
    "path": "canopen_proxy_driver/test/test_driver_component.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <rclcpp_components/component_manager.hpp>\n#include <rclcpp_components/node_factory.hpp>\n#include <rclcpp_components/node_instance_wrapper.hpp>\n#include <thread>\n#include \"canopen_base_driver/node_interfaces/node_canopen_base_driver.hpp\"\n#include \"gtest/gtest.h\"\nusing namespace rclcpp_components;\n\nTEST(ComponentLoad, test_load_component_1)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_proxy_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[0]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n\nTEST(ComponentLoad, test_load_component_2)\n{\n  rclcpp::init(0, nullptr);\n  auto exec = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  auto manager = std::make_shared<rclcpp_components::ComponentManager>(exec);\n\n  std::vector<ComponentManager::ComponentResource> resources =\n    manager->get_component_resources(\"canopen_proxy_driver\");\n\n  EXPECT_EQ(2u, resources.size());\n\n  auto factory = manager->create_component_factory(resources[1]);\n  auto instance_wrapper =\n    factory->create_node_instance(rclcpp::NodeOptions().use_global_arguments(false));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_proxy_driver/test/test_node_interface.cpp",
    "content": "//    Copyright 2022 Christoph Hellmann Santos\n//\n//    Licensed under the Apache License, Version 2.0 (the \"License\");\n//    you may not use this file except in compliance with the License.\n//    You may obtain a copy of the License at\n//\n//        http://www.apache.org/licenses/LICENSE-2.0\n//\n//    Unless required by applicable law or agreed to in writing, software\n//    distributed under the License is distributed on an \"AS IS\" BASIS,\n//    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n//    See the License for the specific language governing permissions and\n//    limitations under the License.\n\n#include <rclcpp/executors.hpp>\n#include <thread>\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n#include \"gtest/gtest.h\"\n\nTEST(NodeCanopenProxyDriver, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp::Node * node = new rclcpp::Node(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenProxyDriver(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\n    \"config\",\n    \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage: \\\"canopen_core\\\"\\ndcf: \"\n    \"\\\"simple.eds\\\"\\ndcf_path: \\\"\\\"\\n\");\n  node->set_parameter(container_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  // Can't activate as master cannot be set.\n  EXPECT_ANY_THROW(iface->activate());\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n\nTEST(NodeCanopenBasicLifecycleMaster, test_good_sequence_advanced)\n{\n  rclcpp::init(0, nullptr);\n  rclcpp_lifecycle::LifecycleNode * node = new rclcpp_lifecycle::LifecycleNode(\"Node\");\n  auto interface = new ros2_canopen::node_interfaces::NodeCanopenProxyDriver(node);\n  auto exec = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n  exec->add_node(node->get_node_base_interface());\n  std::thread spinner = std::thread([exec] { exec->spin(); });\n\n  auto iface = static_cast<ros2_canopen::node_interfaces::NodeCanopenDriverInterface *>(interface);\n\n  EXPECT_NO_THROW(iface->init());\n\n  rclcpp::Parameter container_name(\"container_name\", \"none\");\n  rclcpp::Parameter node_id(\"node_id\", 1);\n  rclcpp::Parameter timeout(\"non_transmit_timeout\", 100);\n  rclcpp::Parameter config(\n    \"config\",\n    \"node_id: 1\\ndriver: \\\"ros2_canopen::CanopenDriver\\\"\\npackage: \\\"canopen_core\\\"\\ndcf: \"\n    \"\\\"simple.eds\\\"\\ndcf_path: \\\"\\\"\\n\");\n  node->set_parameter(container_name);\n  node->set_parameter(node_id);\n  node->set_parameter(timeout);\n  node->set_parameter(config);\n  EXPECT_NO_THROW(iface->configure());\n  // Can't activate as master cannot be set.\n  EXPECT_ANY_THROW(iface->activate());\n  rclcpp::shutdown();\n  std::this_thread::sleep_for(std::chrono::milliseconds(100));\n  if (spinner.joinable())\n  {\n    spinner.join();\n  }\n}\n"
  },
  {
    "path": "canopen_ros2_control/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_ros2_control\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* add pdo 6077 torque actual value to the joint state interface as effort (`#316 <https://github.com/ros-industrial/ros2_canopen/issues/316>`_)\n  Co-authored-by: Vishnuprasad Prachandabhanu <32260301+ipa-vsp@users.noreply.github.com>\n* Refactor on_init method for improved readability and consistency\n* Fix deprecated hardware_interface API (`#386 <https://github.com/ros-industrial/ros2_canopen/issues/386>`_)\n* Fix typos in warning messages and comments for clarity\n* `#379 <https://github.com/ros-industrial/ros2_canopen/issues/379>`_: Fix data conversion in the Lely Bridge to enable more data types and proper handling of Emcy in ros2_control\n* Return error on Emcy.\n* Add correct data conversion for Emcy.\n* Fixed types handling in canopen_ros2_control.\n* Optimize debug output.\n* Fixed sending values.\n* Contributors: Christoph Fröhlich, Dr. Denis Stogl, Vishnuprasad Prachandabhanu, synsi23b\n\n0.3.1 (2025-06-23)\n------------------\n* Fixing ID type in storage of ros2_control system.\n* Contributors: Dr. Denis, Gerry Salinas, Vishnuprasad Prachandabhanu\n\n0.3.0 (2024-12-12)\n------------------\n* pre-commit fix\n* impl operation mode\n* Add cyclic torque mode to cia402 driver and robot system controller (`#293 <https://github.com/ros-industrial/ros2_canopen/issues/293>`_)\n  * Add base functions for switching to cyclic torque mode\n  * Add cyclic torque mode as effort interface to robot_system controller\n  * Add documentation about cyclic torque mode.\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n* Fix clang format\n* Update canopen_system.hpp\n* Add pdo mapping support\n* Fix clang format\n* Fix pre-commit\n* Periodic messages sent, but not received properly.\n* Fix the bug that the rpdo queue keeps poping although it is empty.\n* Use proper function to get rpdo data\n* Fix bug in state interface indexing..\n* WIP: Extend the rpdo to have a queue (FIFO) to save the values.\n  The read function take the latest value out of the queue and assign to the system interface.\n  Need tests.\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Contributors: ipa-vsp\n\n0.2.9 (2024-04-16)\n------------------\n\n0.2.8 (2024-01-19)\n------------------\n* Update robot_system.cpp (`#168 <https://github.com/ros-industrial/ros2_canopen/issues/168>`_)\n* Contributors: Christoph Hellmann Santos\n\n0.2.7 (2023-06-30)\n------------------\n* Correct Proxy controller after changes and update tests.\n* Contributors: Dr. Denis, Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n* Solve buildfarm issues\n* Contributors: Christoph Hellmann Santos\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Use consistenlty (uppercase) HEX output for NodeID and Index.\n* Contributors: Christoph Hellmann Santos, Denis Štogl\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Lovro, Vishnuprasad Prachandabhanu, livanov93\n"
  },
  {
    "path": "canopen_ros2_control/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_ros2_control)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n    # add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\nfind_package(ament_cmake REQUIRED)\nfind_package(canopen_402_driver REQUIRED)\nfind_package(canopen_core REQUIRED)\nfind_package(canopen_proxy_driver REQUIRED)\nfind_package(hardware_interface REQUIRED)\nfind_package(pluginlib REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_components REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\nfind_package(ros2_control_test_assets)\n\nadd_library(\n  canopen_ros2_control\n  SHARED\n  src/canopen_system.cpp\n  src/cia402_system.cpp\n  src/robot_system.cpp\n)\n\n\n\ntarget_compile_features(canopen_ros2_control PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\ntarget_compile_options(canopen_ros2_control PUBLIC -fPIC -Wl,--no-undefined)\n\ntarget_include_directories(canopen_ros2_control PUBLIC include)\ntarget_link_libraries(canopen_ros2_control PUBLIC\n  canopen_402_driver::cia402_driver\n  canopen_402_driver::lely_motion_controller_bridge\n  canopen_402_driver::lifecycle_cia402_driver\n  canopen_402_driver::node_canopen_cia402_driver\n  canopen_core::device_container\n  canopen_core::node_canopen_driver\n  canopen_core::node_canopen_master\n  canopen_proxy_driver::lifecycle_proxy_driver\n  canopen_proxy_driver::node_canopen_proxy_driver\n  canopen_proxy_driver::proxy_driver\n  hardware_interface::hardware_interface\n  hardware_interface::mock_components\n  pluginlib::pluginlib\n  rclcpp::rclcpp\n  rclcpp_components::component\n  rclcpp_components::component_manager\n  rclcpp_lifecycle::rclcpp_lifecycle\n)\n\n# prevent pluginlib from using boost\ntarget_compile_definitions(canopen_ros2_control PUBLIC \"PLUGINLIB__DISABLE_BOOST_FUNCTIONS\")\n\npluginlib_export_plugin_description_file(hardware_interface canopen_ros2_control.xml)\n\ninstall(\n  TARGETS\n  canopen_ros2_control\n  RUNTIME DESTINATION bin\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n)\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\nif(BUILD_TESTING)\n  #find_package(ament_cmake_gmock REQUIRED)\n  #find_package(ros2_control_test_assets REQUIRED)\n\n  #ament_add_gmock(test_canopen_system test/test_canopen_system.cpp)\n  #target_include_directories(test_canopen_system PRIVATE include)\n  #target_link_libraries(test_canopen_system ...\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  canopen_ros2_control\n)\nament_export_dependencies(\n  canopen_402_driver\n  canopen_core\n  canopen_proxy_driver\n  hardware_interface\n  pluginlib\n  rclcpp\n  rclcpp_components\n  rclcpp_lifecycle\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_ros2_control/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_ros2_control/canopen_ros2_control.xml",
    "content": "<library path=\"canopen_ros2_control\">\n  <class name=\"canopen_ros2_control/CanopenSystem\"\n         type=\"canopen_ros2_control::CanopenSystem\"\n         base_class_type=\"hardware_interface::SystemInterface\">\n    <description>\n      ros2_control hardware interface.\n    </description>\n  </class>\n  <class name=\"canopen_ros2_control/Cia402System\"\n         type=\"canopen_ros2_control::Cia402System\"\n         base_class_type=\"hardware_interface::SystemInterface\">\n    <description>\n      ros2_control hardware interface.\n    </description>\n  </class>\n  <class name=\"canopen_ros2_control/RobotSystem\"\n         type=\"canopen_ros2_control::RobotSystem\"\n         base_class_type=\"hardware_interface::SystemInterface\">\n    <description>\n      ros2_control hardware interface.\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/canopen_system.hpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n//----------------------------------------------------------------------\n/*!\\file\n *\n * \\author  Lovro Ivanov lovro.ivanov@gmail.com\n * \\date    2022-06-29\n *\n */\n//----------------------------------------------------------------------\n\n#ifndef CANOPEN_ROS2_CONTROL__CANOPEN_SYSTEM_HPP_\n#define CANOPEN_ROS2_CONTROL__CANOPEN_SYSTEM_HPP_\n\n#include <functional>\n#include <limits>\n#include <queue>\n#include <string>\n#include <unordered_map>\n#include <vector>\n\n#include \"canopen_core/device_container.hpp\"\n#include \"canopen_proxy_driver/proxy_driver.hpp\"\n#include \"canopen_ros2_control/visibility_control.h\"\n#include \"hardware_interface/handle.hpp\"\n#include \"hardware_interface/hardware_info.hpp\"\n#include \"hardware_interface/system_interface.hpp\"\n#include \"hardware_interface/types/hardware_interface_return_values.hpp\"\n#include \"rclcpp/executors.hpp\"\n#include \"rclcpp/macros.hpp\"\n#include \"rclcpp_lifecycle/state.hpp\"\n\nnamespace canopen_ros2_control\n{\ntemplate <typename TargetType, typename SourceType>\nauto makeMemcpyCaster(const SourceType & source)\n{\n  return [&source]() -> TargetType\n  {\n    TargetType target;\n    std::memcpy(&target, &source, sizeof(TargetType));\n    return target;\n  };\n}\n\nconst std::vector<std::string> SUPPORTED_TYPES = {\"bool\",     \"int8_t\",  \"uint8_t\", \"int16_t\",\n                                                  \"uint16_t\", \"int32_t\", \"uint32_t\"};\n\n// needed auxiliary struct for ros2 control double registration\nstruct Ros2ControlCOData\n{\n  // TODO(Dr.Denis): rename original data to canopen data\n  // Soon we can drop this as ros2_control support variants - we have to add support for all this\n  // types\n  ros2_canopen::COData original_data;\n\n  double index;     // cast to uint16_t\n  double subindex;  // cast to uint8_t\n  double data;      // cast to uint32_t\n\n  std::string co_type = \"int32_t\";  // use int32_t as default\n\n  void set_co_data_type(const std::string & type)\n  {\n    if (\n      type.empty() ||\n      std::find(SUPPORTED_TYPES.begin(), SUPPORTED_TYPES.end(), type) != SUPPORTED_TYPES.end())\n    {\n      co_type = type;\n    }\n    else\n    {\n      RCLCPP_WARN(\n        rclcpp::get_logger(\"rclcpp\"),\n        \"Type '%s' empty or not yet supported. Using 'int32_t' as default to cast directly to \"\n        \"double. This might cause erroneous data! Please contribute or by maintainers a cookie and \"\n        \"hope they implement it for you!\",\n        type.c_str());\n      co_type = \"int32_t\";\n    }\n  }\n};\n\nstruct RORos2ControlCOData : public Ros2ControlCOData\n{\n  void set_data(ros2_canopen::COData d) { original_data = d; }\n\n  void prepare_data()\n  {\n    index = static_cast<double>(original_data.index_);\n    subindex = static_cast<double>(original_data.subindex_);\n\n    if (co_type == \"bool\")\n    {\n      bool bool_data;\n      std::memcpy(&bool_data, &original_data.data_, sizeof(bool));\n      data = static_cast<double>(bool_data);\n    }\n    else if (co_type == \"int8_t\")\n    {\n      int8_t int8_data;\n      std::memcpy(&int8_data, &original_data.data_, sizeof(int8_t));\n      data = static_cast<double>(int8_data);\n    }\n    else if (co_type == \"uint8_t\")\n    {\n      uint8_t uint8_data;\n      std::memcpy(&uint8_data, &original_data.data_, sizeof(uint8_t));\n      data = static_cast<double>(uint8_data);\n    }\n    else if (co_type == \"int16_t\")\n    {\n      int16_t int16_data;\n      std::memcpy(&int16_data, &original_data.data_, sizeof(int16_t));\n      data = static_cast<double>(int16_data);\n    }\n    else if (co_type == \"uint16_t\")\n    {\n      uint16_t uint16_data;\n      std::memcpy(&uint16_data, &original_data.data_, sizeof(uint16_t));\n      data = static_cast<double>(uint16_data);\n    }\n    else if (co_type == \"int32_t\")\n    {\n      int32_t int32_data;\n      std::memcpy(&int32_data, &original_data.data_, sizeof(int32_t));\n      data = static_cast<double>(int32_data);\n    }\n    else if (co_type == \"uint32_t\")\n    {\n      uint32_t uint32_data;\n      std::memcpy(&uint32_data, &original_data.data_, sizeof(uint32_t));\n      data = static_cast<double>(uint32_data);\n    }\n    else\n    {\n      RCLCPP_WARN(\n        rclcpp::get_logger(\"rclcpp\"),\n        \"Type '%s' not yet supported. Trying to cast directly to double. This might cause \"\n        \"erroneous data! Please contribute or by maintainers a cookie and hope they implement it \"\n        \"for you!\",\n        co_type.c_str());\n      data = static_cast<double>(original_data.data_);\n    }\n  }\n};\n\nstruct WORos2ControlCoData : public Ros2ControlCOData\n{\n  WORos2ControlCoData() : one_shot(std::numeric_limits<double>::quiet_NaN()) {}\n\n  // needed internally for write-only data\n  double one_shot;\n\n  bool write_command()\n  {\n    bool ret_val;\n    // store ret value\n    ret_val = !std::isnan(one_shot);\n    // reset the existing active command if one exists\n    one_shot = std::numeric_limits<double>::quiet_NaN();\n    return ret_val;\n  }\n\n  void prepare_data()\n  {\n    original_data.index_ = static_cast<uint16_t>(index);\n    original_data.subindex_ = static_cast<uint8_t>(subindex);\n\n    if (co_type == \"bool\")\n    {\n      bool bool_data = static_cast<bool>(data);\n      std::memcpy(&original_data.data_, &bool_data, sizeof(bool));\n    }\n    else if (co_type == \"int8_t\")\n    {\n      int8_t int8_data = static_cast<int8_t>(data);\n      std::memcpy(&original_data.data_, &int8_data, sizeof(int8_t));\n    }\n    else if (co_type == \"uint8_t\")\n    {\n      uint8_t uint8_data = static_cast<uint8_t>(data);\n      std::memcpy(&original_data.data_, &uint8_data, sizeof(uint8_t));\n    }\n    else if (co_type == \"int16_t\")\n    {\n      int16_t int16_data = static_cast<int16_t>(data);\n      std::memcpy(&original_data.data_, &int16_data, sizeof(int16_t));\n    }\n    else if (co_type == \"uint16_t\")\n    {\n      uint16_t uint16_data = static_cast<uint16_t>(data);\n      std::memcpy(&original_data.data_, &uint16_data, sizeof(uint16_t));\n    }\n    else if (co_type == \"int32_t\")\n    {\n      int32_t int32_data = static_cast<int32_t>(data);\n      std::memcpy(&original_data.data_, &int32_data, sizeof(int32_t));\n    }\n    else if (co_type == \"uint32_t\")\n    {\n      uint32_t uint32_data = static_cast<uint32_t>(data);\n      std::memcpy(&original_data.data_, &uint32_data, sizeof(uint32_t));\n    }\n    else\n    {\n      RCLCPP_WARN(\n        rclcpp::get_logger(\"rclcpp\"),\n        \"Type '%s' not yet supported. Trying to cast directly to uint32_t. This might cause \"\n        \"erroneous data! Please contribute or by maintainers a cookie and hope they implement it \"\n        \"for you!\",\n        co_type.c_str());\n      original_data.data_ = static_cast<uint32_t>(data);\n    }\n  }\n};\n\nstruct Ros2ControlEmcyData\n{\n  Ros2ControlEmcyData()\n  : error_code(0),\n    error_register(0),\n    manufacturer_error_code1(0),\n    manufacturer_error_code2(0),\n    manufacturer_error_code3(0),\n    manufacturer_error_code4(0),\n    manufacturer_error_code5(0)\n  {\n  }\n\n  void set_emcy(ros2_canopen::COEmcy e)\n  {\n    original_emcy = e;\n\n    uint16_t eec_data;\n    std::memcpy(&eec_data, &e.eec, sizeof(uint16_t));\n    error_code = static_cast<double>(eec_data);\n\n    uint8_t er_data;\n    std::memcpy(&er_data, &e.er, sizeof(uint8_t));\n    error_register = static_cast<double>(er_data);\n\n    uint16_t msef_data;\n    std::memcpy(&msef_data, &e.msef[0], sizeof(uint16_t));\n    manufacturer_error_code1 = static_cast<double>(msef_data);\n    std::memcpy(&msef_data, &e.msef[1], sizeof(uint16_t));\n    manufacturer_error_code2 = static_cast<double>(msef_data);\n    std::memcpy(&msef_data, &e.msef[2], sizeof(uint16_t));\n    manufacturer_error_code3 = static_cast<double>(msef_data);\n    std::memcpy(&msef_data, &e.msef[3], sizeof(uint16_t));\n    manufacturer_error_code4 = static_cast<double>(msef_data);\n    std::memcpy(&msef_data, &e.msef[4], sizeof(uint16_t));\n    manufacturer_error_code5 = static_cast<double>(msef_data);\n  }\n\n  double error_code;                // read-only\n  double error_register;            // read-only\n  double manufacturer_error_code1;  // read-only\n  double manufacturer_error_code2;  // read-only\n  double manufacturer_error_code3;  // read-only\n  double manufacturer_error_code4;  // read-only\n  double manufacturer_error_code5;  // read-only\n\n  ros2_canopen::COEmcy original_emcy;  // read-only\n};\n\nstruct Ros2ControlNmtState\n{\n  Ros2ControlNmtState()\n  : reset_ons(std::numeric_limits<double>::quiet_NaN()),\n    reset_fbk(std::numeric_limits<double>::quiet_NaN()),\n    start_ons(std::numeric_limits<double>::quiet_NaN()),\n    start_fbk(std::numeric_limits<double>::quiet_NaN())\n  {\n  }\n\n  void set_state(canopen::NmtState s)\n  {\n    original_state = s;\n    state = static_cast<double>(s);\n  }\n\n  bool reset_command()\n  {\n    bool ret_val;\n    // store ret value\n    ret_val = !std::isnan(reset_ons);\n    // reset the existing active command if one exists\n    reset_ons = std::numeric_limits<double>::quiet_NaN();\n    return ret_val;\n  }\n\n  bool start_command()\n  {\n    bool ret_val;\n    // store ret value\n    ret_val = !std::isnan(start_ons);\n    // reset the existing active command if one exists\n    start_ons = std::numeric_limits<double>::quiet_NaN();\n    return ret_val;\n  }\n  canopen::NmtState original_state;\n\n  double state;  // read-only\n\n  // basic commands\n  double reset_ons;  // write-only\n  double reset_fbk;\n  double start_ons;  // write-only\n  double start_fbk;\n};\n\nstruct pair_hash\n{\n  template <class T1, class T2>\n  std::size_t operator()(const std::pair<T1, T2> & pair) const\n  {\n    auto h1 = std::hash<T1>{}(pair.first);\n    auto h2 = std::hash<T2>{}(pair.second);\n\n    return h1 ^ h2;\n  }\n};\n\nstruct CanopenNodeData\n{\n  Ros2ControlNmtState nmt_state;  // read-write\n  RORos2ControlCOData rpdo_data;  // read-only\n  WORos2ControlCoData tpdo_data;  // write-only\n\n  Ros2ControlEmcyData emcy_data;  // read-only\n\n  WORos2ControlCoData rsdo;  // write-only\n  WORos2ControlCoData wsdo;  // write-only\n\n  using PDO_INDICES = std::pair<uint16_t, uint8_t>;  // Index, Subindex\n  std::unordered_map<PDO_INDICES, double, pair_hash>\n    rpdo_data_map;  // kept for backward compoatibility - should b removed\n  std::unordered_map<PDO_INDICES, uint32_t, pair_hash> rpdo_raw_data_map;\n\n  // Push data to the queue - FIFO\n  void set_rpdo_data(ros2_canopen::COData d)\n  {\n    rpdo_data.set_data(d);\n    rpdo_data.prepare_data();\n\n    PDO_INDICES index_pair(d.index_, d.subindex_);\n\n    // check if the index pair is already in the map\n    if (rpdo_raw_data_map.find(index_pair) != rpdo_raw_data_map.end())\n    {\n      // if it is, update the value\n      rpdo_raw_data_map.at(index_pair) = d.data_;\n    }\n    else\n    {\n      // if it is not, add it to the map\n      rpdo_raw_data_map.emplace(index_pair, d.data_);\n    }\n    // TODO(Dr.Denis): kept for backward compatibility - should be removed\n    // check if the index pair is already in the map\n    if (rpdo_data_map.find(index_pair) != rpdo_data_map.end())\n    {\n      // if it is, update the value\n      rpdo_data_map.at(index_pair) = rpdo_data.data;\n    }\n    else\n    {\n      // if it is not, add it to the map\n      rpdo_data_map.emplace(index_pair, rpdo_data.data);\n    }\n  }\n\n  uint32_t get_rpdo_raw_data(uint16_t index, uint8_t subindex)\n  {\n    PDO_INDICES index_pair(index, subindex);\n    if (rpdo_raw_data_map.find(index_pair) != rpdo_raw_data_map.end())\n    {\n      return rpdo_raw_data_map.at(index_pair);\n    }\n    else\n    {\n      // Log error\n      // RCLCPP_WARN(kLogger, \"The index pair (%u, %u) is not in the map\", index, subindex);\n      return std::numeric_limits<uint32_t>::quiet_NaN();\n    }\n  }\n\n  // Pop data from the queue\n  double get_rpdo_data(uint16_t index, uint8_t subindex)\n  {\n    PDO_INDICES index_pair(index, subindex);\n    if (rpdo_data_map.find(index_pair) != rpdo_data_map.end())\n    {\n      return rpdo_data_map[index_pair];\n    }\n    else\n    {\n      // // Log error\n      // RCLCPP_WARN(kLogger, \"The index pair (%u, %u) is not in the map\", index, subindex);\n      return std::numeric_limits<double>::quiet_NaN();\n    }\n  }\n};\n\nclass CanopenSystem : public hardware_interface::SystemInterface\n{\npublic:\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  CanopenSystem();\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  ~CanopenSystem();\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_init(\n    const hardware_interface::HardwareComponentInterfaceParams & params) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::StateInterface> export_state_interfaces() override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type read(\n    const rclcpp::Time & time, const rclcpp::Duration & period) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type write(\n    const rclcpp::Time & time, const rclcpp::Duration & period) override;\n\nprotected:\n  std::shared_ptr<ros2_canopen::DeviceContainer> device_container_;\n  std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;\n  // can stuff\n  std::map<uint16_t, CanopenNodeData> canopen_data_;\n  // threads\n  std::unique_ptr<std::thread> spin_thread_;\n  std::unique_ptr<std::thread> init_thread_;\n\n  void spin();\n  void clean();\n\nprivate:\n  void initDeviceContainer();\n};\n\n}  // namespace canopen_ros2_control\n\n#endif  // CANOPEN_ROS2_CONTROL__CANOPEN_SYSTEM_HPP_\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/cia402_data.hpp",
    "content": "// Copyright (c) 2023, Fraunhofer IPA\n// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROL__CIA402_DATA_HPP_\n#define CANOPEN_ROS2_CONTROL__CIA402_DATA_HPP_\n#include <yaml-cpp/yaml.h>\n#include <cstdint>\n#include <memory>\n#include <string>\n#include \"canopen_402_driver/base.hpp\"\n#include \"canopen_402_driver/cia402_driver.hpp\"\n#include \"canopen_ros2_control/helpers.hpp\"\n#include \"hardware_interface/handle.hpp\"\n#include \"hardware_interface/hardware_info.hpp\"\n#include \"hardware_interface/types/hardware_interface_type_values.hpp\"\n\nusing namespace ros2_canopen;\nnamespace canopen_ros2_control\n{\nstruct Cia402Data\n{\n  uint8_t node_id;\n  uint8_t channel = 0;  // Channel for multi-axis support (0 for single-axis, 1+ for multi-axis)\n  std::string joint_name;\n  std::shared_ptr<ros2_canopen::Cia402Driver> driver;\n  std::map<std::string, ros2_canopen::MotorBase::OperationMode> command_interface_to_operation_mode;\n  std::vector<std::string> interfaces;\n  std::vector<std::string> interfaces_to_start;\n  std::vector<std::string> interfaces_to_running;\n  std::vector<std::string> interfaces_to_stop;\n  YAML::Node config;\n\n  // FROM MOTOR\n  double actual_position = std::numeric_limits<double>::quiet_NaN();\n  double actual_velocity = std::numeric_limits<double>::quiet_NaN();\n  double actual_effort = std::numeric_limits<double>::quiet_NaN();\n\n  // TO MOTOR\n  double target_position = std::numeric_limits<double>::quiet_NaN();\n  double target_velocity = std::numeric_limits<double>::quiet_NaN();\n  double target_torque = std::numeric_limits<double>::quiet_NaN();\n\n  bool init_data(hardware_interface::ComponentInfo & joint, std::string device_dump)\n  {\n    joint_name = joint.name;\n    auto config = YAML::Load(device_dump);\n\n    if (!config[\"node_id\"])\n    {\n      RCLCPP_ERROR(rclcpp::get_logger(joint_name), \"No node id for '%s'\", joint.name.c_str());\n      return false;\n    }\n\n    node_id = config[\"node_id\"].as<uint16_t>();\n\n    // Get channel parameter (defaults to 0 for backward compatibility)\n    if (config[\"channel\"])\n    {\n      channel = config[\"channel\"].as<uint8_t>();\n      RCLCPP_INFO(\n        rclcpp::get_logger(joint_name), \"Node id for '%s' is '%u', channel is '%u'\",\n        joint.name.c_str(), node_id, channel);\n    }\n    else\n    {\n      RCLCPP_ERROR(\n        rclcpp::get_logger(joint_name), \"Node id for '%s' is '%u'\", joint.name.c_str(), node_id);\n    }\n\n    if (config[\"position_mode\"])\n    {\n      auto position_mode =\n        (ros2_canopen::MotorBase::OperationMode)config[\"position_mode\"].as<uint>();\n      RCLCPP_INFO(\n        rclcpp::get_logger(joint_name), \"Registered position_mode '%u' for '%s'\", position_mode,\n        joint.name.c_str());\n      command_interface_to_operation_mode.emplace(\n        std::pair(joint.name + \"/\" + \"position\", position_mode));\n    }\n    if (config[\"velocity_mode\"])\n    {\n      auto velocity_mode =\n        (ros2_canopen::MotorBase::OperationMode)config[\"velocity_mode\"].as<uint>();\n      RCLCPP_INFO(\n        rclcpp::get_logger(joint_name), \"Registered velocity_mode '%u' for '%s'\", velocity_mode,\n        joint.name.c_str());\n      command_interface_to_operation_mode.emplace(\n        std::pair(joint.name + \"/\" + \"velocity\", velocity_mode));\n    }\n    if (config[\"effort_mode\"])\n    {\n      auto effort_mode = (ros2_canopen::MotorBase::OperationMode)config[\"effort_mode\"].as<uint>();\n      RCLCPP_INFO(\n        rclcpp::get_logger(joint_name), \"Registered effort_mode '%u' for '%s'\", effort_mode,\n        joint.name.c_str());\n      command_interface_to_operation_mode.emplace(\n        std::pair(joint.name + \"/\" + \"effort\", effort_mode));\n    }\n    return true;\n  }\n\n  void export_state_interface(std::vector<hardware_interface::StateInterface> & state_interfaces)\n  {\n    // actual position\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      joint_name, hardware_interface::HW_IF_POSITION, &actual_position));\n\n    // actual speed\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      joint_name, hardware_interface::HW_IF_VELOCITY, &actual_velocity));\n\n    // actual effort\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      joint_name, hardware_interface::HW_IF_EFFORT, &actual_effort));\n  }\n\n  void export_command_interface(\n    std::vector<hardware_interface::CommandInterface> & command_interfaces)\n  {\n    if (\n      command_interface_to_operation_mode.find(joint_name + \"/\" + \"position\") !=\n      command_interface_to_operation_mode.end())\n    {\n      // target position\n      command_interfaces.emplace_back(\n        joint_name, hardware_interface::HW_IF_POSITION, &target_position);\n      interfaces.push_back(joint_name + \"/\" + \"position\");\n    }\n    if (\n      command_interface_to_operation_mode.find(joint_name + \"/\" + \"velocity\") !=\n      command_interface_to_operation_mode.end())\n    {\n      // target velocity\n      command_interfaces.emplace_back(\n        joint_name, hardware_interface::HW_IF_VELOCITY, &target_velocity);\n      interfaces.push_back(joint_name + \"/\" + \"velocity\");\n    }\n    if (\n      command_interface_to_operation_mode.find(joint_name + \"/\" + \"effort\") !=\n      command_interface_to_operation_mode.end())\n    {\n      // target effort\n      command_interfaces.emplace_back(joint_name, hardware_interface::HW_IF_EFFORT, &target_torque);\n      interfaces.push_back(joint_name + \"/\" + \"effort\");\n    }\n  }\n\n  void read_state()\n  {\n    actual_position = driver->get_position();\n    actual_velocity = driver->get_speed();\n    actual_effort = driver->get_effort();\n  }\n\n  void write_target()\n  {\n    const uint16_t & mode = driver->get_mode();\n    switch (mode)\n    {\n      case MotorBase::No_Mode:\n        break;\n      case MotorBase::Profiled_Position:\n      case MotorBase::Cyclic_Synchronous_Position:\n      case MotorBase::Interpolated_Position:\n        driver->set_target(target_position);\n        break;\n      case MotorBase::Profiled_Velocity:\n      case MotorBase::Cyclic_Synchronous_Velocity:\n        driver->set_target(target_velocity);\n        break;\n      case MotorBase::Profiled_Torque:\n      case MotorBase::Cyclic_Synchronous_Torque:\n        driver->set_target(target_torque);\n        break;\n      default:\n        RCLCPP_INFO(rclcpp::get_logger(\"robot_system_interface\"), \"Mode not supported\");\n    }\n  }\n\n  bool perform_switch()\n  {\n    if (interfaces_to_start.size() > 1)\n    {\n      RCLCPP_ERROR(\n        rclcpp::get_logger(joint_name),\n        \"Trying to start multiple command interfaces at once for joint '%s'\", joint_name.c_str());\n      return false;\n    }\n    if (interfaces_to_start.size() == 0)\n    {\n      return true;\n    }\n    auto mode = command_interface_to_operation_mode[interfaces_to_start[0]];\n    interfaces_to_running.clear();\n    interfaces_to_running.push_back(interfaces_to_start[0]);\n    interfaces_to_stop.clear();\n    interfaces_to_start.clear();\n    RCLCPP_INFO(\n      rclcpp::get_logger(joint_name),\n      \"Switching to '%s' command mode with CIA402 operation mode '%u'\",\n      interfaces_to_running[0].c_str(), mode);\n    return driver->set_operation_mode(mode);\n  }\n\n  bool check_id(uint8_t id)\n  {\n    if (node_id == id)\n    {\n      return true;\n    }\n    return false;\n  }\n};\n}  // namespace canopen_ros2_control\n#endif\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/cia402_system.hpp",
    "content": "// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n//----------------------------------------------------------------------\n/*!\\file\n *\n * \\author  Lovro Ivanov lovro.ivanov@gmail.com\n * \\date    2022-08-01\n *\n */\n//----------------------------------------------------------------------\n\n#ifndef CANOPEN_ROS2_CONTROL__CIA402_SYSTEM_HPP_\n#define CANOPEN_ROS2_CONTROL__CIA402_SYSTEM_HPP_\n\n#include \"canopen_402_driver/cia402_driver.hpp\"\n#include \"canopen_ros2_control/canopen_system.hpp\"\n\nconstexpr double kResponseOk = 1.0;\nconstexpr double kResponseFail = 0.0;\n\nnamespace canopen_ros2_control\n{\n\nstruct MotorTriggerCommand\n{\n  double ons_cmd{std::numeric_limits<double>::quiet_NaN()};\n  double resp{std::numeric_limits<double>::quiet_NaN()};\n\n  bool is_commanded()\n  {\n    bool tmp = !std::isnan(ons_cmd);\n    ons_cmd = std::numeric_limits<double>::quiet_NaN();\n    return tmp;\n  }\n\n  void set_response(bool response) { resp = response ? kResponseOk : kResponseFail; }\n};\n\nstruct MotorTarget : public MotorTriggerCommand\n{\n  double position_value;\n  double velocity_value;\n  double torque_value;\n};\n\nstruct MotorNodeData\n{\n  // feedback\n  double actual_position;\n  double actual_speed;\n  double actual_effort;\n\n  // basic control\n  MotorTriggerCommand init;\n  MotorTriggerCommand halt;\n  MotorTriggerCommand recover;\n\n  // mode control\n  MotorTriggerCommand position_mode;\n  MotorTriggerCommand velocity_mode;\n  MotorTriggerCommand cyclic_velocity_mode;\n  MotorTriggerCommand cyclic_position_mode;\n  MotorTriggerCommand torque_mode;\n  MotorTriggerCommand interpolated_position_mode;\n\n  // setpoint\n  MotorTarget target;\n};\n\nusing namespace ros2_canopen;\nclass Cia402System : public CanopenSystem\n{\npublic:\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  Cia402System();\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  ~Cia402System() = default;\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_init(\n    const hardware_interface::HardwareComponentInterfaceParams & params);\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::StateInterface> export_state_interfaces();\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::CommandInterface> export_command_interfaces();\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type read(const rclcpp::Time & time, const rclcpp::Duration & period);\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type write(const rclcpp::Time & time, const rclcpp::Duration & period);\n\nprotected:\n  // can stuff\n  // Map from (node_id, channel) to motor data for multi-channel support\n  // channel 0 is used for single-channel devices for backward compatibility\n  std::map<std::pair<uint, uint>, MotorNodeData> motor_data_;\n\n  // Helper to get motor data key\n  std::pair<uint, uint> getMotorKey(uint node_id, uint channel = 0) const\n  {\n    return std::make_pair(node_id, channel);\n  }\n\nprivate:\n  void switchModes(\n    uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver);\n\n  void handleInit(\n    uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver);\n\n  void handleRecover(\n    uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver);\n\n  void handleHalt(\n    uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver);\n\n  void initDeviceContainer();\n};\n\n}  // namespace canopen_ros2_control\n\n#endif  // CANOPEN_ROS2_CONTROL__CIA402_SYSTEM_HPP_\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/helpers.hpp",
    "content": "// Copyright (c) 2023, Fraunhofer IPA\n// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROL__HELPER_HPP_\n#define CANOPEN_ROS2_CONTROL__HELPER_HPP_\n\n#include <cmath>\n#include <cstdint>\n#include <functional>\n#include <limits>\n\nnamespace canopen_ros2_control\n{\n/**\n * @brief Struct for storing the data necessary for a triggering command.\n *\n * @details\n * A trigger command from a controller will write to the command double.\n * The result of the trigger operation will be written to the response double.\n * A result of 1.0 means the operation was successful.\n * A result of 0.0 means the operation failed.\n * Only a trigger command of 1.0 will be accepted and trigger the operation.\n * The command_available function can be used to check if a command is available,\n * undefined commands (other than 1.0) will be ignored.\n * The set_response function should be used to set the response value.\n * It will then clear the command.\n *\n */\nstruct TriggerCommand\n{\n  double command = std::numeric_limits<double>::quiet_NaN();\n  double response = std::numeric_limits<double>::quiet_NaN();\n  std::function<bool()> trigger_function;\n\n  bool try_trigger()\n  {\n    if (command == 1.0)\n    {\n      response = trigger_function() ? 1.0 : 0.0;\n      command = std::numeric_limits<double>::quiet_NaN();\n      return true;\n    }\n    command = std::numeric_limits<double>::quiet_NaN();\n    return false;\n  }\n};\n\n}  // namespace canopen_ros2_control\n#endif\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/robot_system.hpp",
    "content": "// Copyright (c) 2023, Fraunhofer IPA\n// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n#ifndef CANOPEN_ROS2_CONTROL__ROBOT_SYSTEM_HPP_\n#define CANOPEN_ROS2_CONTROL__ROBOT_SYSTEM_HPP_\n\n#include \"canopen_402_driver/cia402_driver.hpp\"\n#include \"canopen_core/configuration_manager.hpp\"\n#include \"canopen_core/device_container.hpp\"\n#include \"canopen_ros2_control/cia402_data.hpp\"\n#include \"canopen_ros2_control/visibility_control.h\"\n#include \"hardware_interface/handle.hpp\"\n#include \"hardware_interface/hardware_info.hpp\"\n#include \"hardware_interface/system_interface.hpp\"\n#include \"hardware_interface/types/hardware_interface_return_values.hpp\"\n#include \"rclcpp/executors.hpp\"\n#include \"rclcpp/macros.hpp\"\n#include \"rclcpp_lifecycle/state.hpp\"\nnamespace canopen_ros2_control\n{\nclass RobotSystem : public hardware_interface::SystemInterface\n{\npublic:\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  RobotSystem() : hardware_interface::SystemInterface() {}\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  ~RobotSystem() = default;\n\n  /**\n   * @brief Initialize the hardware interface\n   *\n   * Fetch the hardware info stored in the urdf.\n   * Specifically these values:\n   * - bus_config\n   * - master_config\n   * - can_interface_name\n   * - master_bin\n   *\n   * @param info\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_init(\n    const hardware_interface::HardwareComponentInterfaceParams & params) override;\n\n  /**\n   * @brief Configure the hardware interface\n   *\n   * Create the device container and the executor.\n   * Start the threads for running the canopen stack.\n   *\n   * @param info\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  /**\n   * @brief Export the state interfaces for this system.\n   *\n   * The state interface of each cia402 device contains the following:\n   * - Position\n   * - Velocity\n   *\n   * @return std::vector<hardware_interface::StateInterface>\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::StateInterface> export_state_interfaces() override;\n\n  /**\n   * @brief Export the command interfaces for this system.\n   *\n   * The command interface of each cia402 device contains the following:\n   * - Position\n   * - Velocity\n   * - Effort\n   * - Operation Mode\n   * - Init Command\n   * - Halt Command\n   * - Recover Command\n   *\n   * @return std::vector<hardware_interface::CommandInterface>\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;\n\n  /**\n   * @brief Cleanup the hardware interface\n   *\n   * @param previous_state\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_cleanup(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  /**\n   * @brief Shutdown the hardware interface\n   *\n   * @param previous_state\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_shutdown(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  /**\n   * @brief Activate the hardware interface\n   *\n   * @param previous_state\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  /**\n   * @brief Deactivate the hardware interface\n   *\n   * @param previous_state\n   * @return hardware_interface::CallbackReturn\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  /**\n   * @brief Read the state from the hardware interface\n   *\n   * @return hardware_interface::return_type\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type read(\n    const rclcpp::Time & time, const rclcpp::Duration & period) override;\n\n  /**\n   * @brief Write the command to the hardware interface\n   *\n   * @return hardware_interface::return_type\n   */\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type write(\n    const rclcpp::Time & time, const rclcpp::Duration & period) override;\n\n  CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n  hardware_interface::return_type perform_command_mode_switch(\n    const std::vector<std::string> & start_interfaces,\n    const std::vector<std::string> & stop_interfaces) override;\n\nprotected:\n  std::shared_ptr<ros2_canopen::DeviceContainer> device_container_;\n  std::shared_ptr<rclcpp::executors::MultiThreadedExecutor> executor_;\n  std::vector<Cia402Data> robot_motor_data_;\n  std::string bus_config_;\n  std::string master_config_;\n  std::string master_bin_;\n  std::string can_interface_;\n  std::unique_ptr<std::thread> spin_thread_;\n  std::unique_ptr<std::thread> init_thread_;\n  rclcpp::Logger robot_system_logger = rclcpp::get_logger(\"robot_system\");\n\nprivate:\n  /**\n   * @brief Spins the ROS executor\n   *\n   */\n  void spin();\n  void clean();\n\n  /**\n   * @brief Initialize the device container\n   *\n   */\n  void initDeviceContainer();\n};\n}  // namespace canopen_ros2_control\n\n#endif\n"
  },
  {
    "path": "canopen_ros2_control/include/canopen_ros2_control/visibility_control.h",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROL__VISIBILITY_CONTROL_H_\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_EXPORT __attribute__((dllexport))\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_EXPORT __declspec(dllexport)\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_ROS2_CONTROL__VISIBILITY_BUILDING_DLL\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC CANOPEN_ROS2_CONTROL__VISIBILITY_EXPORT\n#else\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC CANOPEN_ROS2_CONTROL__VISIBILITY_IMPORT\n#endif\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC_TYPE CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_LOCAL\n#else\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_LOCAL\n#endif\n#define CANOPEN_ROS2_CONTROL__VISIBILITY_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_ROS2_CONTROL__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_ros2_control/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_ros2_control</name>\n  <version>0.3.2</version>\n  <description>ros2_control wrapper for ros2_canopen functionalities</description>\n  <maintainer email=\"lovro.ivanov@gmail.com\">Lovro Ivanov</maintainer>\n  <maintainer email=\"denis.stogl@stoglrobotics.de\">Denis Stogl</maintainer>\n\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <depend>canopen_402_driver</depend>\n  <depend>canopen_core</depend>\n  <depend>canopen_proxy_driver</depend>\n  <depend>hardware_interface</depend>\n  <depend>pluginlib</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_components</depend>\n  <depend>rclcpp_lifecycle</depend>\n\n  <test_depend>ros2_control_test_assets</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_ros2_control/src/canopen_system.cpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n//----------------------------------------------------------------------\n/*!\\file\n *\n * \\author  Lovro Ivanov lovro.ivanov@gmail.com\n * \\date    2022-06-29\n *\n */\n//----------------------------------------------------------------------\n\n#include \"canopen_ros2_control/canopen_system.hpp\"\n\n#include <limits>\n#include <vector>\n#include \"hardware_interface/types/hardware_interface_type_values.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n\nnamespace\n{\nauto const kLogger = rclcpp::get_logger(\"CanopenSystem\");\n}\n\nnamespace canopen_ros2_control\n{\n\nCanopenSystem::CanopenSystem() {}\n\nvoid CanopenSystem::clean()\n{\n  executor_->cancel();\n  printf(\"Joining...\");\n  spin_thread_->join();\n  printf(\"Joined!\");\n\n  device_container_.reset();\n  executor_.reset();\n\n  if (init_thread_->joinable())\n  {\n    init_thread_->join();\n  }\n  init_thread_.reset();\n\n  executor_.reset();\n  spin_thread_.reset();\n}\n\nCanopenSystem::~CanopenSystem() { clean(); }\n\nhardware_interface::CallbackReturn CanopenSystem::on_init(\n  const hardware_interface::HardwareComponentInterfaceParams & params)\n{\n  if (hardware_interface::SystemInterface::on_init(params) != CallbackReturn::SUCCESS)\n  {\n    return CallbackReturn::ERROR;\n  }\n\n  RCLCPP_INFO(kLogger, \"bus_config: '%s'\", info_.hardware_parameters[\"bus_config\"].c_str());\n  RCLCPP_INFO(kLogger, \"master_config: '%s'\", info_.hardware_parameters[\"master_config\"].c_str());\n  RCLCPP_INFO(\n    kLogger, \"can_interface_name: '%s'\", info_.hardware_parameters[\"can_interface_name\"].c_str());\n  RCLCPP_INFO(kLogger, \"master_bin: '%s'\", info_.hardware_parameters[\"master_bin\"].c_str());\n\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::CallbackReturn CanopenSystem::on_configure(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  executor_ = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  device_container_ = std::make_shared<ros2_canopen::DeviceContainer>(executor_);\n  executor_->add_node(device_container_);\n\n  // threads\n  spin_thread_ = std::make_unique<std::thread>(&CanopenSystem::spin, this);\n  init_thread_ = std::make_unique<std::thread>(&CanopenSystem::initDeviceContainer, this);\n\n  // actually wait for init phase to end\n  if (init_thread_->joinable())\n  {\n    init_thread_->join();\n  }\n  else\n  {\n    RCLCPP_ERROR(kLogger, \"Could not join init thread!\");\n    return CallbackReturn::ERROR;\n  }\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::CallbackReturn CanopenSystem::on_cleanup(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  clean();\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::CallbackReturn CanopenSystem::on_shutdown(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  clean();\n  return CallbackReturn::SUCCESS;\n}\n\nvoid CanopenSystem::spin()\n{\n  executor_->spin();\n  executor_->remove_node(device_container_);\n\n  RCLCPP_INFO(kLogger, \"Exiting spin thread...\");\n}\n\nvoid CanopenSystem::initDeviceContainer()\n{\n  std::string tmp_master_bin = (info_.hardware_parameters[\"master_bin\"] == \"\\\"\\\"\")\n                                 ? \"\"\n                                 : info_.hardware_parameters[\"master_bin\"];\n\n  device_container_->init(\n    info_.hardware_parameters[\"can_interface_name\"], info_.hardware_parameters[\"master_config\"],\n    info_.hardware_parameters[\"bus_config\"], tmp_master_bin);\n  RCLCPP_INFO(kLogger, \"Number of registered drivers: '%zu'\", device_container_->count_drivers());\n  for (const auto & [node_id, driver] : device_container_->get_registered_drivers())\n  {\n    auto proxy_driver = std::static_pointer_cast<ros2_canopen::ProxyDriver>(driver);\n    // initialize canopen data it not existing\n    if (canopen_data_.find(node_id) == canopen_data_.end())\n    {\n      canopen_data_[node_id] = CanopenNodeData();\n    }\n\n    auto nmt_state_cb = [&](canopen::NmtState nmt_state, uint8_t id)\n    { canopen_data_[id].nmt_state.set_state(nmt_state); };\n    // register callback\n    proxy_driver->register_nmt_state_cb(nmt_state_cb);\n\n    auto rpdo_cb = [&](ros2_canopen::COData data, uint8_t id)\n    { canopen_data_[id].set_rpdo_data(data); };\n    // register callback\n    proxy_driver->register_rpdo_cb(rpdo_cb);\n\n    auto emcy_cb = [&](ros2_canopen::COEmcy data, uint8_t id)\n    { canopen_data_[id].emcy_data.set_emcy(data); };\n    // register callback\n    proxy_driver->register_emcy_cb(emcy_cb);\n\n    RCLCPP_INFO(\n      kLogger, \"\\nRegistered driver:\\n    name: '%s'\\n    node_id: '0x%X'\",  //\n      driver->get_node_base_interface()->get_name(), node_id);\n  }\n\n  RCLCPP_INFO(device_container_->get_logger(), \"Initialisation successful.\");\n}\n\nstd::vector<hardware_interface::StateInterface> CanopenSystem::export_state_interfaces()\n{\n  std::vector<hardware_interface::StateInterface> state_interfaces;\n  for (uint i = 0; i < info_.joints.size(); i++)\n  {\n    if (info_.joints[i].parameters.find(\"node_id\") == info_.joints[i].parameters.end())\n    {\n      // skip adding canopen interfaces\n      continue;\n    }\n    const uint8_t node_id = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"node_id\"]));\n    //      RCLCPP_INFO(kLogger, \"node id on export state interface for joint: '%s' is '%s'\",\n    //      info_.joints[i].name.c_str(), info_.joints[i].parameters[\"node_id\"].c_str());\n\n    // rpdo index\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"rpdo/index\", &canopen_data_[node_id].rpdo_data.index));\n\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"rpdo/subindex\", &canopen_data_[node_id].rpdo_data.subindex));\n\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"rpdo/data\", &canopen_data_[node_id].rpdo_data.data));\n\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"nmt/state\", &canopen_data_[node_id].nmt_state.state));\n\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/error_code\", &canopen_data_[node_id].emcy_data.error_code));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/error_register\",\n      &canopen_data_[node_id].emcy_data.error_register));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/manufacturer_error_code1\",\n      &canopen_data_[node_id].emcy_data.manufacturer_error_code1));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/manufacturer_error_code2\",\n      &canopen_data_[node_id].emcy_data.manufacturer_error_code2));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/manufacturer_error_code3\",\n      &canopen_data_[node_id].emcy_data.manufacturer_error_code3));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/manufacturer_error_code4\",\n      &canopen_data_[node_id].emcy_data.manufacturer_error_code4));\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, \"emcy/manufacturer_error_code5\",\n      &canopen_data_[node_id].emcy_data.manufacturer_error_code5));\n  }\n\n  return state_interfaces;\n}\n\nstd::vector<hardware_interface::CommandInterface> CanopenSystem::export_command_interfaces()\n{\n  std::vector<hardware_interface::CommandInterface> command_interfaces;\n  for (uint i = 0; i < info_.joints.size(); i++)\n  {\n    if (info_.joints[i].parameters.find(\"node_id\") == info_.joints[i].parameters.end())\n    {\n      // skip adding canopen interfaces\n      continue;\n    }\n\n    const uint8_t node_id = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"node_id\"]));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"tpdo/index\", &canopen_data_[node_id].tpdo_data.index));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"tpdo/subindex\", &canopen_data_[node_id].tpdo_data.subindex));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"tpdo/data\", &canopen_data_[node_id].tpdo_data.data));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"tpdo/ons\", &canopen_data_[node_id].tpdo_data.one_shot));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"nmt/reset\", &canopen_data_[node_id].nmt_state.reset_ons));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"nmt/reset_fbk\", &canopen_data_[node_id].nmt_state.reset_fbk));\n\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"nmt/start\", &canopen_data_[node_id].nmt_state.start_ons));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"nmt/start_fbk\", &canopen_data_[node_id].nmt_state.start_fbk));\n  }\n\n  return command_interfaces;\n}\n\nhardware_interface::CallbackReturn CanopenSystem::on_activate(\n  const rclcpp_lifecycle::State & /*previous_state*/)\n{\n  // TODO(anyone): prepare the robot to receive commands\n\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::CallbackReturn CanopenSystem::on_deactivate(\n  const rclcpp_lifecycle::State & /*previous_state*/)\n{\n  // TODO(anyone): prepare the robot to stop receiving commands\n\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::return_type CanopenSystem::read(\n  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)\n{\n  // TODO(anyone): read robot states\n\n  // nmt state is set via Ros2ControlNmtState::set_state within nmt_state_cb\n\n  // rpdo has a queue of messages, we read the latest one\n\n  for (const auto & [node_id, canopen_data] : canopen_data_)\n  {\n    if (canopen_data.emcy_data.error_code != 0)\n    {\n      RCLCPP_ERROR(\n        kLogger,\n        \"NodeID: 0x%X; Error code: %X; Error register: %X; Manufacturer error code: [%X, %X, %X, \"\n        \"%X, %X];\",\n        node_id, canopen_data.emcy_data.original_emcy.eec, canopen_data.emcy_data.original_emcy.er,\n        canopen_data.emcy_data.original_emcy.msef[0], canopen_data.emcy_data.original_emcy.msef[1],\n        canopen_data.emcy_data.original_emcy.msef[2], canopen_data.emcy_data.original_emcy.msef[3],\n        canopen_data.emcy_data.original_emcy.msef[4]);\n    }\n  }\n\n  return hardware_interface::return_type::OK;\n}\n\nhardware_interface::return_type CanopenSystem::write(\n  const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)\n{\n  // TODO(anyone): write robot's commands'\n  auto drivers = device_container_->get_registered_drivers();\n\n  for (auto it = canopen_data_.begin(); it != canopen_data_.end(); ++it)\n  {\n    if (drivers.find(it->first) == drivers.end())\n    {\n      // this is expected for NodeID 0x00 - why do we have it at all?\n      RCLCPP_DEBUG(kLogger, \"Driver for NodeID 0x%X not found. Skipping...\", it->first);\n      continue;\n    }\n    auto proxy_driver = std::static_pointer_cast<ros2_canopen::ProxyDriver>(drivers[it->first]);\n\n    // reset node nmt\n    if (it->second.nmt_state.reset_command())\n    {\n      it->second.nmt_state.reset_fbk = static_cast<double>(proxy_driver->reset_node_nmt_command());\n    }\n\n    // start nmt\n    if (it->second.nmt_state.start_command())\n    {\n      it->second.nmt_state.start_fbk = static_cast<double>(proxy_driver->start_node_nmt_command());\n    }\n\n    // tpdo data one shot mechanism\n    if (it->second.tpdo_data.write_command())\n    {\n      it->second.tpdo_data.prepare_data();\n      try\n      {\n        proxy_driver->tpdo_transmit(it->second.tpdo_data.original_data);\n      }\n      catch (const std::exception & e)\n      {\n        std::cerr << e.what() << '\\n';\n      }\n    }\n  }\n\n  return hardware_interface::return_type::OK;\n}\n\n}  // namespace canopen_ros2_control\n\n#include \"pluginlib/class_list_macros.hpp\"\n\nPLUGINLIB_EXPORT_CLASS(canopen_ros2_control::CanopenSystem, hardware_interface::SystemInterface)\n"
  },
  {
    "path": "canopen_ros2_control/src/cia402_system.cpp",
    "content": "// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n//----------------------------------------------------------------------\n/*!\\file\n *\n * \\author  Lovro Ivanov lovro.ivanov@gmail.com\n * \\date    2022-08-01\n *\n */\n//----------------------------------------------------------------------\n\n#include \"canopen_ros2_control/cia402_system.hpp\"\n#include <hardware_interface/types/hardware_interface_type_values.hpp>\n\nnamespace\n{\nauto const kLogger = rclcpp::get_logger(\"Cia402System\");\n}\n\nnamespace canopen_ros2_control\n{\n\nCia402System::Cia402System() : CanopenSystem() {}\n\nhardware_interface::CallbackReturn Cia402System::on_init(\n  const hardware_interface::HardwareComponentInterfaceParams & params)\n{\n  auto ret_val = CanopenSystem::on_init(params);\n  if (ret_val != hardware_interface::CallbackReturn::SUCCESS)\n  {\n    return ret_val;\n  }\n\n  return CallbackReturn::SUCCESS;\n}\n\nvoid Cia402System::initDeviceContainer()\n{\n  std::string tmp_master_bin = (info_.hardware_parameters[\"master_bin\"] == \"\\\"\\\"\")\n                                 ? \"\"\n                                 : info_.hardware_parameters[\"master_bin\"];\n\n  device_container_->init(\n    info_.hardware_parameters[\"can_interface_name\"], info_.hardware_parameters[\"master_config\"],\n    info_.hardware_parameters[\"bus_config\"], tmp_master_bin);\n  auto drivers = device_container_->get_registered_drivers();\n  RCLCPP_INFO(kLogger, \"Number of registered drivers: '%lu'\", device_container_->count_drivers());\n  for (auto it = drivers.begin(); it != drivers.end(); it++)\n  {\n    auto driver = std::static_pointer_cast<ros2_canopen::Cia402Driver>(it->second);\n\n    auto nmt_state_cb = [&](canopen::NmtState nmt_state, uint8_t id)\n    { canopen_data_[id].nmt_state.set_state(nmt_state); };\n    // register callback\n    driver->register_nmt_state_cb(nmt_state_cb);\n\n    auto rpdo_cb = [&](ros2_canopen::COData data, uint8_t id)\n    { canopen_data_[id].rpdo_data.set_data(data); };\n    // register callback\n    driver->register_rpdo_cb(rpdo_cb);\n\n    RCLCPP_INFO(\n      kLogger, \"\\nRegistered driver:\\n    name: '%s'\\n    node_id: '0x%X'\",\n      it->second->get_node_base_interface()->get_name(), it->first);\n  }\n\n  RCLCPP_INFO(device_container_->get_logger(), \"Initialisation successful.\");\n}\n\nhardware_interface::CallbackReturn Cia402System::on_configure(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  executor_ = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();\n  device_container_ = std::make_shared<ros2_canopen::DeviceContainer>(executor_);\n  executor_->add_node(device_container_);\n\n  // threads\n  spin_thread_ = std::make_unique<std::thread>(&Cia402System::spin, this);\n  init_thread_ = std::make_unique<std::thread>(&Cia402System::initDeviceContainer, this);\n\n  // actually wait for init phase to end\n  if (init_thread_->joinable())\n  {\n    init_thread_->join();\n\n    // TODO(livanov93): see how to handle configure once LifecycleCia402Driver is introduced\n    /*\n    auto drivers = device_container_->get_registered_drivers();\n    for (auto it = drivers.begin(); it != drivers.end(); it++) {\n        auto d = std::static_pointer_cast<ros2_canopen::LifecycleCia402Driver>(it->second);\n        d->configure();\n    }\n    */\n  }\n  else\n  {\n    RCLCPP_ERROR(kLogger, \"Could not join init thread!\");\n    return CallbackReturn::ERROR;\n  }\n  return CallbackReturn::SUCCESS;\n}\n\nstd::vector<hardware_interface::StateInterface> Cia402System::export_state_interfaces()\n{\n  std::vector<hardware_interface::StateInterface> state_interfaces;\n\n  // underlying base class export first\n  state_interfaces = CanopenSystem::export_state_interfaces();\n\n  for (uint i = 0; i < info_.joints.size(); i++)\n  {\n    if (info_.joints[i].parameters.find(\"node_id\") == info_.joints[i].parameters.end())\n    {\n      // skip adding motor canopen interfaces\n      continue;\n    }\n    const uint8_t node_id = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"node_id\"]));\n\n    // Get channel parameter (defaults to 0 for backward compatibility)\n    uint8_t channel = 0;\n    if (info_.joints[i].parameters.find(\"channel\") != info_.joints[i].parameters.end())\n    {\n      channel = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"channel\"]));\n    }\n\n    auto motor_key = getMotorKey(node_id, channel);\n\n    // actual position\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_POSITION,\n      &motor_data_[motor_key].actual_position));\n    // actual speed\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_VELOCITY,\n      &motor_data_[motor_key].actual_speed));\n    // actual effort\n    state_interfaces.emplace_back(hardware_interface::StateInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_EFFORT,\n      &motor_data_[motor_key].actual_effort));\n  }\n\n  return state_interfaces;\n}\n\nstd::vector<hardware_interface::CommandInterface> Cia402System::export_command_interfaces()\n{\n  std::vector<hardware_interface::CommandInterface> command_interfaces;\n\n  // underlying base class export first\n  command_interfaces = CanopenSystem::export_command_interfaces();\n\n  for (uint i = 0; i < info_.joints.size(); i++)\n  {\n    if (info_.joints[i].parameters.find(\"node_id\") == info_.joints[i].parameters.end())\n    {\n      // skip adding canopen interfaces\n      continue;\n    }\n\n    const uint8_t node_id = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"node_id\"]));\n\n    // Get channel parameter (defaults to 0 for backward compatibility)\n    uint8_t channel = 0;\n    if (info_.joints[i].parameters.find(\"channel\") != info_.joints[i].parameters.end())\n    {\n      channel = static_cast<uint8_t>(std::stoi(info_.joints[i].parameters[\"channel\"]));\n    }\n\n    auto motor_key = getMotorKey(node_id, channel);\n\n    // target\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_POSITION,\n      &motor_data_[motor_key].target.position_value));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_VELOCITY,\n      &motor_data_[motor_key].target.velocity_value));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, hardware_interface::HW_IF_EFFORT,\n      &motor_data_[motor_key].target.torque_value));\n    // init\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"init_cmd\", &motor_data_[motor_key].init.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"init_fbk\", &motor_data_[motor_key].init.resp));\n\n    // halt\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"halt_cmd\", &motor_data_[motor_key].halt.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"halt_fbk\", &motor_data_[motor_key].halt.resp));\n\n    // recover\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"recover_cmd\", &motor_data_[motor_key].recover.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"recover_fbk\", &motor_data_[motor_key].recover.resp));\n\n    // set position mode\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"position_mode_cmd\", &motor_data_[motor_key].position_mode.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"position_mode_fbk\", &motor_data_[motor_key].position_mode.resp));\n\n    // set velocity mode\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"velocity_mode_cmd\", &motor_data_[motor_key].velocity_mode.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"velocity_mode_fbk\", &motor_data_[motor_key].velocity_mode.resp));\n\n    // set cyclic velocity mode\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"cyclic_velocity_mode_cmd\",\n      &motor_data_[motor_key].cyclic_velocity_mode.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"cyclic_velocity_mode_fbk\",\n      &motor_data_[motor_key].cyclic_velocity_mode.resp));\n    // set cyclic position mode\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"cyclic_position_mode_cmd\",\n      &motor_data_[motor_key].cyclic_position_mode.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"cyclic_position_mode_fbk\",\n      &motor_data_[motor_key].cyclic_position_mode.resp));\n    // set interpolated position mode\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"interpolated_position_mode_cmd\",\n      &motor_data_[motor_key].interpolated_position_mode.ons_cmd));\n    command_interfaces.emplace_back(hardware_interface::CommandInterface(\n      info_.joints[i].name, \"interpolated_position_mode_fbk\",\n      &motor_data_[motor_key].interpolated_position_mode.resp));\n  }\n\n  return command_interfaces;\n}\n\nhardware_interface::CallbackReturn Cia402System::on_activate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  return CanopenSystem::on_activate(previous_state);\n}\n\nhardware_interface::CallbackReturn Cia402System::on_deactivate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  return CanopenSystem::on_deactivate(previous_state);\n}\n\nhardware_interface::return_type Cia402System::read(\n  const rclcpp::Time & time, const rclcpp::Duration & period)\n{\n  // TODO(anyone): read robot states\n\n  auto ret_val = CanopenSystem::read(time, period);\n\n  auto drivers = device_container_->get_registered_drivers();\n\n  // Iterate through all motor data entries which now include channel info\n  for (auto it = motor_data_.begin(); it != motor_data_.end(); ++it)\n  {\n    const auto & node_id = it->first.first;\n    const auto & channel = it->first.second;\n\n    auto motion_controller_driver =\n      std::static_pointer_cast<ros2_canopen::Cia402Driver>(drivers[node_id]);\n    // get position\n    motor_data_[it->first].actual_position = motion_controller_driver->get_position(channel);\n    // get speed\n    motor_data_[it->first].actual_speed = motion_controller_driver->get_speed(channel);\n    // get effort\n    motor_data_[it->first].actual_effort = motion_controller_driver->get_effort(channel);\n  }\n\n  return ret_val;\n}\n\nhardware_interface::return_type Cia402System::write(\n  const rclcpp::Time & time, const rclcpp::Duration & period)\n{\n  auto drivers = device_container_->get_registered_drivers();\n\n  // Process NMT commands per node (not per channel)\n  for (auto it = canopen_data_.begin(); it != canopen_data_.end(); ++it)\n  {\n    auto motion_controller_driver =\n      std::static_pointer_cast<ros2_canopen::Cia402Driver>(drivers[it->first]);\n    // do same as in proxy system first - handle nmt, tpdo, rpdo\n    // reset node nmt\n    if (it->second.nmt_state.reset_command())\n    {\n      motion_controller_driver->reset_node_nmt_command();\n    }\n\n    // start nmt\n    if (it->second.nmt_state.start_command())\n    {\n      motion_controller_driver->start_node_nmt_command();\n    }\n\n    // tpdo data one shot mechanism\n    if (it->second.tpdo_data.write_command())\n    {\n      it->second.tpdo_data.prepare_data();\n      motion_controller_driver->tpdo_transmit(it->second.tpdo_data.original_data);\n    }\n  }\n\n  // Process motor commands per channel\n  for (auto it = motor_data_.begin(); it != motor_data_.end(); ++it)\n  {\n    const auto & node_id = it->first.first;\n    const auto & channel = it->first.second;\n\n    auto motion_controller_driver =\n      std::static_pointer_cast<ros2_canopen::Cia402Driver>(drivers[node_id]);\n\n    // initialisation\n    handleInit(node_id, channel, motion_controller_driver);\n\n    // halt\n    handleHalt(node_id, channel, motion_controller_driver);\n\n    // recover\n    handleRecover(node_id, channel, motion_controller_driver);\n\n    // mode switching\n    switchModes(node_id, channel, motion_controller_driver);\n\n    const uint16_t & mode = motion_controller_driver->get_mode(channel);\n\n    switch (mode)\n    {\n      case MotorBase::No_Mode:\n        break;\n      case MotorBase::Profiled_Position:\n      case MotorBase::Cyclic_Synchronous_Position:\n      case MotorBase::Interpolated_Position:\n        motion_controller_driver->set_target(motor_data_[it->first].target.position_value, channel);\n        break;\n      case MotorBase::Profiled_Velocity:\n      case MotorBase::Cyclic_Synchronous_Velocity:\n        motion_controller_driver->set_target(motor_data_[it->first].target.velocity_value, channel);\n        break;\n      case MotorBase::Profiled_Torque:\n        motion_controller_driver->set_target(motor_data_[it->first].target.torque_value, channel);\n        break;\n      default:\n        RCLCPP_INFO(kLogger, \"Mode %u not supported\", mode);\n    }\n  }\n\n  return hardware_interface::return_type::OK;\n}\n\nvoid Cia402System::switchModes(\n  uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver)\n{\n  auto motor_key = getMotorKey(id, channel);\n\n  if (motor_data_[motor_key].position_mode.is_commanded())\n  {\n    motor_data_[motor_key].position_mode.set_response(\n      driver->set_operation_mode(MotorBase::Profiled_Position, channel));\n  }\n\n  if (motor_data_[motor_key].cyclic_position_mode.is_commanded())\n  {\n    motor_data_[motor_key].cyclic_position_mode.set_response(\n      driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Position, channel));\n  }\n\n  if (motor_data_[motor_key].velocity_mode.is_commanded())\n  {\n    motor_data_[motor_key].velocity_mode.set_response(\n      driver->set_operation_mode(MotorBase::Profiled_Velocity, channel));\n  }\n\n  if (motor_data_[motor_key].cyclic_velocity_mode.is_commanded())\n  {\n    motor_data_[motor_key].cyclic_velocity_mode.set_response(\n      driver->set_operation_mode(MotorBase::Cyclic_Synchronous_Velocity, channel));\n  }\n\n  if (motor_data_[motor_key].torque_mode.is_commanded())\n  {\n    motor_data_[motor_key].torque_mode.set_response(\n      driver->set_operation_mode(MotorBase::Profiled_Torque, channel));\n  }\n\n  if (motor_data_[motor_key].interpolated_position_mode.is_commanded())\n  {\n    motor_data_[motor_key].interpolated_position_mode.set_response(\n      driver->set_operation_mode(MotorBase::Interpolated_Position, channel));\n  }\n}\n\nvoid Cia402System::handleInit(\n  uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver)\n{\n  auto motor_key = getMotorKey(id, channel);\n  if (motor_data_[motor_key].init.is_commanded())\n  {\n    motor_data_[motor_key].init.set_response(driver->init_motor(channel));\n  }\n}\n\nvoid Cia402System::handleRecover(\n  uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver)\n{\n  auto motor_key = getMotorKey(id, channel);\n  if (motor_data_[motor_key].recover.is_commanded())\n  {\n    motor_data_[motor_key].recover.set_response(driver->recover_motor(channel));\n  }\n}\n\nvoid Cia402System::handleHalt(\n  uint id, uint channel, const std::shared_ptr<ros2_canopen::Cia402Driver> & driver)\n{\n  auto motor_key = getMotorKey(id, channel);\n  if (motor_data_[motor_key].halt.is_commanded())\n  {\n    motor_data_[motor_key].halt.set_response(driver->halt_motor(channel));\n  }\n}\n\n}  // namespace canopen_ros2_control\n\n#include \"pluginlib/class_list_macros.hpp\"\n\nPLUGINLIB_EXPORT_CLASS(canopen_ros2_control::Cia402System, hardware_interface::SystemInterface)\n"
  },
  {
    "path": "canopen_ros2_control/src/robot_system.cpp",
    "content": "// Copyright (c) 2023, Fraunhofer IPA\n// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include \"canopen_ros2_control/robot_system.hpp\"\n#include <hardware_interface/types/hardware_interface_type_values.hpp>\n\nusing namespace canopen_ros2_control;\n\n// auto robot_system_logger = rclcpp::get_logger(\"robot_system_interface\");\n\nhardware_interface::CallbackReturn RobotSystem::on_init(\n  const hardware_interface::HardwareComponentInterfaceParams & params)\n{\n  if (hardware_interface::SystemInterface::on_init(params) != CallbackReturn::SUCCESS)\n  {\n    return CallbackReturn::ERROR;\n  }\n  robot_system_logger = rclcpp::get_logger(info_.name + \"_interface\");\n  RCLCPP_INFO(robot_system_logger, \"Registering hardware interface '%s'\", info_.name.c_str());\n\n  // Check bus config is specified.\n  if (info_.hardware_parameters.find(\"bus_config\") == info_.hardware_parameters.end())\n  {\n    RCLCPP_ERROR(\n      robot_system_logger, \"No bus_config parameter provided for '%s' hardware interface.\",\n      info_.name.c_str());\n    return CallbackReturn::ERROR;\n  }\n  bus_config_ = info_.hardware_parameters[\"bus_config\"];\n  RCLCPP_INFO(\n    robot_system_logger, \"'%s' has bus config: '%s'\", info_.name.c_str(), bus_config_.c_str());\n\n  // Check master config is specified.\n  if (info_.hardware_parameters.find(\"master_config\") == info_.hardware_parameters.end())\n  {\n    RCLCPP_ERROR(\n      robot_system_logger, \"No master_config parameter provided for '%s' hardware interface.\",\n      info_.name.c_str());\n    return CallbackReturn::ERROR;\n  }\n  master_config_ = info_.hardware_parameters[\"master_config\"];\n  RCLCPP_INFO(\n    robot_system_logger, \"'%s' has master config: '%s'\", info_.name.c_str(),\n    master_config_.c_str());\n\n  // Check master bin is specified.\n  if (info_.hardware_parameters.find(\"master_bin\") != info_.hardware_parameters.end())\n  {\n    master_bin_ = info_.hardware_parameters[\"master_bin\"];\n    if (master_bin_ == \"\\\"\\\"\")\n    {\n      master_bin_ = \"\";\n    }\n    RCLCPP_INFO(\n      robot_system_logger, \"'%s' has master bin: '%s'\", info_.name.c_str(), master_bin_.c_str());\n  }\n  else\n  {\n    master_bin_ = \"\";\n  }\n\n  // Check can_interface_name is specified.\n  if (info_.hardware_parameters.find(\"can_interface_name\") == info_.hardware_parameters.end())\n  {\n    RCLCPP_ERROR(\n      robot_system_logger, \"No can_interface_name parameter provided for '%s' hardware interface.\",\n      info_.name.c_str());\n    return CallbackReturn::ERROR;\n  }\n  can_interface_ = info_.hardware_parameters[\"can_interface_name\"];\n  RCLCPP_INFO(\n    robot_system_logger, \"'%s' has can interface: '%s'\", info_.name.c_str(),\n    can_interface_.c_str());\n\n  ros2_canopen::ConfigurationManager config(bus_config_);\n  config.init_config();\n\n  // Load joint data\n  for (auto joint : info_.joints)\n  {\n    auto driver_type =\n      config.get_entry<std::string>(joint.parameters[\"device_name\"], \"driver\").value();\n    if (driver_type == \"ros2_canopen::Cia402Driver\")\n    {\n      auto data = Cia402Data();\n      if (data.init_data(joint, config.dump_device(joint.parameters[\"device_name\"])))\n      {\n        robot_motor_data_.push_back(data);\n      }\n    }\n    else\n    {\n      RCLCPP_ERROR(\n        robot_system_logger, \"Driver type '%s' not supported for joint '%s'\", driver_type.c_str(),\n        joint.name.c_str());\n      return CallbackReturn::ERROR;\n    }\n  }\n  return CallbackReturn::SUCCESS;\n}\n\nhardware_interface::CallbackReturn RobotSystem::on_configure(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  executor_ =\n    std::make_shared<rclcpp::executors::MultiThreadedExecutor>(rclcpp::ExecutorOptions(), 2);\n  device_container_ = std::make_shared<ros2_canopen::DeviceContainer>(executor_);\n  executor_->add_node(device_container_);\n\n  spin_thread_ = std::make_unique<std::thread>(&RobotSystem::spin, this);\n  init_thread_ = std::make_unique<std::thread>(&RobotSystem::initDeviceContainer, this);\n\n  if (init_thread_->joinable())\n  {\n    init_thread_->join();\n  }\n  else\n  {\n    RCLCPP_ERROR(robot_system_logger, \"Could not join init thread!\");\n    return CallbackReturn::ERROR;\n  }\n  return CallbackReturn::SUCCESS;\n}\nhardware_interface::CallbackReturn RobotSystem::on_activate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  for (auto & data : robot_motor_data_)\n  {\n    if (!data.driver->init_motor())\n    {\n      RCLCPP_ERROR(robot_system_logger, \"Failed to activate '%s'\", data.joint_name.c_str());\n      return CallbackReturn::FAILURE;\n    }\n  }\n  return CallbackReturn::SUCCESS;\n}\nhardware_interface::CallbackReturn RobotSystem::on_deactivate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  for (auto & data : robot_motor_data_)\n  {\n    if (!data.driver->halt_motor())\n    {\n      RCLCPP_ERROR(robot_system_logger, \"Failed to deactivate '%s'\", data.joint_name.c_str());\n      return CallbackReturn::FAILURE;\n    }\n  }\n  return CallbackReturn::SUCCESS;\n}\nhardware_interface::CallbackReturn RobotSystem::on_cleanup(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  clean();\n  return CallbackReturn::SUCCESS;\n}\nhardware_interface::CallbackReturn RobotSystem::on_shutdown(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  clean();\n  return CallbackReturn::SUCCESS;\n}\n\nstd::vector<hardware_interface::StateInterface> RobotSystem::export_state_interfaces()\n{\n  std::vector<hardware_interface::StateInterface> state_interfaces;\n\n  // Iterate over joints in xacro\n  for (canopen_ros2_control::Cia402Data & data : robot_motor_data_)\n  {\n    data.export_state_interface(state_interfaces);\n  }\n  return state_interfaces;\n}\n\nstd::vector<hardware_interface::CommandInterface> RobotSystem::export_command_interfaces()\n{\n  std::vector<hardware_interface::CommandInterface> command_interfaces;\n\n  // Iterate over joints in xacro\n  for (canopen_ros2_control::Cia402Data & data : robot_motor_data_)\n  {\n    data.export_command_interface(command_interfaces);\n  }\n  return command_interfaces;\n}\n\nhardware_interface::return_type RobotSystem::read(\n  const rclcpp::Time & time, const rclcpp::Duration & period)\n{\n  // Iterate over joints\n  for (canopen_ros2_control::Cia402Data & data : robot_motor_data_)\n  {\n    data.read_state();\n  }\n\n  return hardware_interface::return_type::OK;\n}\n\nhardware_interface::return_type RobotSystem::write(\n  const rclcpp::Time & time, const rclcpp::Duration & period)\n{\n  for (canopen_ros2_control::Cia402Data & data : robot_motor_data_)\n  {\n    data.write_target();\n  }\n  return hardware_interface::return_type::OK;\n}\n\nhardware_interface::return_type RobotSystem::perform_command_mode_switch(\n  const std::vector<std::string> & start_interfaces,\n  const std::vector<std::string> & stop_interfaces)\n{\n  // register interfaces to start per device\n  for (auto interface : start_interfaces)\n  {\n    auto it = std::find_if(\n      robot_motor_data_.begin(), robot_motor_data_.end(),\n      [interface](Cia402Data & data)\n      {\n        return std::find(data.interfaces.begin(), data.interfaces.end(), interface) !=\n               data.interfaces.end();\n      });\n    if (it != robot_motor_data_.end())\n    {\n      it->interfaces_to_start.push_back(\n        hardware_interface::CommandInterface(interface).get_interface_name());\n    }\n  }\n\n  // register interfaces to stop per device\n  for (auto interface : stop_interfaces)\n  {\n    auto it = std::find_if(\n      robot_motor_data_.begin(), robot_motor_data_.end(),\n      [interface](Cia402Data & data)\n      {\n        return std::find(data.interfaces.begin(), data.interfaces.end(), interface) !=\n               data.interfaces.end();\n      });\n    if (it != robot_motor_data_.end())\n    {\n      it->interfaces_to_stop.push_back(\n        hardware_interface::CommandInterface(interface).get_interface_name());\n    }\n  }\n\n  // perform switching\n  for (auto & data : robot_motor_data_)\n  {\n    if (!data.perform_switch())\n    {\n      return hardware_interface::return_type::ERROR;\n    }\n  }\n  return hardware_interface::return_type::OK;\n}\n\nvoid RobotSystem::initDeviceContainer()\n{\n  // Init device container\n  device_container_->init(\n    this->can_interface_, this->master_config_, this->bus_config_, this->master_bin_);\n\n  // Get all registered drivers.\n  auto drivers = device_container_->get_registered_drivers();\n\n  // Iterate over all drivers and allocate them to the correct joint.\n  for (auto & data : robot_motor_data_)\n  {\n    // Find correct driver for joint via node id.\n    auto driver = std::find_if(\n      drivers.begin(), drivers.end(),\n      [&data](const std::pair<int, std::shared_ptr<ros2_canopen::CanopenDriverInterface>> & driver)\n      { return driver.first == data.node_id; });\n\n    if (driver == drivers.end())\n    {\n      RCLCPP_ERROR(\n        device_container_->get_logger(), \"Could not find driver for joint '%s' with node id '%d'\",\n        data.joint_name.c_str(), data.node_id);\n      continue;\n    }\n\n    // Allocate driver to joint.\n    if (\n      device_container_->get_driver_type(driver->first).compare(\"ros2_canopen::Cia402Driver\") == 0)\n    {\n      data.driver = std::static_pointer_cast<ros2_canopen::Cia402Driver>(driver->second);\n    }\n  }\n  RCLCPP_INFO(device_container_->get_logger(), \"Initialisation successful.\");\n}\n\nvoid RobotSystem::spin()\n{\n  executor_->spin();\n  executor_->remove_node(device_container_);\n  RCLCPP_INFO(device_container_->get_logger(), \"Stopped spinning RobotSystem ROS2 executor\");\n}\n\nvoid RobotSystem::clean()\n{\n  printf(\"Cancel exectutor...\");\n  executor_->cancel();\n  printf(\"Join spin thread...\");\n  spin_thread_->join();\n\n  printf(\"Reset variables...\");\n  device_container_.reset();\n  executor_.reset();\n\n  init_thread_->join();\n  init_thread_.reset();\n\n  executor_.reset();\n  spin_thread_.reset();\n  robot_motor_data_.clear();\n}\n\n#include \"pluginlib/class_list_macros.hpp\"\n\nPLUGINLIB_EXPORT_CLASS(canopen_ros2_control::RobotSystem, hardware_interface::SystemInterface)\n"
  },
  {
    "path": "canopen_ros2_control/test/test_canopen_system.cpp",
    "content": "// Copyright (c) 2022, StoglRobotics\n// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n//----------------------------------------------------------------------\n/*!\\file\n *\n * \\author  Lovro Ivanov lovro.ivanov@gmail.com\n * \\date    2022-06-29\n *\n */\n//----------------------------------------------------------------------\n\n#include <gmock/gmock.h>\n\n#include <string>\n\n#include \"hardware_interface/resource_manager.hpp\"\n#include \"ros2_control_test_assets/components_urdfs.hpp\"\n#include \"ros2_control_test_assets/descriptions.hpp\"\n\nclass TestCanopenSystem : public ::testing::Test\n{\nprotected:\n  void SetUp() override\n  {\n    // TODO(anyone): Extend this description to your robot\n    canopen_system_2dof_ =\n      R\"(\n        <ros2_control name=\"CanopenSystem2dof\" type=\"system\">\n          <hardware>\n            <plugin>canopen_ros2_control/CanopenSystem</plugin>\n          </hardware>\n          <joint name=\"joint1\">\n            <command_interface name=\"position\"/>\n            <state_interface name=\"position\"/>\n            <param name=\"initial_position\">1.57</param>\n          </joint>\n          <joint name=\"joint2\">\n            <command_interface name=\"position\"/>\n            <state_interface name=\"position\"/>\n            <param name=\"initial_position\">0.7854</param>\n          </joint>\n        </ros2_control>\n    )\";\n  }\n\n  std::string canopen_system_2dof_;\n};\n\nTEST_F(TestCanopenSystem, load_canopen_system_2dof)\n{\n  auto urdf = ros2_control_test_assets::urdf_head + canopen_system_2dof_ +\n              ros2_control_test_assets::urdf_tail;\n  ASSERT_NO_THROW(hardware_interface::ResourceManager rm(urdf));\n}\n"
  },
  {
    "path": "canopen_ros2_controllers/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_ros2_controllers\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* Merge pull request `#400 <https://github.com/ros-industrial/ros2_canopen/issues/400>`_ from ros-industrial/fix/proxy_controller\n  Update controllers for ROS Rolling API changes and fix fake slave type handling\n* Enhance command interface error handling and feedback reporting in CanopenProxyController\n* Contributors: Vishnuprasad Prachandabhanu\n\n0.2.9 (2024-04-16)\n------------------\n\n\n0.3.1 (2025-06-23)\n------------------\n* Add boot timeout and retry\n* Fix command interfaces value missmatch.\n* Fix realtime-tools include header file\n* Include upstream changes from 'master'.\n* Contributors: Gerry Salinas, Marco A. Gutierrez, Vishnuprasad Prachandabhanu\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Contributors: ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n* Remove controller tests (`#249 <https://github.com/ros-industrial/ros2_canopen/issues/249>`_)\n* Disable controller tests for now (`#231 <https://github.com/ros-industrial/ros2_canopen/issues/231>`_)\n  * Disable controller tests for now\n  * Update iron.yml\n  * Fix ci\n* Contributors: Christoph Hellmann Santos, Vishnuprasad Prachandabhanu\n\n0.2.7 (2023-06-30)\n------------------\n* Correct Proxy controller after changes and update tests.\n* Contributors: Dr. Denis, Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Fix QoS build warning canopen_ros2_controllers\n* Don't use ros2_control_test_assets since not needed anymore. Add load tests for all controllers.\n* Contributors: Christoph Hellmann Santos, Denis Štogl, Vishnuprasad Prachandabhanu\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, Dr.-Ing. Denis Štogl, Lovro, livanov93\n"
  },
  {
    "path": "canopen_ros2_controllers/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_ros2_controllers)\n\nfind_package(ament_cmake REQUIRED)\nfind_package(canopen_402_driver REQUIRED)\nfind_package(canopen_interfaces REQUIRED)\nfind_package(canopen_proxy_driver REQUIRED)\nfind_package(controller_interface REQUIRED)\nfind_package(controller_manager REQUIRED)\nfind_package(hardware_interface REQUIRED)\nfind_package(pluginlib REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(rclcpp_lifecycle REQUIRED)\nfind_package(realtime_tools REQUIRED)\nfind_package(std_msgs REQUIRED)\nfind_package(std_srvs REQUIRED)\n\nadd_library(\n  ${PROJECT_NAME}\n  SHARED\n  src/canopen_proxy_controller.cpp\n  src/cia402_device_controller.cpp\n)\n\ntarget_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)\ntarget_include_directories(${PROJECT_NAME} PUBLIC\n  $<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>\n  $<INSTALL_INTERFACE:include/${PROJECT_NAME}>\n)\ntarget_link_libraries(${PROJECT_NAME} PUBLIC\n  ${canopen_interfaces_TARGETS}\n  ${std_msgs_TARGETS}\n  ${std_srvs_TARGETS}\n  canopen_402_driver::cia402_driver\n  canopen_402_driver::lely_motion_controller_bridge\n  canopen_402_driver::lifecycle_cia402_driver\n  canopen_402_driver::node_canopen_cia402_driver\n  canopen_proxy_driver::lifecycle_proxy_driver\n  canopen_proxy_driver::node_canopen_proxy_driver\n  canopen_proxy_driver::proxy_driver\n  controller_interface::controller_interface\n  controller_manager::controller_manager\n  controller_manager::controller_manager_parameters\n  hardware_interface::hardware_interface\n  hardware_interface::mock_components\n  pluginlib::pluginlib\n  rclcpp::rclcpp\n  rclcpp_lifecycle::rclcpp_lifecycle\n  realtime_tools::realtime_tools\n  realtime_tools::thread_priority\n)\n\ntarget_compile_definitions(${PROJECT_NAME} PRIVATE \"CANOPEN_PROXY_CONTROLLER_BUILDING_DLL\" \"_USE_MATH_DEFINES\")\npluginlib_export_plugin_description_file(controller_interface canopen_ros2_controllers.xml)\n\ninstall(\n  TARGETS\n    ${PROJECT_NAME}\n  RUNTIME DESTINATION bin\n  ARCHIVE DESTINATION lib\n  LIBRARY DESTINATION lib\n  INCLUDES DESTINATION include\n)\n\ninstall(\n  DIRECTORY include/\n  DESTINATION include\n)\n\nif(FALSE)\n  # find_package(ament_cmake_gmock REQUIRED)\n\n#   ament_add_gmock(test_load_canopen_proxy_controller test/test_load_canopen_proxy_controller.cpp)\n#   target_include_directories(test_load_canopen_proxy_controller PRIVATE include)\n#   target_link_libraries(test_load_canopen_proxy_controller ...\n\n#   ament_add_gmock(test_load_cia402_device_controller test/test_load_cia402_device_controller.cpp)\n#   target_include_directories(test_load_cia402_device_controller PRIVATE include)\n#   target_link_libraries(test_load_cia402_device_controller ...\n\n#   ament_add_gmock(test_load_cia402_robot_controller test/test_load_cia402_robot_controller.cpp)\n#   target_include_directories(test_load_cia402_robot_controller PRIVATE include)\n#   target_link_libraries(test_load_cia402_robot_controller ...\n\n#   ament_add_gmock(test_canopen_proxy_controller test/test_canopen_proxy_controller.cpp)\n#   target_include_directories(test_canopen_proxy_controller PRIVATE include)\n#   target_link_libraries(test_canopen_proxy_controller ...\nendif()\n\nament_export_include_directories(\n  include\n)\nament_export_libraries(\n  ${PROJECT_NAME}\n)\nament_export_dependencies(\n  canopen_402_driver\n  canopen_interfaces\n  canopen_proxy_driver\n  controller_interface\n  controller_manager\n  hardware_interface\n  pluginlib\n  rclcpp\n  rclcpp_lifecycle\n  realtime_tools\n  std_msgs\n  std_srvs\n)\n\nament_package()\n"
  },
  {
    "path": "canopen_ros2_controllers/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_ros2_controllers/canopen_ros2_controllers.xml",
    "content": "<library path=\"canopen_ros2_controllers\">\n  <class name=\"canopen_ros2_controllers/CanopenProxyController\"\n         type=\"canopen_ros2_controllers::CanopenProxyController\" base_class_type=\"controller_interface::ControllerInterface\">\n  <description>\n    Generic controller for Canopen devices providing service interfaces through ros2_control stack to the can devices.\n  </description>\n  </class>\n  <class name=\"canopen_ros2_controllers/Cia402DeviceController\"\n         type=\"canopen_ros2_controllers::Cia402DeviceController\" base_class_type=\"controller_interface::ControllerInterface\">\n    <description>\n      Generic controller for Canopen 402 devices providing service interfaces through ros2_control stack to the can devices.\n    </description>\n  </class>\n  <class name=\"canopen_ros2_controllers/Cia402RobotController\"\n         type=\"cia402_robot_controller::Cia402RobotController\" base_class_type=\"controller_interface::ControllerInterface\">\n    <description>\n      Generic controller for Canopen 402 devices providing service interfaces through ros2_control stack to the can devices.\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "canopen_ros2_controllers/include/canopen_ros2_controllers/canopen_proxy_controller.hpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROLLERS__CANOPEN_PROXY_CONTROLLER_HPP_\n#define CANOPEN_ROS2_CONTROLLERS__CANOPEN_PROXY_CONTROLLER_HPP_\n\n#include <memory>\n#include <string>\n#include <vector>\n\n#include \"canopen_interfaces/msg/co_data.hpp\"\n#include \"canopen_interfaces/srv/co_read.hpp\"\n#include \"canopen_interfaces/srv/co_write.hpp\"\n#include \"canopen_ros2_controllers/visibility_control.h\"\n#include \"controller_interface/controller_interface.hpp\"\n#include \"rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp\"\n#include \"rclcpp_lifecycle/state.hpp\"\n#include \"realtime_tools/realtime_buffer.hpp\"\n#include \"realtime_tools/realtime_publisher.hpp\"\n#include \"std_msgs/msg/string.hpp\"\n#include \"std_srvs/srv/set_bool.hpp\"\n#include \"std_srvs/srv/trigger.hpp\"\n\nnamespace\n{\nenum CommandInterfaces\n{\n  TPDO_INDEX,\n  TPDO_SUBINDEX,\n  TPDO_DATA,\n  TPDO_ONS,\n  NMT_RESET,\n  NMT_RESET_FBK,\n  NMT_START,\n  NMT_START_FBK,\n  LAST_COMMAND_AUX,\n};\n\nenum StateInterfaces\n{\n  RPDO_INDEX,\n  RPDO_SUBINDEX,\n  RPDO_DATA,\n  NMT_STATE,\n  LAST_STATE_AUX,\n};\n\n}  // namespace\n\nnamespace canopen_ros2_controllers\n{\n\nclass CanopenProxyController : public controller_interface::ControllerInterface\n{\npublic:\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  CanopenProxyController();\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_init() override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::InterfaceConfiguration command_interface_configuration() const override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::InterfaceConfiguration state_interface_configuration() const override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_activate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & previous_state) override;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::return_type update(\n    const rclcpp::Time & time, const rclcpp::Duration & period) override;\n\n  using ControllerCommandMsg = canopen_interfaces::msg::COData;\n  using ControllerStartResetSrvType = std_srvs::srv::Trigger;\n  using ControllerSDOReadSrvType = canopen_interfaces::srv::CORead;\n  using ControllerSDOWriteSrvType = canopen_interfaces::srv::COWrite;\n  using ControllerNMTStateMsg = std_msgs::msg::String;\n\nprotected:\n  std::string joint_name_;\n\n  // Command subscribers\n  // TPDO subscription\n  rclcpp::Subscription<ControllerCommandMsg>::SharedPtr tpdo_subscriber_ = nullptr;\n  realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerCommandMsg>> input_cmd_;\n\n  // NMT state publisher\n  using ControllerNmtStateRTPublisher = realtime_tools::RealtimePublisher<ControllerNMTStateMsg>;\n  rclcpp::Publisher<ControllerNMTStateMsg>::SharedPtr nmt_state_pub_;\n  std::unique_ptr<ControllerNmtStateRTPublisher> nmt_state_rt_publisher_;\n  std::string nmt_state_actual_ = \"BOOTUP\";\n\n  // RPDO publisher\n  using ControllerRPDOPRTublisher = realtime_tools::RealtimePublisher<ControllerCommandMsg>;\n  rclcpp::Publisher<ControllerCommandMsg>::SharedPtr rpdo_pub_;\n  std::unique_ptr<ControllerRPDOPRTublisher> rpdo_rt_publisher_;\n\n  // NMT reset service\n  rclcpp::Service<ControllerStartResetSrvType>::SharedPtr nmt_state_reset_service_;\n  // NMT start service\n  rclcpp::Service<ControllerStartResetSrvType>::SharedPtr nmt_state_start_service_;\n  // SDO read service\n  rclcpp::Service<ControllerSDOReadSrvType>::SharedPtr sdo_read_service_;\n  // SDO write service\n  rclcpp::Service<ControllerSDOWriteSrvType>::SharedPtr sdo_write_service_;\n};\n\n}  // namespace canopen_ros2_controllers\n\n#endif  // CANOPEN_ROS2_CONTROLLERS__CANOPEN_PROXY_CONTROLLER_HPP_\n"
  },
  {
    "path": "canopen_ros2_controllers/include/canopen_ros2_controllers/cia402_device_controller.hpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROLLERS__CANOPEN_CIA402_CONTROLLER_HPP_\n#define CANOPEN_ROS2_CONTROLLERS__CANOPEN_CIA402_CONTROLLER_HPP_\n\n#include \"canopen_interfaces/srv/co_target_double.hpp\"\n#include \"canopen_ros2_controllers/canopen_proxy_controller.hpp\"\n\nstatic constexpr int kLoopPeriodMS = 100;\nstatic constexpr double kCommandValue = 1.0;\n\nnamespace\n{\nenum Cia402CommandInterfaces\n{\n  INIT_CMD = CommandInterfaces::LAST_COMMAND_AUX,\n  INIT_FBK,\n  HALT_CMD,\n  HALT_FBK,\n  RECOVER_CMD,\n  RECOVER_FBK,\n  POSITION_MODE_CMD,\n  POSITION_MODE_FBK,\n  VELOCITY_MODE_CMD,\n  VELOCITY_MODE_FBK,\n  CYCLIC_VELOCITY_MODE_CMD,\n  CYCLIC_VELOCITY_MODE_FBK,\n  CYCLIC_POSITION_MODE_CMD,\n  CYCLIC_POSITION_MODE_FBK,\n  INTERPOLATED_POSITION_MODE_CMD,\n  INTERPOLATED_POSITION_MODE_FBK,\n};\n\nenum Cia402StateInterfaces\n{\n  FIRST_STATE = StateInterfaces::LAST_STATE_AUX,\n};\n\n}  // namespace\n\nnamespace canopen_ros2_controllers\n{\n\nclass Cia402DeviceController : public canopen_ros2_controllers::CanopenProxyController\n{\npublic:\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  Cia402DeviceController();\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_init();\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::InterfaceConfiguration command_interface_configuration() const;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::InterfaceConfiguration state_interface_configuration() const;\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::CallbackReturn on_deactivate(\n    const rclcpp_lifecycle::State & previous_state);\n\n  CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n  controller_interface::return_type update(\n    const rclcpp::Time & time, const rclcpp::Duration & period);\n\nprotected:\n  inline rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr createTriggerSrv(\n    const std::string & service, Cia402CommandInterfaces cmd, Cia402CommandInterfaces fbk)\n  {\n    // define service profile Qos\n    auto service_profile = rclcpp::QoS(1);\n    service_profile.keep_all();\n\n    rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr srv =\n      get_node()->create_service<std_srvs::srv::Trigger>(\n        service,\n        [&, cmd, fbk](\n          const std_srvs::srv::Trigger::Request::SharedPtr request,\n          std_srvs::srv::Trigger::Response::SharedPtr response)\n        {\n          response->success = false;\n          const bool sent = command_interfaces_[cmd].set_value(kCommandValue);\n          if (!sent)\n          {\n            RCLCPP_WARN(\n              this->get_node()->get_logger(), \"Failed to send command interface: %d request\", cmd);\n          }\n\n          while (rclcpp::ok())\n          {\n            const auto fbk_value = command_interfaces_[fbk].get_optional<double>();\n            if (fbk_value && !std::isnan(*fbk_value))\n            {\n              response->success = static_cast<bool>(*fbk_value);\n              break;\n            }\n            std::this_thread::sleep_for(std::chrono::milliseconds(kLoopPeriodMS));\n          }\n\n          // reset to nan\n          if (!command_interfaces_[fbk].set_value(std::numeric_limits<double>::quiet_NaN()))\n          {\n            RCLCPP_WARN(\n              this->get_node()->get_logger(), \"Failed to reset feedback for service %d\", fbk);\n          }\n          if (!command_interfaces_[cmd].set_value(std::numeric_limits<double>::quiet_NaN()))\n          {\n            RCLCPP_WARN(\n              this->get_node()->get_logger(), \"Failed to reset command for service %d\", cmd);\n          }\n        },\n        service_profile);\n\n    return srv;\n  }\n\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_init_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_halt_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_recover_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_position_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_torque_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_velocity_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_velocity_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_cyclic_position_service_;\n  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr handle_set_mode_interpolated_position_service_;\n  rclcpp::Service<canopen_interfaces::srv::COTargetDouble>::SharedPtr handle_set_target_service_;\n};\n\n}  // namespace canopen_ros2_controllers\n\n#endif  // CANOPEN_ROS2_CONTROLLERS__CANOPEN_CIA402_CONTROLLER_HPP_\n"
  },
  {
    "path": "canopen_ros2_controllers/include/canopen_ros2_controllers/visibility_control.h",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROLLERS__VISIBILITY_CONTROL_H_\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_CONTROL_H_\n\n// This logic was borrowed (then namespaced) from the examples on the gcc wiki:\n//     https://gcc.gnu.org/wiki/Visibility\n\n#if defined _WIN32 || defined __CYGWIN__\n#ifdef __GNUC__\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_EXPORT __attribute__((dllexport))\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_IMPORT __attribute__((dllimport))\n#else\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_EXPORT __declspec(dllexport)\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_IMPORT __declspec(dllimport)\n#endif\n#ifdef CANOPEN_ROS2_CONTROLLERS__VISIBILITY_BUILDING_DLL\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC CANOPEN_ROS2_CONTROLLERS__VISIBILITY_EXPORT\n#else\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC CANOPEN_ROS2_CONTROLLERS__VISIBILITY_IMPORT\n#endif\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC_TYPE CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_LOCAL\n#else\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_EXPORT __attribute__((visibility(\"default\")))\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_IMPORT\n#if __GNUC__ >= 4\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC __attribute__((visibility(\"default\")))\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_LOCAL __attribute__((visibility(\"hidden\")))\n#else\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_LOCAL\n#endif\n#define CANOPEN_ROS2_CONTROLLERS__VISIBILITY_PUBLIC_TYPE\n#endif\n\n#endif  // CANOPEN_ROS2_CONTROLLERS__VISIBILITY_CONTROL_H_\n"
  },
  {
    "path": "canopen_ros2_controllers/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_ros2_controllers</name>\n  <version>0.3.2</version>\n  <description>ros2_control controllers for ros2_canopen functionalities</description>\n  <maintainer email=\"denis@stoglrobotics.de\">Denis Stogl</maintainer>\n  <maintainer email=\"lovro.ivanov@gmail.com\">Lovro Ivanov</maintainer>\n\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <depend>canopen_402_driver</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>canopen_proxy_driver</depend>\n  <depend>controller_interface</depend>\n  <depend>controller_manager</depend>\n  <depend>hardware_interface</depend>\n  <depend>pluginlib</depend>\n  <depend>rclcpp</depend>\n  <depend>rclcpp_lifecycle</depend>\n  <depend>realtime_tools</depend>\n  <depend>std_msgs</depend>\n  <depend>std_srvs</depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_ros2_controllers/src/canopen_proxy_controller.cpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include \"canopen_ros2_controllers/canopen_proxy_controller.hpp\"\n\n#include <chrono>\n#include <limits>\n#include <memory>\n#include <optional>\n#include <string>\n#include <thread>\n#include <vector>\n\n#include \"controller_interface/helpers.hpp\"\n\n#include \"canopen_proxy_driver/node_interfaces/node_canopen_proxy_driver.hpp\"\n\nstatic constexpr int kLoopPeriodMS = 100;\nstatic constexpr double kCommandValue = 1.0;\n\nnamespace\n{  // utility\n\nusing ControllerCommandMsg = canopen_ros2_controllers::CanopenProxyController::ControllerCommandMsg;\n\n// called from RT control loop\nbool propagate_controller_command_msg(std::shared_ptr<ControllerCommandMsg> & msg)\n{\n  // TODO (livanov93): add better logic to decide if a message\n  //  should be propagated to the bus\n  // check if it is 8 = uint8_t or 16 = uint16_t or 32 = uint32_t\n  return true;\n}\n}  // namespace\n\nnamespace canopen_ros2_controllers\n{\nCanopenProxyController::CanopenProxyController() : controller_interface::ControllerInterface() {}\n\ncontroller_interface::CallbackReturn CanopenProxyController::on_init()\n{\n  try\n  {\n    // use auto declare\n    auto_declare<std::string>(\"joint\", joint_name_);\n  }\n  catch (const std::exception & e)\n  {\n    fprintf(stderr, \"Exception thrown during init stage with message: %s \\n\", e.what());\n    return controller_interface::CallbackReturn::ERROR;\n  }\n\n  return controller_interface::CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::CallbackReturn CanopenProxyController::on_configure(\n  const rclcpp_lifecycle::State & /*previous_state*/)\n{\n  auto error_if_empty = [&](const auto & parameter, const char * parameter_name)\n  {\n    if (parameter.empty())\n    {\n      RCLCPP_ERROR(get_node()->get_logger(), \"'%s' parameter was empty\", parameter_name);\n      return true;\n    }\n    return false;\n  };\n\n  auto get_string_array_param_and_error_if_empty =\n    [&](std::vector<std::string> & parameter, const char * parameter_name)\n  {\n    parameter = get_node()->get_parameter(parameter_name).as_string_array();\n    return error_if_empty(parameter, parameter_name);\n  };\n\n  auto get_string_param_and_error_if_empty =\n    [&](std::string & parameter, const char * parameter_name)\n  {\n    parameter = get_node()->get_parameter(parameter_name).as_string();\n    return error_if_empty(parameter, parameter_name);\n  };\n\n  if (get_string_param_and_error_if_empty(joint_name_, \"joint\"))\n  {\n    return controller_interface::CallbackReturn::ERROR;\n  }\n\n  // Command Subscriber and callbacks\n  auto callback_cmd = [&](const std::shared_ptr<ControllerCommandMsg> msg) -> void\n  { input_cmd_.writeFromNonRT(msg); };\n  tpdo_subscriber_ = get_node()->create_subscription<ControllerCommandMsg>(\n    \"~/tpdo\", rclcpp::SystemDefaultsQoS(), callback_cmd);\n\n  input_cmd_.writeFromNonRT(nullptr);\n\n  try\n  {\n    // nmt state publisher\n    nmt_state_pub_ = get_node()->create_publisher<ControllerNMTStateMsg>(\n      \"~/nmt_state\", rclcpp::SystemDefaultsQoS());\n    nmt_state_rt_publisher_ = std::make_unique<ControllerNmtStateRTPublisher>(nmt_state_pub_);\n\n    // rpdo publisher\n    rpdo_pub_ =\n      get_node()->create_publisher<ControllerCommandMsg>(\"~/rpdo\", rclcpp::SystemDefaultsQoS());\n    rpdo_rt_publisher_ = std::make_unique<ControllerRPDOPRTublisher>(rpdo_pub_);\n  }\n  catch (const std::exception & e)\n  {\n    fprintf(\n      stderr, \"Exception thrown during publisher creation at configure stage with message : %s \\n\",\n      e.what());\n    return controller_interface::CallbackReturn::ERROR;\n  }\n\n  if (nmt_state_rt_publisher_)\n  {\n    ControllerNMTStateMsg msg;\n    msg.data = std::string();\n    bool published = nmt_state_rt_publisher_->try_publish(msg);\n    if (!published)\n    {\n      RCLCPP_WARN(\n        get_node()->get_logger(), \"Could not publish initial NMT state message on controller '%s'\",\n        joint_name_.c_str());\n    }\n  }\n\n  if (rpdo_rt_publisher_)\n  {\n    ControllerCommandMsg msg;\n    msg.index = 0u;\n    msg.subindex = 0u;\n    msg.data = 0u;\n    bool published = rpdo_rt_publisher_->try_publish(msg);\n    if (!published)\n    {\n      RCLCPP_WARN(\n        get_node()->get_logger(), \"Could not publish initial RPDO message on controller '%s'\",\n        joint_name_.c_str());\n    }\n  }\n\n  // init services\n\n  // NMT reset\n  auto on_nmt_state_reset = [&](\n                              const std_srvs::srv::Trigger::Request::SharedPtr request,\n                              std_srvs::srv::Trigger::Response::SharedPtr response)\n  {\n    response->success = false;\n    const auto logger = get_node()->get_logger();\n    if (!command_interfaces_[CommandInterfaces::NMT_RESET].set_value(kCommandValue))\n    {\n      RCLCPP_WARN(logger, \"Failed to set NMT reset command\");\n    }\n\n    while (rclcpp::ok())\n    {\n      const auto reset_cmd_value =\n        command_interfaces_[CommandInterfaces::NMT_RESET].get_optional<double>();\n      if (reset_cmd_value && std::isnan(*reset_cmd_value))\n      {\n        break;\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(kLoopPeriodMS));\n    }\n\n    // report success\n    const auto reset_feedback =\n      command_interfaces_[CommandInterfaces::NMT_RESET_FBK].get_optional<double>();\n    if (reset_feedback && !std::isnan(*reset_feedback))\n    {\n      response->success = static_cast<bool>(*reset_feedback);\n    }\n    // reset to nan\n    if (!command_interfaces_[CommandInterfaces::NMT_RESET_FBK].set_value(\n          std::numeric_limits<double>::quiet_NaN()))\n    {\n      RCLCPP_WARN(logger, \"Failed to reset NMT reset feedback interface\");\n    }\n  };\n\n  auto service_profile = rclcpp::QoS(1);\n  service_profile.keep_all();\n  nmt_state_reset_service_ = get_node()->create_service<ControllerStartResetSrvType>(\n    \"~/nmt_reset_node\", on_nmt_state_reset, service_profile);\n\n  // NMT start\n  auto on_nmt_state_start = [&](\n                              const std_srvs::srv::Trigger::Request::SharedPtr request,\n                              std_srvs::srv::Trigger::Response::SharedPtr response)\n  {\n    response->success = false;\n    const auto logger = get_node()->get_logger();\n    if (!command_interfaces_[CommandInterfaces::NMT_START].set_value(kCommandValue))\n    {\n      RCLCPP_WARN(logger, \"Failed to send command for NMT start service\");\n    }\n\n    while (rclcpp::ok())\n    {\n      const auto reset_fbk =\n        command_interfaces_[CommandInterfaces::NMT_START_FBK].get_optional<double>();\n      if (reset_fbk && !std::isnan(*reset_fbk))\n      {\n        break;\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(kLoopPeriodMS));\n    }\n\n    // report success\n    const auto start_feedback =\n      command_interfaces_[CommandInterfaces::NMT_START_FBK].get_optional<double>();\n    if (start_feedback && !std::isnan(*start_feedback))\n    {\n      response->success = static_cast<bool>(*start_feedback);\n    }\n    // reset to nan\n    if (!command_interfaces_[CommandInterfaces::NMT_START_FBK].set_value(\n          std::numeric_limits<double>::quiet_NaN()))\n    {\n      RCLCPP_WARN(logger, \"Failed to reset NMT start feedback interface\");\n    }\n  };\n  nmt_state_start_service_ = get_node()->create_service<ControllerStartResetSrvType>(\n    \"~/nmt_start_node\", on_nmt_state_start, service_profile);\n\n  // SDO read\n  auto on_sdo_read = [&](\n                       const canopen_interfaces::srv::CORead::Request::SharedPtr request,\n                       canopen_interfaces::srv::CORead::Response::SharedPtr response) {};\n\n  sdo_read_service_ = get_node()->create_service<ControllerSDOReadSrvType>(\n    \"~/sdo_read\", on_sdo_read, service_profile);\n\n  // SDO write\n  auto on_sdo_write = [&](\n                        const canopen_interfaces::srv::COWrite::Request::SharedPtr request,\n                        canopen_interfaces::srv::COWrite::Response::SharedPtr response) {\n\n  };\n\n  sdo_write_service_ = get_node()->create_service<ControllerSDOWriteSrvType>(\n    \"~/sdo_write\", on_sdo_write, service_profile);\n\n  RCLCPP_INFO(get_node()->get_logger(), \"configure successful\");\n  return controller_interface::CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::InterfaceConfiguration\nCanopenProxyController::command_interface_configuration() const\n{\n  controller_interface::InterfaceConfiguration command_interfaces_config;\n  command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;\n\n  command_interfaces_config.names.reserve(8);\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"tpdo/index\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"tpdo/subindex\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"tpdo/data\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"tpdo/ons\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"nmt/reset\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"nmt/reset_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"nmt/start\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"nmt/start_fbk\");\n\n  return command_interfaces_config;\n}\n\ncontroller_interface::InterfaceConfiguration CanopenProxyController::state_interface_configuration()\n  const\n{\n  controller_interface::InterfaceConfiguration state_interfaces_config;\n  state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;\n\n  state_interfaces_config.names.reserve(4);\n  state_interfaces_config.names.push_back(joint_name_ + \"/\" + \"rpdo/index\");\n  state_interfaces_config.names.push_back(joint_name_ + \"/\" + \"rpdo/subindex\");\n  state_interfaces_config.names.push_back(joint_name_ + \"/\" + \"rpdo/data\");\n  state_interfaces_config.names.push_back(joint_name_ + \"/\" + \"nmt/state\");\n\n  return state_interfaces_config;\n}\n\ncontroller_interface::CallbackReturn CanopenProxyController::on_activate(\n  const rclcpp_lifecycle::State & /*previous_state*/)\n{\n  // Set default value in command\n  if (input_cmd_.readFromRT())\n  {\n    *(input_cmd_.readFromRT()) = nullptr;\n  }\n\n  return controller_interface::CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::CallbackReturn CanopenProxyController::on_deactivate(\n  const rclcpp_lifecycle::State & /*previous_state*/)\n{\n  // instead of a loop\n  auto warn_on_failure = [&](bool ok, const char * name)\n  {\n    if (!ok)\n    {\n      RCLCPP_WARN_THROTTLE(\n        get_node()->get_logger(), *get_node()->get_clock(), 5000,\n        \"Failed to reset command interface %s during deactivate\", name);\n    }\n  };\n  for (size_t i = 0; i < command_interfaces_.size(); ++i)\n  {\n    warn_on_failure(\n      command_interfaces_[i].set_value(std::numeric_limits<double>::quiet_NaN()),\n      command_interfaces_[i].get_name().c_str());\n  }\n  return controller_interface::CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::return_type CanopenProxyController::update(\n  const rclcpp::Time & time, const rclcpp::Duration & /*period*/)\n{\n  // nmt state is retrieved in SystemInterface via cb and is exposed here\n  if (nmt_state_rt_publisher_)\n  {\n    auto message = std_msgs::msg::String();\n    const auto nmt_state_optional =\n      state_interfaces_[StateInterfaces::NMT_STATE].get_optional<double>();\n\n    if (nmt_state_optional)\n    {\n      auto nmt_state = static_cast<int>(*nmt_state_optional);\n\n      switch (static_cast<canopen::NmtState>(nmt_state))\n      {\n        case canopen::NmtState::BOOTUP:\n          message.data = \"BOOTUP\";\n          break;\n        case canopen::NmtState::PREOP:\n          message.data = \"PREOP\";\n          break;\n        case canopen::NmtState::RESET_COMM:\n          message.data = \"RESET_COMM\";\n          break;\n        case canopen::NmtState::RESET_NODE:\n          message.data = \"RESET_NODE\";\n          break;\n        case canopen::NmtState::START:\n          message.data = \"START\";\n          break;\n        case canopen::NmtState::STOP:\n          message.data = \"STOP\";\n          break;\n        case canopen::NmtState::TOGGLE:\n          message.data = \"TOGGLE\";\n          break;\n        default:\n          RCLCPP_ERROR(get_node()->get_logger(), \"Unknown NMT State.\");\n          message.data = \"ERROR\";\n          break;\n      }\n\n      if (nmt_state_actual_ != message.data)\n      {\n        // publish on change only\n        nmt_state_actual_ = std::string(message.data);\n        const bool published = nmt_state_rt_publisher_->try_publish(message);\n        if (!published)\n        {\n          RCLCPP_WARN_THROTTLE(\n            get_node()->get_logger(), *get_node()->get_clock(), 5000,\n            \"Failed to publish NMT state\");\n        }\n      }\n    }\n  }\n\n  // exposing rpdo data via real-time publisher\n  if (rpdo_rt_publisher_)\n  {\n    const auto rpdo_index = state_interfaces_[StateInterfaces::RPDO_INDEX].get_optional<double>();\n    const auto rpdo_subindex =\n      state_interfaces_[StateInterfaces::RPDO_SUBINDEX].get_optional<double>();\n    const auto rpdo_data = state_interfaces_[StateInterfaces::RPDO_DATA].get_optional<double>();\n\n    if (rpdo_index && rpdo_subindex && rpdo_data)\n    {\n      ControllerCommandMsg msg;\n      msg.index = static_cast<uint16_t>(*rpdo_index);\n      msg.subindex = static_cast<uint8_t>(*rpdo_subindex);\n      msg.data = static_cast<uint32_t>(*rpdo_data);\n\n      const bool published = rpdo_rt_publisher_->try_publish(msg);\n      if (!published)\n      {\n        RCLCPP_WARN_THROTTLE(\n          get_node()->get_logger(), *get_node()->get_clock(), 5000,\n          \"Failed to publish RPDO message\");\n      }\n    }\n  }\n\n  // tpdo data is the main controller data retrieved via subscription\n  auto current_cmd = input_cmd_.readFromRT();\n  if (!current_cmd || !(*current_cmd))\n  {\n    return controller_interface::return_type::OK;\n  }\n  else if (propagate_controller_command_msg(*current_cmd))\n  {\n    auto warn_on_failure = [&](bool ok, const char * name)\n    {\n      if (!ok)\n      {\n        RCLCPP_WARN_THROTTLE(\n          get_node()->get_logger(), *get_node()->get_clock(), 5000, \"Failed to set TPDO command %s\",\n          name);\n      }\n    };\n\n    warn_on_failure(\n      command_interfaces_[CommandInterfaces::TPDO_INDEX].set_value(\n        static_cast<double>((*current_cmd)->index)),\n      \"index\");\n    warn_on_failure(\n      command_interfaces_[CommandInterfaces::TPDO_SUBINDEX].set_value(\n        static_cast<double>((*current_cmd)->subindex)),\n      \"subindex\");\n    warn_on_failure(\n      command_interfaces_[CommandInterfaces::TPDO_DATA].set_value(\n        static_cast<double>((*current_cmd)->data)),\n      \"data\");\n    // tpdo data one shot mechanism\n    warn_on_failure(\n      command_interfaces_[CommandInterfaces::TPDO_ONS].set_value(kCommandValue), \"ons\");\n\n    *(input_cmd_.readFromRT()) = nullptr;\n  }\n\n  return controller_interface::return_type::OK;\n}\n\n}  // namespace canopen_ros2_controllers\n\n#include \"pluginlib/class_list_macros.hpp\"\n\nPLUGINLIB_EXPORT_CLASS(\n  canopen_ros2_controllers::CanopenProxyController, controller_interface::ControllerInterface)\n"
  },
  {
    "path": "canopen_ros2_controllers/src/cia402_device_controller.cpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include \"canopen_ros2_controllers/cia402_device_controller.hpp\"\n\n#include <limits>\n#include <memory>\n#include <string>\n#include <vector>\n\n#include \"canopen_402_driver/node_interfaces/node_canopen_402_driver.hpp\"\n#include \"controller_interface/helpers.hpp\"\n\nnamespace\n{  // utility\n\nusing ControllerCommandMsg = canopen_ros2_controllers::CanopenProxyController::ControllerCommandMsg;\n\n// called from RT control loop\nvoid reset_controller_command_msg(\n  std::shared_ptr<ControllerCommandMsg> & msg, const std::string & joint_name)\n{\n}\n\n}  // namespace\n\nnamespace canopen_ros2_controllers\n{\nCia402DeviceController::Cia402DeviceController()\n: canopen_ros2_controllers::CanopenProxyController()\n{\n}\n\ncontroller_interface::CallbackReturn Cia402DeviceController::on_init()\n{\n  if (CanopenProxyController::on_init() != controller_interface::CallbackReturn::SUCCESS)\n    return controller_interface::CallbackReturn::ERROR;\n\n  handle_init_service_ = createTriggerSrv(\n    \"~/init\", Cia402CommandInterfaces::INIT_CMD, Cia402CommandInterfaces::INIT_FBK);\n\n  handle_halt_service_ = createTriggerSrv(\n    \"~/halt\", Cia402CommandInterfaces::HALT_CMD, Cia402CommandInterfaces::HALT_FBK);\n\n  handle_recover_service_ = createTriggerSrv(\n    \"~/recover\", Cia402CommandInterfaces::RECOVER_CMD, Cia402CommandInterfaces::RECOVER_FBK);\n\n  handle_set_mode_position_service_ = createTriggerSrv(\n    \"~/position_mode\", Cia402CommandInterfaces::POSITION_MODE_CMD,\n    Cia402CommandInterfaces::POSITION_MODE_FBK);\n\n  handle_set_mode_velocity_service_ = createTriggerSrv(\n    \"~/velocity_mode\", Cia402CommandInterfaces::VELOCITY_MODE_CMD,\n    Cia402CommandInterfaces::VELOCITY_MODE_FBK);\n\n  handle_set_mode_cyclic_velocity_service_ = createTriggerSrv(\n    \"~/cyclic_velocity_mode\", Cia402CommandInterfaces::CYCLIC_VELOCITY_MODE_CMD,\n    Cia402CommandInterfaces::CYCLIC_VELOCITY_MODE_FBK);\n\n  handle_set_mode_cyclic_position_service_ = createTriggerSrv(\n    \"~/cyclic_position_mode\", Cia402CommandInterfaces::CYCLIC_POSITION_MODE_CMD,\n    Cia402CommandInterfaces::CYCLIC_POSITION_MODE_FBK);\n\n  handle_set_mode_interpolated_position_service_ = createTriggerSrv(\n    \"~/interpolated_position_mode\", Cia402CommandInterfaces::INTERPOLATED_POSITION_MODE_CMD,\n    Cia402CommandInterfaces::INTERPOLATED_POSITION_MODE_FBK);\n\n  /*\n  handle_set_mode_torque_service_ = createTriggerSrv(\"~/torque_mode\",\n                                                             Cia402CommandInterfaces::,\n                                                             Cia402CommandInterfaces::);\n\n  handle_set_target_service_ = createTriggerSrv(\"~/target\", Cia402CommandInterfaces::,\n                                               Cia402CommandInterfaces::);\n  */\n\n  return controller_interface::CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::InterfaceConfiguration\nCia402DeviceController::command_interface_configuration() const\n{\n  auto command_interfaces_config = CanopenProxyController::command_interface_configuration();\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"init_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"init_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"halt_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"halt_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"recover_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"recover_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"position_mode_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"position_mode_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"velocity_mode_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"velocity_mode_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"cyclic_velocity_mode_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"cyclic_velocity_mode_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"cyclic_position_mode_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"cyclic_position_mode_fbk\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"interpolated_position_mode_cmd\");\n  command_interfaces_config.names.push_back(joint_name_ + \"/\" + \"interpolated_position_mode_fbk\");\n  return command_interfaces_config;\n}\n\ncontroller_interface::InterfaceConfiguration Cia402DeviceController::state_interface_configuration()\n  const\n{\n  auto state_interfaces_config = CanopenProxyController::state_interface_configuration();\n  // no new state interfaces for this controller - additional state interfaces in cia402_system\n  // are position and velocity which are claimed by joint_state_broadcaster and\n  // feedback based controllers\n  return state_interfaces_config;\n}\n\ncontroller_interface::CallbackReturn Cia402DeviceController::on_configure(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  if (CanopenProxyController::on_configure(previous_state) != CallbackReturn::SUCCESS)\n    return CallbackReturn::ERROR;\n\n  return CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::CallbackReturn Cia402DeviceController::on_activate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  if (CanopenProxyController::on_activate(previous_state) != CallbackReturn::SUCCESS)\n    return CallbackReturn::ERROR;\n\n  return CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::CallbackReturn Cia402DeviceController::on_deactivate(\n  const rclcpp_lifecycle::State & previous_state)\n{\n  if (CanopenProxyController::on_deactivate(previous_state) != CallbackReturn::SUCCESS)\n    return CallbackReturn::ERROR;\n\n  return CallbackReturn::SUCCESS;\n}\n\ncontroller_interface::return_type Cia402DeviceController::update(\n  const rclcpp::Time & time, const rclcpp::Duration & period)\n{\n  if (CanopenProxyController::update(time, period) != controller_interface::return_type::OK)\n    return controller_interface::return_type::ERROR;\n\n  return controller_interface::return_type::OK;\n}\n\n}  // namespace canopen_ros2_controllers\n\n#include \"pluginlib/class_list_macros.hpp\"\n\nPLUGINLIB_EXPORT_CLASS(\n  canopen_ros2_controllers::Cia402DeviceController, controller_interface::ControllerInterface)\n"
  },
  {
    "path": "canopen_ros2_controllers/test/test_canopen_proxy_controller.cpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include \"test_canopen_proxy_controller.hpp\"\n\n#include <limits>\n#include <memory>\n#include <optional>\n#include <string>\n#include <utility>\n#include <vector>\n\nclass CanopenProxyControllerTest\n: public CanopenProxyControllerFixture<TestableCanopenProxyController>\n{\n};\n\n// When there are many mandatory parameters, set all by default and remove one by one in a\n// parameterized test\nTEST_P(CanopenProxyControllerTestParameterizedParameters, one_parameter_is_missing)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);\n}\n\n// TODO(anyone): the new gtest version after 1.8.0 uses INSTANTIATE_TEST_SUITE_P\nINSTANTIATE_TEST_SUITE_P(\n  MissingMandatoryParameterDuringConfiguration, CanopenProxyControllerTestParameterizedParameters,\n  ::testing::Values(\n    std::make_tuple(std::string(\"joint\"), rclcpp::ParameterValue(std::string({})))));\n\nTEST_F(CanopenProxyControllerTest, joint_names_parameter_not_set)\n{\n  SetUpController(false);\n\n  ASSERT_TRUE(controller_->joint_name_.empty());\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);\n\n  ASSERT_TRUE(controller_->joint_name_.empty());\n}\n\nTEST_F(CanopenProxyControllerTest, all_parameters_set_configure_success)\n{\n  SetUpController();\n\n  ASSERT_TRUE(controller_->joint_name_.empty());\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  // check that the message is reset\n  auto msg = controller_->input_cmd_.readFromNonRT();\n\n  ASSERT_THAT(controller_->joint_name_, joint_name_);\n}\n\nTEST_F(CanopenProxyControllerTest, check_exported_intefaces)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n\n  auto command_intefaces = controller_->command_interface_configuration();\n  ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size());\n  for (size_t i = 0; i < command_intefaces.names.size(); ++i)\n  {\n    EXPECT_EQ(command_intefaces.names[i], joint_name_ + \"/\" + command_interface_names_[i]);\n  }\n\n  auto state_intefaces = controller_->state_interface_configuration();\n  ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size());\n  for (size_t i = 0; i < state_intefaces.names.size(); ++i)\n  {\n    EXPECT_EQ(state_intefaces.names[i], joint_name_ + \"/\" + state_interface_names_[i]);\n  }\n}\n\nTEST_F(CanopenProxyControllerTest, activate_success)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n\n  // check that the message is reset\n  auto msg = *(controller_->input_cmd_.readFromNonRT());\n  EXPECT_EQ(msg, nullptr);\n}\n\nTEST_F(CanopenProxyControllerTest, update_success)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n\n  ASSERT_EQ(\n    controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),\n    controller_interface::return_type::OK);\n}\n\nTEST_F(CanopenProxyControllerTest, deactivate_success)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n}\n\nTEST_F(CanopenProxyControllerTest, reactivate_success)\n{\n  SetUpController();\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  const auto tpdo_data_initial =\n    controller_->command_interfaces_[CommandInterfaces::TPDO_DATA].get_optional<double>();\n  ASSERT_TRUE(tpdo_data_initial);\n  ASSERT_DOUBLE_EQ(*tpdo_data_initial, 101.101);\n  ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  const auto tpdo_data_after_deactivate =\n    controller_->command_interfaces_[CommandInterfaces::TPDO_DATA].get_optional<double>();\n  ASSERT_TRUE(tpdo_data_after_deactivate);\n  ASSERT_TRUE(std::isnan(*tpdo_data_after_deactivate));\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  const auto tpdo_data_after_activate =\n    controller_->command_interfaces_[CommandInterfaces::TPDO_DATA].get_optional<double>();\n  ASSERT_TRUE(tpdo_data_after_activate);\n  ASSERT_TRUE(std::isnan(*tpdo_data_after_activate));\n\n  ASSERT_EQ(\n    controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),\n    controller_interface::return_type::OK);\n}\n\nTEST_F(CanopenProxyControllerTest, test_sequence_configure_activate)\n{\n  SetUpController();\n\n  rclcpp::executors::MultiThreadedExecutor executor;\n  executor.add_node(controller_->get_node()->get_node_base_interface());\n  executor.add_node(service_caller_node_->get_node_base_interface());\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n}\n\nTEST_F(CanopenProxyControllerTest, test_update_logic_fast)\n{\n  SetUpController();\n  rclcpp::executors::MultiThreadedExecutor executor;\n  executor.add_node(controller_->get_node()->get_node_base_interface());\n  executor.add_node(service_caller_node_->get_node_base_interface());\n\n  ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);\n  ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);\n\n  // set command statically as value for good type\n  std::shared_ptr<ControllerCommandMsg> msg = std::make_shared<ControllerCommandMsg>();\n  msg->index = 0u;\n  msg->subindex = 0u;\n  msg->data = 0u;\n\n  controller_->input_cmd_.writeFromNonRT(msg);\n\n  ASSERT_EQ(\n    controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),\n    controller_interface::return_type::OK);\n}\n"
  },
  {
    "path": "canopen_ros2_controllers/test/test_canopen_proxy_controller.hpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#ifndef CANOPEN_ROS2_CONTROLLERS__CONTROLLER__TEST_CANOPEN_PROXY_CONTROLLER_HPP_\n#define CANOPEN_ROS2_CONTROLLERS__CONTROLLER__TEST_CANOPEN_PROXY_CONTROLLER_HPP_\n\n#include <chrono>\n#include <limits>\n#include <memory>\n#include <string>\n#include <tuple>\n#include <utility>\n#include <vector>\n\n#include \"canopen_ros2_controllers/canopen_proxy_controller.hpp\"\n#include \"gmock/gmock.h\"\n#include \"hardware_interface/loaned_command_interface.hpp\"\n#include \"hardware_interface/loaned_state_interface.hpp\"\n#include \"hardware_interface/types/hardware_interface_return_values.hpp\"\n#include \"rclcpp/parameter_value.hpp\"\n#include \"rclcpp/time.hpp\"\n#include \"rclcpp/utilities.hpp\"\n#include \"rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp\"\n\n// TODO(anyone): replace the state and command message types\nusing ControllerStateMsg = canopen_ros2_controllers::CanopenProxyController::ControllerNMTStateMsg;\nusing ControllerCommandMsg = canopen_ros2_controllers::CanopenProxyController::ControllerCommandMsg;\nusing ControllerModeSrvType =\n  canopen_ros2_controllers::CanopenProxyController::ControllerStartResetSrvType;\n\nnamespace\n{\nconstexpr auto NODE_SUCCESS = controller_interface::CallbackReturn::SUCCESS;\nconstexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR;\n}  // namespace\n\n// subclassing and friending so we can access member variables\nclass TestableCanopenProxyController : public canopen_ros2_controllers::CanopenProxyController\n{\n  FRIEND_TEST(CanopenProxyControllerTest, joint_names_parameter_not_set);\n  FRIEND_TEST(CanopenProxyControllerTest, all_parameters_set_configure_success);\n  FRIEND_TEST(CanopenProxyControllerTest, activate_success);\n  FRIEND_TEST(CanopenProxyControllerTest, reactivate_success);\n  FRIEND_TEST(CanopenProxyControllerTest, test_setting_slow_mode_service);\n  FRIEND_TEST(CanopenProxyControllerTest, test_update_logic_fast);\n  FRIEND_TEST(CanopenProxyControllerTest, test_update_logic_slow);\n\npublic:\n  controller_interface::CallbackReturn on_configure(\n    const rclcpp_lifecycle::State & previous_state) override\n  {\n    auto ret = canopen_ros2_controllers::CanopenProxyController::on_configure(previous_state);\n    // Only if on_configure is successful create subscription\n    if (ret == CallbackReturn::SUCCESS)\n    {\n      cmd_subscriber_wait_set_.add_subscription(tpdo_subscriber_);\n    }\n    return ret;\n  }\n\n  /**\n   * @brief wait_for_command blocks until a new ControllerCommandMsg is received.\n   * Requires that the executor is not spinned elsewhere between the\n   *  message publication and the call to this function.\n   *\n   * @return true if new ControllerCommandMsg msg was received, false if timeout.\n   */\n  bool wait_for_command(\n    rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set,\n    const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500})\n  {\n    bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready;\n    if (success)\n    {\n      executor.spin_some();\n    }\n    return success;\n  }\n\n  bool wait_for_commands(\n    rclcpp::Executor & executor,\n    const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500})\n  {\n    return wait_for_command(executor, cmd_subscriber_wait_set_, timeout);\n  }\n\n  // TODO(anyone): add implementation of any methods of your controller is needed\n\nprivate:\n  rclcpp::WaitSet cmd_subscriber_wait_set_;\n};\n\n// We are using template class here for easier reuse of Fixture in specializations of controllers\ntemplate <typename CtrlType>\nclass CanopenProxyControllerFixture : public ::testing::Test\n{\npublic:\n  static void SetUpTestCase() { rclcpp::init(0, nullptr); }\n\n  void SetUp()\n  {\n    // initialize controller\n    controller_ = std::make_unique<CtrlType>();\n\n    command_publisher_node_ = std::make_shared<rclcpp::Node>(\"command_publisher\");\n    command_publisher_ = command_publisher_node_->create_publisher<ControllerCommandMsg>(\n      \"/test_canopen_ros2_controllers/commands\", rclcpp::SystemDefaultsQoS());\n\n    service_caller_node_ = std::make_shared<rclcpp::Node>(\"service_caller\");\n    slow_control_service_client_ = service_caller_node_->create_client<ControllerModeSrvType>(\n      \"/test_canopen_ros2_controllers/set_slow_control_mode\");\n  }\n\n  static void TearDownTestCase() { rclcpp::shutdown(); }\n\n  void TearDown() { controller_.reset(nullptr); }\n\nprotected:\n  void SetUpController(\n    bool set_parameters = true, std::string controller_name = \"test_canopen_ros2_controllers\")\n  {\n    ASSERT_EQ(controller_->init(controller_name), controller_interface::return_type::OK);\n\n    std::vector<hardware_interface::LoanedCommandInterface> command_ifs;\n    command_itfs_.reserve(joint_command_values_.size());\n    command_ifs.reserve(joint_command_values_.size());\n\n    for (size_t i = 0; i < joint_command_values_.size(); ++i)\n    {\n      command_itfs_.emplace_back(hardware_interface::CommandInterface(\n        joint_name_, command_interface_names_[i], &joint_command_values_[i]));\n      command_ifs.emplace_back(command_itfs_.back());\n    }\n\n    std::vector<hardware_interface::LoanedStateInterface> state_ifs;\n    state_itfs_.reserve(joint_state_values_.size());\n    state_ifs.reserve(joint_state_values_.size());\n\n    for (size_t i = 0; i < joint_state_values_.size(); ++i)\n    {\n      state_itfs_.emplace_back(hardware_interface::StateInterface(\n        joint_name_, state_interface_names_[i], &joint_state_values_[i]));\n      state_ifs.emplace_back(state_itfs_.back());\n    }\n\n    controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));\n\n    if (set_parameters)\n    {\n      controller_->get_node()->set_parameter({\"joint\", joint_name_});\n    }\n  }\n\n  void subscribe_and_get_messages(ControllerStateMsg & msg)\n  {\n    // create a new subscriber\n    rclcpp::Node test_subscription_node(\"test_subscription_node\");\n    auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {};\n    auto subscription = test_subscription_node.create_subscription<ControllerStateMsg>(\n      \"/test_canopen_ros2_controllers/state\", 10, subs_callback);\n\n    // call update to publish the test value\n    ASSERT_EQ(\n      controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),\n      controller_interface::return_type::OK);\n\n    // call update to publish the test value\n    // since update doesn't guarantee a published message, republish until received\n    int max_sub_check_loop_count = 5;  // max number of tries for pub/sub loop\n    rclcpp::WaitSet wait_set;          // block used to wait on message\n    wait_set.add_subscription(subscription);\n    while (max_sub_check_loop_count--)\n    {\n      controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));\n      // check if message has been received\n      if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready)\n      {\n        break;\n      }\n    }\n    ASSERT_GE(max_sub_check_loop_count, 0) << \"Test was unable to publish a message through \"\n                                              \"controller/broadcaster update loop\";\n\n    // take message from subscription\n    rclcpp::MessageInfo msg_info;\n    ASSERT_TRUE(subscription->take(msg, msg_info));\n  }\n\n  // TODO(anyone): add/remove arguments as it suites your command message type\n  void publish_commands(\n    const std::vector<double> & displacements = {0.45},\n    const std::vector<double> & velocities = {0.0}, const double duration = 1.25)\n  {\n    auto wait_for_topic = [&](const auto topic_name)\n    {\n      size_t wait_count = 0;\n      while (command_publisher_node_->count_subscribers(topic_name) == 0)\n      {\n        if (wait_count >= 5)\n        {\n          auto error_msg =\n            std::string(\"publishing to \") + topic_name + \" but no node subscribes to it\";\n          throw std::runtime_error(error_msg);\n        }\n        std::this_thread::sleep_for(std::chrono::milliseconds(100));\n        ++wait_count;\n      }\n    };\n\n    wait_for_topic(command_publisher_->get_topic_name());\n\n    ControllerCommandMsg msg;\n    msg.index = 0u;\n    msg.subindex = 0u;\n    msg.data = 0u;\n\n    command_publisher_->publish(msg);\n  }\n\nprotected:\n  // Controller-related parameters\n  std::string joint_name_ = {\"joint1\"};\n  std::vector<std::string> command_interface_names_ = {\n    \"tpdo/index\", \"tpdo/subindex\", \"tpdo/data\", \"tpdo/ons\",\n    \"nmt/reset\",  \"nmt/reset_fbk\", \"nmt/start\", \"nmt/start_fbk\"};\n\n  std::vector<std::string> state_interface_names_ = {\n    \"rpdo/index\", \"rpdo/subindex\", \"rpdo/data\", \"nmt/state\"};\n\n  // see StateInterfaces in canopen_proxy_controller.hpp for correct order;\n  std::array<double, 4> joint_state_values_ = {0, 0, 0, 0};\n  // see CommandInterfaces in canopen_proxy_controller.hpp for correct order;\n  std::array<double, 8> joint_command_values_ = {101.101, 101.101, 101.101, 101.101,\n                                                 101.101, 101.101, 101.101, 101.101};\n\n  std::vector<hardware_interface::StateInterface> state_itfs_;\n  std::vector<hardware_interface::CommandInterface> command_itfs_;\n\n  // Test related parameters\n  std::unique_ptr<TestableCanopenProxyController> controller_;\n  rclcpp::Node::SharedPtr command_publisher_node_;\n  rclcpp::Publisher<ControllerCommandMsg>::SharedPtr command_publisher_;\n  rclcpp::Node::SharedPtr service_caller_node_;\n  rclcpp::Client<ControllerModeSrvType>::SharedPtr slow_control_service_client_;\n};\n\n// From the tutorial: https://www.sandordargo.com/blog/2019/04/24/parameterized-testing-with-gtest\nclass CanopenProxyControllerTestParameterizedParameters\n: public CanopenProxyControllerFixture<TestableCanopenProxyController>,\n  public ::testing::WithParamInterface<std::tuple<std::string, rclcpp::ParameterValue>>\n{\npublic:\n  virtual void SetUp() { CanopenProxyControllerFixture::SetUp(); }\n\n  static void TearDownTestCase() { CanopenProxyControllerFixture::TearDownTestCase(); }\n\nprotected:\n  void SetUpController(bool set_parameters = true)\n  {\n    CanopenProxyControllerFixture::SetUpController(set_parameters);\n    controller_->get_node()->set_parameter({std::get<0>(GetParam()), std::get<1>(GetParam())});\n  }\n};\n\n#endif  // CANOPEN_ROS2_CONTROLLERS__CONTROLLER__TEST_CANOPEN_PROXY_CONTROLLER_HPP_\n"
  },
  {
    "path": "canopen_ros2_controllers/test/test_load_canopen_proxy_controller.cpp",
    "content": "// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include <gmock/gmock.h>\n#include <memory>\n\n#include \"controller_manager/controller_manager.hpp\"\n#include \"hardware_interface/resource_manager.hpp\"\n#include \"rclcpp/executor.hpp\"\n#include \"rclcpp/executors/single_threaded_executor.hpp\"\n#include \"rclcpp/utilities.hpp\"\n\nTEST(TestLoadCanopenProxyController, load_controller)\n{\n  rclcpp::init(0, nullptr);\n\n  std::shared_ptr<rclcpp::Executor> executor =\n    std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n\n  controller_manager::ControllerManager cm(\n    std::make_unique<hardware_interface::ResourceManager>(), executor, \"test_controller_manager\");\n\n  ASSERT_NO_THROW(cm.load_controller(\n    \"test_canopen_ros2_controllers\", \"canopen_ros2_controllers/CanopenProxyController\"));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_ros2_controllers/test/test_load_cia402_device_controller.cpp",
    "content": "// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include <gmock/gmock.h>\n#include <memory>\n\n#include \"controller_manager/controller_manager.hpp\"\n#include \"hardware_interface/resource_manager.hpp\"\n#include \"rclcpp/executor.hpp\"\n#include \"rclcpp/executors/single_threaded_executor.hpp\"\n#include \"rclcpp/utilities.hpp\"\n\nTEST(TestLoadCanopenProxyController, load_controller)\n{\n  rclcpp::init(0, nullptr);\n\n  std::shared_ptr<rclcpp::Executor> executor =\n    std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n\n  controller_manager::ControllerManager cm(\n    std::make_unique<hardware_interface::ResourceManager>(), executor, \"test_controller_manager\");\n\n  ASSERT_NO_THROW(cm.load_controller(\n    \"test_canopen_ros2_controllers\", \"canopen_ros2_controllers/Cia402DeviceController\"));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_ros2_controllers/test/test_load_cia402_robot_controller.cpp",
    "content": "// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)\n//\n// Licensed under the Apache License, Version 2.0 (the \"License\");\n// you may not use this file except in compliance with the License.\n// You may obtain a copy of the License at\n//\n//     http://www.apache.org/licenses/LICENSE-2.0\n//\n// Unless required by applicable law or agreed to in writing, software\n// distributed under the License is distributed on an \"AS IS\" BASIS,\n// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n// See the License for the specific language governing permissions and\n// limitations under the License.\n\n#include <gmock/gmock.h>\n#include <memory>\n\n#include \"controller_manager/controller_manager.hpp\"\n#include \"hardware_interface/resource_manager.hpp\"\n#include \"rclcpp/executor.hpp\"\n#include \"rclcpp/executors/single_threaded_executor.hpp\"\n#include \"rclcpp/utilities.hpp\"\n\nTEST(TestLoadCanopenProxyController, load_controller)\n{\n  rclcpp::init(0, nullptr);\n\n  std::shared_ptr<rclcpp::Executor> executor =\n    std::make_shared<rclcpp::executors::SingleThreadedExecutor>();\n\n  controller_manager::ControllerManager cm(\n    std::make_unique<hardware_interface::ResourceManager>(), executor, \"test_controller_manager\");\n\n  ASSERT_NO_THROW(cm.load_controller(\n    \"test_canopen_ros2_controllers\", \"canopen_ros2_controllers/Cia402RobotController\"));\n\n  rclcpp::shutdown();\n}\n"
  },
  {
    "path": "canopen_tests/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_tests\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* Enhance SimpleSlave class with vendor ID parsing and adjust bus configuration timeouts\n* Multiple SDO types for slaves (`#278 <https://github.com/ros-industrial/ros2_canopen/issues/278>`_)\n  Co-authored-by: Kurtis Thrush <kthrush@jlg.com>\n  Co-authored-by: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\n* Contributors: Christoph Hellmann Santos\n\n0.2.9 (2024-04-16)\n------------------\n0.3.1 (2025-06-23)\n------------------\n\n0.3.0 (2024-12-12)\n------------------\n* Add new line to get checking pipeline okay\n* Working version.\n* Periodic messages sent, but not received properly.\n\n0.2.12 (2024-04-22)\n-------------------\n* Merge pull request `#270 <https://github.com/ros-industrial/ros2_canopen/issues/270>`_ from gsalinas/can-namespace-pr\n  Put components loaded by the device container into its namespace, if any.\n* pre-commit update\n* Add node on namespaces.\n* Restore base version of canopen_system example.\n* Restore cia402_system launch to original.\n* Change cia402_system ros2_controllers back to original.\n* Add comment about the use of ReplaceString.\n* Push namespace to nodes in a group.\n* Separate out example of how to use a namespaced ros2_control/cia402 based system.\n* Remove commented-out arg and unneeded logging.\n* Update canopen test system launch to use a namespace.\n* Output robot_description_content to log during launch.\n* WIP adding namespace to cia402_system launch.\n* 0.2.9\n* forthcoming\n* Contributors: Gerry Salinas, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n* Update package.xml\n* Solve buildfarm issues (`#155 <https://github.com/ros-industrial/ros2_canopen/issues/155>`_)\n  * Move exec deps from ros2_control to tests\n  * Remove mkdir in install dir from cogen and dcfgen\n  This causes a permission denied error on buildfarm.\n  The install command creates it anyways\n* Contributors: Christoph Hellmann Santos\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Add trvivial integration test for robot_control\n* Add trivial integration tests for cia402_driver\n* Use the more tidy launch_test_node\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Denis Štogl, James Ward, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_tests/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(canopen_tests)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(lely_core_libraries REQUIRED)\n\n\ngenerate_dcf(simple)\ngenerate_dcf(canopen_system)\ncogen_dcf(cia402_system)\ncogen_dcf(cia402_namespaced_system)\ncogen_dcf(cia402)\ngenerate_dcf(cia402_lifecycle)\ncogen_dcf(cia402_diagnostics)\ngenerate_dcf(simple_lifecycle)\ncogen_dcf(simple_diagnostics)\ngenerate_dcf(robot_control)\n\ninstall(DIRECTORY\n  launch rviz urdf launch_tests\n  DESTINATION share/${PROJECT_NAME}\n)\n\n\n\nif(BUILD_TESTING)\n  if(CANOPEN_ENABLED)\n    find_package(launch_testing_ament_cmake REQUIRED)\n    add_launch_test(launch_tests/test_proxy_driver.py)\n    add_launch_test(launch_tests/test_proxy_lifecycle_driver.py)\n  endif()\nendif()\n\nament_package()\n"
  },
  {
    "path": "canopen_tests/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_tests/README.md",
    "content": "# CANopen Tests\n\nEnable launch tests with --cmake-args -DCANOPEN_ENABLED.\nThey can only be run on devices that have vcan0 enabled.\n"
  },
  {
    "path": "canopen_tests/ROS_NAMESPACES.md",
    "content": "The `cia402_namespaced_system.launch.py` example demonstrates how to run a\nCIA402 system in a namespace to allow multiple CANOpen-based robots in the\nsame ROS domain. This example is necessary because the controller names\nare picked up from `ros2_controllers.yaml` and we must define their names\nin that file with a `__namespace__/controller_name:` key, then use\nReplaceString from `nav2_common` to dynamically add the namespace to the\ncontroller definition.\n\nFor a proxy system, no example is included; it's sufficient to include, e.g.\nthe `proxy_setup.launch.py` launch description in another launch file and\npush a namespace onto it with PushROSNamespace in the ordinary way.\n"
  },
  {
    "path": "canopen_tests/config/canopen_system/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::ProxyDriver\"\n  package: \"canopen_proxy_driver\"\n\nproxy_device_2:\n  node_id: 3\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::ProxyDriver\"\n  package: \"canopen_proxy_driver\"\n"
  },
  {
    "path": "canopen_tests/config/canopen_system/ros2_controllers.yaml",
    "content": "controller_manager:\n  ros__parameters:\n    update_rate: 10  # Hz\n\n    joint_state_broadcaster:\n      type: joint_state_broadcaster/JointStateBroadcaster\n\n    node_1_controller:\n      type: canopen_ros2_controllers/CanopenProxyController\n\nnode_1_controller:\n  ros__parameters:\n    joint: node_1\n"
  },
  {
    "path": "canopen_tests/config/canopen_system/simple.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=2\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=13\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1801\n12=0x1A00\n13=0x1A01\n\n[ManufacturerObjects]\nSupportedObjects=5\n1=0x4000\n2=0x4001\n3=0x4002\n4=0x4003\n5=0x4004\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1801]\nSubNumber=7\nParameterName=TPDO communication parameter 2\nObjectType=0x09\n\n[1801sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1801sub1]\nParameterName=COB-ID used by TPDO 2\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x280\n\n[1801sub2]\nParameterName=transmission type 2\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1801sub3]\nParameterName=inhibit time 2\nDataType=0x0006\nAccessType=rw\n\n[1801sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1801sub5]\nParameterName=event timer 2\nDataType=0x0006\nAccessType=rw\n\n[1801sub6]\nParameterName=SYNC start value 2\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[1A01]\nParameterName=TPDO mapping parameter 2\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A01Value]\nNrOfEntries=1\n1=0x40040020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[4002]\nParameterName=INTEGER32 test\nDataType=0x0004\nAccessType=rw\n\n[4003]\nParameterName=INTEGER16 test\nDataType=0x0003\nAccessType=rw\n\n[4004]\nParameterName=UNSIGNED32 sent from slave 2\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n"
  },
  {
    "path": "canopen_tests/config/cia402/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\ndefaults:\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 10\n  revision_number: 0\n  boot_timeout_ms: 1000\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n    3:\n      enabled: false\n    4:\n      enabled: false\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      - {index: 0x60FF, sub_index: 0} # target velocity\n\nnodes:\n  cia402_device_1:\n    node_id: 2\n    namespace: \"/test1\"\n  # cia402_device_2:\n  #   node_id: 3\n  # cia402_device_3:\n  #   node_id: 4\n  # cia402_device_4:\n  #   node_id: 5\n  # cia402_device_5:\n  #   node_id: 6\n  # cia402_device_6:\n  #   node_id: 7\n"
  },
  {
    "path": "canopen_tests/config/cia402/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_tests/config/cia402_diagnostics/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\ndefaults:\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  diagnostics:\n    enable: true\n    period: 1000 # in milliseconds\n  revision_number: 0\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n    3:\n      enabled: false\n    4:\n      enabled: false\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      - {index: 0x60FF, sub_index: 0} # target velocity\n\nnodes:\n  cia402_device_1:\n    node_id: 2\n  cia402_device_2:\n    node_id: 3\n  cia402_device_3:\n    node_id: 4\n"
  },
  {
    "path": "canopen_tests/config/cia402_diagnostics/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_tests/config/cia402_lifecycle/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::LifecycleMasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 20000\n\ncia402_device_1:\n  node_id: 2\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::LifecycleCia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 20\n  enable_lazy_load: false\n  revision_number: 0\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n    3:\n      enabled: false\n    4:\n      enabled: false\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      - {index: 0x60FF, sub_index: 0} # target velocity\n"
  },
  {
    "path": "canopen_tests/config/cia402_lifecycle/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0xC0000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x40000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0xC0000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_tests/config/cia402_multichannel_system/README.md",
    "content": "# Multi-Channel CiA 402 System Configuration\n\nThis configuration demonstrates the multi-channel/multi-axes feature as described in CiA 302-7 and CiA 402-2 specifications.\n\n## Overview\n\nMulti-channel devices allow controlling multiple independent axes over a single CANopen Node-ID. This is useful for:\n- Multi-axis motor controllers (e.g., dual-axis servo drives)\n- Coordinated motion control systems\n- Reducing network complexity by consolidating multiple axes into one node\n\n## CiA 402-2 Specification\n\nAccording to CiA 402-2, multi-axis devices use offset object dictionary indices:\n\n- **Channel 0** (standard): Indices 0x6000-0x67FF\n- **Channel 1**: Indices 0x6800-0x6FFF (offset +0x800)\n- **Channel 2**: Indices 0x7000-0x77FF (offset +0x1000)\n- **Channel N**: Indices 0x6000 + (N * 0x800)\n\n### Common Object Examples\n\n| Object | Channel 0 | Channel 1 | Channel 2 |\n|--------|-----------|-----------|-----------|\n| Controlword | 0x6040 | 0x6840 | 0x7040 |\n| Statusword | 0x6041 | 0x6841 | 0x7041 |\n| Modes of operation | 0x6060 | 0x6860 | 0x7060 |\n| Position actual value | 0x6064 | 0x6864 | 0x7064 |\n| Velocity actual value | 0x606C | 0x686C | 0x706C |\n| Target position | 0x607A | 0x687A | 0x707A |\n| Target velocity | 0x60FF | 0x68FF | 0x70FF |\n\n## Configuration Structure\n\n### Bus Configuration (bus.yml)\n\nThe bus configuration defines:\n1. PDO mappings for each channel with appropriate index offsets\n2. SDO initialization values for each channel\n3. A single node_id that hosts multiple channels\n\n### Hardware Description (URDF)\n\nWhen using ros2_control, the hardware interface must specify the channel for each joint:\n\n```xml\n<ros2_control name=\"cia402_multichannel_system\" type=\"system\">\n  <hardware>\n    <plugin>canopen_ros2_control/Cia402System</plugin>\n    <param name=\"bus_config\">$(find canopen_tests)/config/cia402_multichannel_system/bus.yml</param>\n    <param name=\"master_config\">$(find canopen_tests)/config/master.dcf</param>\n    <param name=\"can_interface_name\">vcan0</param>\n    <param name=\"master_bin\"></param>\n  </hardware>\n\n  <!-- First axis (channel 0) -->\n  <joint name=\"node_2_channel_0\">\n    <command_interface name=\"position\"/>\n    <command_interface name=\"velocity\"/>\n    <state_interface name=\"position\"/>\n    <state_interface name=\"velocity\"/>\n    <param name=\"node_id\">2</param>\n    <param name=\"channel\">0</param>  <!-- Channel specification -->\n  </joint>\n\n  <!-- Second axis (channel 1) -->\n  <joint name=\"node_2_channel_1\">\n    <command_interface name=\"position\"/>\n    <command_interface name=\"velocity\"/>\n    <state_interface name=\"position\"/>\n    <state_interface name=\"velocity\"/>\n    <param name=\"node_id\">2</param>\n    <param name=\"channel\">1</param>  <!-- Channel specification -->\n  </joint>\n</ros2_control>\n```\n\n### Key Parameters\n\n- **node_id**: The CANopen node ID of the device\n- **channel**: The channel/axis number within that device (0, 1, 2, ...)\n  - Defaults to 0 if not specified (backward compatible)\n  - Used to calculate the object dictionary index offset\n\n## Backward Compatibility\n\nThe multi-channel feature is fully backward compatible:\n\n- If the `channel` parameter is not specified, it defaults to 0\n- Channel 0 uses standard object indices (no offset)\n- Existing single-axis configurations work without modification\n\n## Usage Example\n\n1. Configure the bus with appropriate PDO mappings for all channels\n2. In your URDF, specify joints with their `node_id` and `channel`\n3. Use standard ros2_control interfaces to control each axis independently\n4. Each channel operates as an independent joint in the system\n\n## Hardware Requirements\n\nYour CANopen device must:\n- Support CiA 402-2 multi-axis specification\n- Implement object dictionary entries at the correct offset indices\n- Have appropriate EDS/DCF file defining all channel objects\n\n## Testing\n\nTo test this configuration with simulated devices:\n\n```bash\n# Set up virtual CAN interface\nsudo modprobe vcan\nsudo ip link add dev vcan0 type vcan\nsudo ip link set vcan0 txqueuelen 1000\nsudo ip link set up vcan0\n\n# Launch the multi-channel system\nros2 launch canopen_tests cia402_multichannel_system_setup.launch.py\n```\n\n## References\n\n- CiA 302-7: Framework for programmable CANopen devices - Part 7: Multi-axis positioning controller\n- CiA 402-2: CANopen device profile for drives and motion control - Part 2: Multiple axis communication parameter\n"
  },
  {
    "path": "canopen_tests/config/cia402_multichannel_system/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\n# Multi-channel device configuration for CiA 402-2\n# This example shows a device at node_id 2 with two channels (axes)\nnodes:\n  # Single device with two channels\n  cia402_multichannel_device:\n    node_id: 2\n    driver: \"ros2_canopen::Cia402Driver\"\n    package: \"canopen_402_driver\"\n    dcf: \"cia402_slave_multichannel.eds\"\n    period: 10\n    revision_number: 0\n\n    # Multi-channel configuration\n    num_channels: 2  # Number of axes/channels on this device\n\n    # Optional: Custom names for each channel (used in joint_states topic)\n    # If not provided, defaults to <node_name>/0, <node_name>/1, etc.\n    channel_names:\n      - \"joint_0\"\n      - \"joint_1\"\n\n    # Global scale factors and offsets (used as defaults for all channels)\n    scale_pos_to_dev: 1000.0       # Convert position from SI units to device units\n    scale_pos_from_dev: 0.001      # Convert position from device units to SI units\n    scale_vel_to_dev: 1000.0       # Convert velocity from SI units to device units\n    scale_vel_from_dev: 0.001      # Convert velocity from device units to SI units\n    offset_pos_to_dev: 0.0         # Offset when converting position to device\n    offset_pos_from_dev: 0.0       # Offset when converting position from device\n\n    # Optional: Per-channel scale factors and offsets (override global settings)\n    # If a channel is not listed, it will use the global values above\n    channels:\n      - # Channel 0 configuration\n        scale_pos_to_dev: 1000.0\n        scale_pos_from_dev: 0.001\n        scale_vel_to_dev: 1000.0\n        scale_vel_from_dev: 0.001\n        offset_pos_to_dev: 0.0\n        offset_pos_from_dev: 0.0\n      - # Channel 1 configuration (different scale for this axis)\n        scale_pos_to_dev: 2000.0\n        scale_pos_from_dev: 0.0005\n        scale_vel_to_dev: 2000.0\n        scale_vel_from_dev: 0.0005\n        offset_pos_to_dev: 10.0\n        offset_pos_from_dev: 5.0\n\n    # Other CIA 402 settings\n    switching_state: 8              # Target state for mode switching (8 = Operation Enable)\n    homing_timeout_seconds: 10      # Timeout for homing operation\n\n\n    # Usage notes:\n    # 1. Service naming depends on num_channels:\n    #    Single-channel (num_channels: 1): /node_name/init, /node_name/target\n    #    Multi-channel (num_channels: 2): /joint_0/init, /joint_1/target, etc.\n    #\n    #    Examples for multi-channel:\n    #    ros2 service call /joint_0/target canopen_interfaces/srv/COTargetDouble \"{target: 100.0}\"\n    #    ros2 service call /joint_1/target canopen_interfaces/srv/COTargetDouble \"{target: 50.0}\"\n    #    ros2 service call /joint_0/init std_srvs/srv/Trigger\n    #    ros2 service call /joint_1/enable std_srvs/srv/Trigger\n    #\n    # 2. Joint state publishing:\n    #    Single-channel: name: [\"node_name\"]\n    #    Multi-channel: name: [\"joint_0\", \"joint_1\"]\n    #    Topic: ~/joint_states (sensor_msgs/msg/JointState)\n    #    - position: [pos_ch0, pos_ch1]\n    #    - velocity: [vel_ch0, vel_ch1]\n    #\n    # 3. Multi-channel services use channel_name as prefix:\n    #    - joint_0/init, joint_0/enable, joint_0/target, joint_0/position_mode, etc.\n    #    - joint_1/init, joint_1/enable, joint_1/target, joint_1/position_mode, etc.\n    #\n    # 4. Per-channel diagnostics are available with prefixes: ch0_, ch1_, etc.\n\n    # Example CiA 402-2 Object Dictionary mapping:\n    # Channel 0: Standard indices (0x6040, 0x6041, 0x6060, etc.)\n    # Channel 1: Offset +0x800 (0x6840, 0x6841, 0x6860, etc.)\n    # Channel 2: Offset +0x1000 (0x7040, 0x7041, 0x7060, etc.)\n\n\n    # SDO configuration for both channels\n    # Channel 0 (standard indices 0x6000-0x67FF)\n    # Channel 1 (offset indices 0x6800-0x6FFF)\n    sdo:\n      # Channel 0 configuration\n      - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n      - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n      - {index: 0x6081, sub_index: 0, value: 1000}\n      - {index: 0x6083, sub_index: 0, value: 2000}\n\n      # Channel 1 configuration (indices offset by 0x800)\n      - {index: 0x68C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n      - {index: 0x68C2, sub_index: 2, value: -3} # Set base 10-3s\n      - {index: 0x6881, sub_index: 0, value: 1000}\n      - {index: 0x6883, sub_index: 0, value: 2000}\n\n    # TPDO configuration for both channels\n    tpdo:\n      # Channel 0 TPDOs\n      1:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6041, sub_index: 0} # status word channel 0\n          - {index: 0x6061, sub_index: 0} # mode of operation display channel 0\n      2:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6064, sub_index: 0} # position actual value channel 0\n          - {index: 0x606c, sub_index: 0} # velocity actual value channel 0\n\n      # Channel 1 TPDOs (indices offset by 0x800)\n      3:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6841, sub_index: 0} # status word channel 1\n          - {index: 0x6861, sub_index: 0} # mode of operation display channel 1\n      4:\n        enabled: true\n        cob_id: \"auto\"\n        transmission: 0x01\n        mapping:\n          - {index: 0x6864, sub_index: 0} # position actual value channel 1\n          - {index: 0x686c, sub_index: 0} # velocity actual value channel 1\n\n    # RPDO configuration for both channels\n    rpdo:\n      # Channel 0 RPDOs\n      1:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n          - {index: 0x6040, sub_index: 0} # controlword channel 0\n          - {index: 0x6060, sub_index: 0} # mode of operation channel 0\n      2:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n          - {index: 0x607A, sub_index: 0} # target position channel 0\n          - {index: 0x60FF, sub_index: 0} # target velocity channel 0\n\n      # Channel 1 RPDOs (indices offset by 0x800)\n      3:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n          - {index: 0x6840, sub_index: 0} # controlword channel 1\n          - {index: 0x6860, sub_index: 0} # mode of operation channel 1\n      4:\n        enabled: true\n        cob_id: \"auto\"\n        mapping:\n          - {index: 0x687A, sub_index: 0} # target position channel 1\n          - {index: 0x68FF, sub_index: 0} # target velocity channel 1\n"
  },
  {
    "path": "canopen_tests/config/cia402_multichannel_system/ros2_controllers.yaml",
    "content": "controller_manager:\n  ros__parameters:\n    update_rate: 10  # Hz\n\n    joint_state_broadcaster:\n      type: joint_state_broadcaster/JointStateBroadcaster\n\n    # Controller for channel 0\n    cia402_channel_0_controller:\n      type: canopen_ros2_controllers/Cia402DeviceController\n\n    # Controller for channel 1\n    cia402_channel_1_controller:\n      type: canopen_ros2_controllers/Cia402DeviceController\n\n    joint_trajectory_controller:\n      type: joint_trajectory_controller/JointTrajectoryController\n\n    forward_position_controller:\n      type: forward_command_controller/ForwardCommandController\n\ncia402_channel_0_controller:\n  ros__parameters:\n    joint: node_2_channel_0\n\ncia402_channel_1_controller:\n  ros__parameters:\n    joint: node_2_channel_1\n\nforward_position_controller:\n  ros__parameters:\n    joints:\n      - node_2_channel_0\n      - node_2_channel_1\n    interface_name: position\n\njoint_trajectory_controller:\n  ros__parameters:\n    joints:\n      - node_2_channel_0\n      - node_2_channel_1\n    command_interfaces:\n      - position\n    state_interfaces:\n      - position\n      - velocity\n    state_publish_rate: 100.0\n    action_monitor_rate: 20.0\n    allow_partial_joints_goal: false\n    constraints:\n      stopped_velocity_tolerance: 0.2\n      goal_time: 0.0\n      node_2_channel_0: { trajectory: 0.2, goal: 0.1 }\n      node_2_channel_1: { trajectory: 0.2, goal: 0.1 }\n"
  },
  {
    "path": "canopen_tests/config/cia402_namespaced_system/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\ndefaults:\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 10\n  revision_number: 0\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n    3:\n      enabled: false\n    4:\n      enabled: false\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      - {index: 0x60FF, sub_index: 0} # target velocity\n\nnodes:\n  cia402_device_1:\n    node_id: 2\n"
  },
  {
    "path": "canopen_tests/config/cia402_namespaced_system/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_tests/config/cia402_namespaced_system/ros2_controllers.yaml",
    "content": "__namespace__/controller_manager:\n  ros__parameters:\n    update_rate: 10  # Hz\n\n    joint_state_broadcaster:\n      type: joint_state_broadcaster/JointStateBroadcaster\n\n    cia402_device_1_controller:\n      type: canopen_ros2_controllers/Cia402DeviceController\n\n    joint_trajectory_controller:\n      type: joint_trajectory_controller/JointTrajectoryController\n\n    forward_position_controller:\n      type: forward_command_controller/ForwardCommandController\n\n__namespace__/cia402_device_1_controller:\n  ros__parameters:\n    joint: node_1\n\n__namespace__/forward_position_controller:\n  ros__parameters:\n    joints:\n      - node_1\n    interface_name: position\n\n__namespace__/joint_trajectory_controller:\n  ros__parameters:\n    joints:\n      - node_1\n    command_interfaces:\n      - position\n    state_interfaces:\n      - position\n      - velocity\n    state_publish_rate: 100.0\n    action_monitor_rate: 20.0\n    allow_partial_joints_goal: false\n    constraints:\n      stopped_velocity_tolerance: 0.2\n      goal_time: 0.0\n      node_1: { trajectory: 0.2, goal: 0.1 }\n"
  },
  {
    "path": "canopen_tests/config/cia402_system/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\ndefaults:\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 10\n  revision_number: 0\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n    3:\n      enabled: false\n    4:\n      enabled: false\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      - {index: 0x60FF, sub_index: 0} # target velocity\n\nnodes:\n  cia402_device_1:\n    node_id: 2\n"
  },
  {
    "path": "canopen_tests/config/cia402_system/cia402_slave.eds",
    "content": "[DeviceInfo]\r\nVendorName=ROS-Industrial\r\nVendorNumber=0x555\r\nProductName=CIA402VTD\r\nBaudRate_10=0\r\nBaudRate_20=1\r\nBaudRate_50=1\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=1\r\nBaudRate_1000=1\r\nDynamicChannelsSupported=0\r\nGroupMessaging=0\r\nLSS_Supported=0\r\nGranularity=8\r\nSimpleBootUpSlave=1\r\nSimpleBootUpMaster=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=67\r\n1=0x1005\r\n2=0x1008\r\n3=0x1009\r\n4=0x100A\r\n5=0x100C\r\n6=0x100D\r\n7=0x1010\r\n8=0x1011\r\n9=0x1014\r\n10=0x1015\r\n11=0x1016\r\n12=0x1017\r\n13=0x1023\r\n14=0x1029\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6040\r\n32=0x6041\r\n33=0x605A\r\n34=0x605B\r\n35=0x605C\r\n36=0x605D\r\n37=0x605E\r\n38=0x6060\r\n39=0x6061\r\n40=0x6062\r\n41=0x6063\r\n42=0x6064\r\n43=0x6065\r\n44=0x6067\r\n45=0x6068\r\n46=0x606A\r\n47=0x606C\r\n48=0x607A\r\n49=0x607C\r\n50=0x607D\r\n51=0x6081\r\n52=0x6082\r\n53=0x6083\r\n54=0x6084\r\n55=0x6085\r\n56=0x608F\r\n57=0x6098\r\n58=0x6099\r\n59=0x609A\r\n60=0x60B0\r\n61=0x60B1\r\n62=0x60C2\r\n63=0x60F2\r\n64=0x60FD\r\n65=0x60FF\r\n66=0x6502\r\n67=0x67FF\r\n\r\n[1000]\r\nParameterName=Device Type\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=const\r\nDefaultValue=0xFFFF0192\r\nPDOMapping=0\r\n\r\n[1001]\r\nParameterName=Error Register\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000080\r\nPDOMapping=0\r\n\r\n[1008]\r\nParameterName=Manufacturer Device Name\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[1009]\r\nParameterName=Manufacturer Hardware Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100A]\r\nParameterName=Manufacturer Software Version\r\nObjectType=0x07\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n[100C]\r\nParameterName=Guard Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[100D]\r\nParameterName=Life Time Factor\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1010]\r\nSubNumber=8\r\nParameterName=Store Parameter Field\r\nObjectType=0x08\r\n\r\n[1010sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub2]\r\nParameterName=Save Communication Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub3]\r\nParameterName=Save Device Profile Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub4]\r\nParameterName=Save Axis 0 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub5]\r\nParameterName=Save Axis 1 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub6]\r\nParameterName=Save Axis 2 Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1010sub7]\r\nParameterName=Save Device Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nSubNumber=8\r\nParameterName=Restore Default Parameters\r\nObjectType=0x08\r\n\r\n[1011sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x7\r\nPDOMapping=0\r\n\r\n[1011sub1]\r\nParameterName=Restore all Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub2]\r\nParameterName=Restore Communication Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub3]\r\nParameterName=Restore Device Profile Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub4]\r\nParameterName=Restore Axis 0 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub5]\r\nParameterName=Restore Axis 1 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1011sub6]\r\nParameterName=Restore Axis 2 Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011sub7]\r\nParameterName=Restore Device Default Parameters\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n[1015]\r\nParameterName=Inhibit Time Emergency\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1016]\r\nSubNumber=2\r\nParameterName=Heartbeat Consumer Entries\r\nObjectType=0x08\r\n\r\n[1016sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1016sub1]\r\nParameterName=Consumer Heartbeat Time 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018]\r\nSubNumber=5\r\nParameterName=Identity Object\r\nObjectType=0x09\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x4\r\nPDOMapping=0\r\n\r\n[1018sub1]\r\nParameterName=Vendor Id\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x555\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023]\r\nSubNumber=4\r\nParameterName=OS Command\r\nObjectType=0x09\r\n\r\n[1023sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x3\r\nPDOMapping=0\r\n\r\n[1023sub1]\r\nParameterName=Command\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=rw\r\nPDOMapping=0\r\nObjFlags=0x00000001\r\n\r\n[1023sub2]\r\nParameterName=Status\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1023sub3]\r\nParameterName=Reply\r\nObjectType=0x07\r\nDataType=0x000A\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1029]\r\nSubNumber=3\r\nParameterName=Error Behaviour\r\nObjectType=0x08\r\n\r\n[1029sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=ro\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[1029sub1]\r\nParameterName=Communication Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1029sub2]\r\nParameterName=Application Error\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1400]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1400sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1400sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1401]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1401sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1401sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1402]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1402sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1402sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFF\r\nPDOMapping=0\r\n\r\n[1403]\r\nSubNumber=3\r\nParameterName=Receive PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1403sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1403sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1600]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1600sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1600sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1601sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1601sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1602sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1602sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nSubNumber=4\r\nParameterName=Receive PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1603sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1603sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 1\r\nObjectType=0x09\r\n\r\n[1800sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1800sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1800sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[1801]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 2\r\nObjectType=0x09\r\n\r\n[1801sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1801sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1801sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 3\r\nObjectType=0x09\r\n\r\n[1802sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1802sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1802sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803]\r\nSubNumber=6\r\nParameterName=Transmit PDO Communication Parameter 4\r\nObjectType=0x09\r\n\r\n[1803sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=0x05\r\nPDOMapping=0\r\n\r\n[1803sub1]\r\nParameterName=COB-ID\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission Type\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0xFE\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1803sub4]\r\nParameterName=Compatibility Entry\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event Timer\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[1A00]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 1\r\nObjectType=0x09\r\n\r\n[1A00sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x01\r\nPDOMapping=0\r\n\r\n[1A00sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 2\r\nObjectType=0x09\r\n\r\n[1A01sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A01sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 3\r\nObjectType=0x09\r\n\r\n[1A02sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A02sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nSubNumber=4\r\nParameterName=Transmit PDO Mapping Parameter 4\r\nObjectType=0x09\r\n\r\n[1A03sub0]\r\nParameterName=Number of Entries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[1A03sub1]\r\nParameterName=Mapping Entry 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapping Entry 2\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapping Entry 3\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6040]\r\nParameterName=Controlword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6041]\r\nParameterName=Statusword 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[605A]\r\nParameterName=Quick Stop Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[605B]\r\nParameterName=Shutdown Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[605C]\r\nParameterName=Disable Operation Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605D]\r\nParameterName=Halt Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0x0001\r\nPDOMapping=0\r\n\r\n[605E]\r\nParameterName=Fault Reaction Option Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=ro\r\nDefaultValue=0x0002\r\nPDOMapping=0\r\n\r\n[6060]\r\nParameterName=Modes of Operation 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0x00\r\nPDOMapping=1\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6062]\r\nParameterName=Position Demand Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6063]\r\nParameterName=Position Actual Internal Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6064]\r\nParameterName=Position Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[6065]\r\nParameterName=Following Error Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6067]\r\nParameterName=Position Window 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0xFFFFFFFF\r\nPDOMapping=0\r\n\r\n[6068]\r\nParameterName=Position Window Time 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x0000\r\nPDOMapping=0\r\n\r\n[606A]\r\nParameterName=Sensor Selection Code 1\r\nObjectType=0x07\r\nDataType=0x0003\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[606C]\r\nParameterName=Velocity Actual Value 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target Position 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[607D]\r\nSubNumber=3\r\nParameterName=Software Position Limit 1\r\nObjectType=0x08\r\n\r\n[607Dsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Min Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=-2147483648\r\nPDOMapping=0\r\n\r\n[607Dsub2]\r\nParameterName=Max Software Position Limit\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=2147483647\r\nPDOMapping=0\r\n\r\n[6081]\r\nParameterName=Profile Velocity in pp-mode 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6082]\r\nParameterName=End velocity 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[6083]\r\nParameterName=Profile Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6084]\r\nParameterName=Profile Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6085]\r\nParameterName=Quick Stop Deceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608F]\r\nSubNumber=3\r\nParameterName=Position Encoder Resolution 1\r\nObjectType=0x08\r\n\r\n[608Fsub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x00000002\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder Increments\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[608Fsub2]\r\nParameterName=Motor Revolutions\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00000001\r\nPDOMapping=0\r\n\r\n[6098]\r\nParameterName=Homing Method 1\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[6099]\r\nSubNumber=3\r\nParameterName=Homing Speeds 1\r\nObjectType=0x08\r\n\r\n[6099sub0]\r\nParameterName=Highest sub-index supported\r\nObjectType=0x07\r\nDataType=5\r\nAccessType=const\r\nDefaultValue=0x2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Fast Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[6099sub2]\r\nParameterName=Slow Homing Speed\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[609A]\r\nParameterName=Homing Acceleration 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[60B0]\r\nParameterName=Position Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=0\r\n\r\n[60B1]\r\nParameterName=Velocity Offset 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60C2]\r\nSubNumber=3\r\nParameterName=Interpolation Time Period 1\r\nObjectType=0x09\r\n\r\n[60C2sub0]\r\nParameterName=NumOfEntries\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=const\r\nDefaultValue=0x02\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=timeUnits\r\nObjectType=0x07\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0x1\r\nPDOMapping=0\r\n\r\n[60C2sub2]\r\nParameterName=timeIndex\r\nObjectType=0x07\r\nDataType=0x0002\r\nAccessType=rw\r\nDefaultValue=-2\r\nPDOMapping=0\r\n\r\n[60F2]\r\nParameterName=Positioning Option Code 1\r\nObjectType=0x07\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x00\r\nPDOMapping=0\r\n\r\n[60FD]\r\nParameterName=Digital Inputs 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target Velocity 1\r\nObjectType=0x07\r\nDataType=0x0004\r\nAccessType=rw\r\nDefaultValue=0x0\r\nPDOMapping=1\r\n\r\n[6502]\r\nParameterName=Supported Drive Modes 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000000A5\r\nPDOMapping=0\r\n\r\n[67FF]\r\nParameterName=Single Device Type 1\r\nObjectType=0x07\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x00040192\r\nPDOMapping=0\r\n"
  },
  {
    "path": "canopen_tests/config/cia402_system/ros2_controllers.yaml",
    "content": "controller_manager:\n  ros__parameters:\n    update_rate: 10  # Hz\n\n    joint_state_broadcaster:\n      type: joint_state_broadcaster/JointStateBroadcaster\n\n    cia402_device_1_controller:\n      type: canopen_ros2_controllers/Cia402DeviceController\n\n    joint_trajectory_controller:\n      type: joint_trajectory_controller/JointTrajectoryController\n\n    forward_position_controller:\n      type: forward_command_controller/ForwardCommandController\n\ncia402_device_1_controller:\n  ros__parameters:\n    joint: node_1\n\nforward_position_controller:\n  ros__parameters:\n    joints:\n      - node_1\n    interface_name: position\n\njoint_trajectory_controller:\n  ros__parameters:\n    joints:\n      - node_1\n    command_interfaces:\n      - position\n    state_interfaces:\n      - position\n      - velocity\n    state_publish_rate: 100.0\n    action_monitor_rate: 20.0\n    allow_partial_joints_goal: false\n    constraints:\n      stopped_velocity_tolerance: 0.2\n      goal_time: 0.0\n      node_1: { trajectory: 0.2, goal: 0.1 }\n"
  },
  {
    "path": "canopen_tests/config/robot_control/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n  sync_period: 10000\n\njoint_1:\n  node_id: 2\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 10\n  position_mode: 1\n  revision_number: 0\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n    - {index: 0x6060, sub_index: 0, value: 7}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      #- {index: 0x60FF, sub_index: 0} # target velocity\n\njoint_2:\n  node_id: 3\n  dcf: \"cia402_slave.eds\"\n  driver: \"ros2_canopen::Cia402Driver\"\n  package: \"canopen_402_driver\"\n  period: 10\n  position_mode: 1\n  revision_number: 0\n  switching_state: 2\n  sdo:\n    - {index: 0x60C2, sub_index: 1, value: 50} # Set interpolation time for cyclic modes to 50 ms\n    - {index: 0x60C2, sub_index: 2, value: -3} # Set base 10-3s\n    - {index: 0x6081, sub_index: 0, value: 1000}\n    - {index: 0x6083, sub_index: 0, value: 2000}\n    - {index: 0x6060, sub_index: 0, value: 7}\n  tpdo: # TPDO needed statusword, actual velocity, actual position, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6041, sub_index: 0} # status word\n        - {index: 0x6061, sub_index: 0} # mode of operation display\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      transmission: 0x01\n      mapping:\n        - {index: 0x6064, sub_index: 0} # position actual value\n        - {index: 0x606c, sub_index: 0} # velocity actual position\n  rpdo: # RPDO needed controlword, target position, target velocity, mode of operation\n    1:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x6040, sub_index: 0} # controlword\n      - {index: 0x6060, sub_index: 0} # mode of operation\n    2:\n      enabled: true\n      cob_id: \"auto\"\n      mapping:\n      - {index: 0x607A, sub_index: 0} # target position\n      #- {index: 0x60FF, sub_index: 0} # target velocity\n"
  },
  {
    "path": "canopen_tests/config/robot_control/cia402_slave.eds",
    "content": "[FileInfo]\r\nCreatedBy=Eduard Prelipcean\r\nModifiedBy=Graure Iulian - Robert\r\nDescription=CANopen Technosoft\r\nCreationTime=01:51PM\r\nCreationDate=02-07-2022\r\nModificationTime=01:51PM\r\nModificationDate=02-07-2022\r\nFileName=iPOS.D.v1.04.eds\r\nFileVersion=0x01\r\nFileRevision=0x05\r\nEDSVersion=5\r\n\r\n[DeviceInfo]\r\nVendorName=Technosoft\r\nVendorNumber=0x000001A3\r\nProductName=iPOS\r\nBaudRate_10=0\r\nBaudRate_20=0\r\nBaudRate_50=0\r\nBaudRate_125=1\r\nBaudRate_250=1\r\nBaudRate_500=1\r\nBaudRate_800=0\r\nBaudRate_1000=1\r\nSimpleBootUpMaster=0\r\nSimpleBootUpSlave=1\r\nGranularity=8\r\nDynamicChannelsSupported=0\r\nCompactPDO=0\r\nGroupMessaging=0\r\nNrOfRXPDO=4\r\nNrOfTXPDO=4\r\nLSS_Supported=1\r\n\r\n[DummyUsage]\r\nDummy0001=0\r\nDummy0002=0\r\nDummy0003=0\r\nDummy0004=0\r\nDummy0005=0\r\nDummy0006=0\r\nDummy0007=0\r\n\r\n[Comments]\r\nLines=0\r\n\r\n[MandatoryObjects]\r\nSupportedObjects=3\r\n1=0x1000\r\n2=0x1001\r\n3=0x1018\r\n\r\n[1000]\r\nParameterName=Device type\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x60192\r\nPDOMapping=0\r\n\r\n\r\n[1001]\r\nParameterName=Error register\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n\r\n[1018]\r\nParameterName=Identity Object\r\nObjectType=0x9\r\nSubNumber=5\r\n\r\n[1018sub0]\r\nParameterName=number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=4\r\nPDOMapping=0\r\nLowLimit=1\r\nHighLimit=4\r\n\r\n[1018sub1]\r\nParameterName=Vendor ID\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x000001A3\r\nPDOMapping=0\r\n\r\n[1018sub2]\r\nParameterName=Product Code\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1018sub3]\r\nParameterName=Revision number\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[1018sub4]\r\nParameterName=Serial number\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n[OptionalObjects]\r\nSupportedObjects=102\r\n1=0x1002\r\n2=0x1003\r\n3=0x1005\r\n4=0x1006\r\n5=0x1008\r\n6=0x100A\r\n7=0x100C\r\n8=0x100D\r\n9=0x1010\r\n10=0x1011\r\n11=0x1013\r\n12=0x1014\r\n13=0x1017\r\n14=0x1200\r\n15=0x1400\r\n16=0x1401\r\n17=0x1402\r\n18=0x1403\r\n19=0x1600\r\n20=0x1601\r\n21=0x1602\r\n22=0x1603\r\n23=0x1800\r\n24=0x1801\r\n25=0x1802\r\n26=0x1803\r\n27=0x1A00\r\n28=0x1A01\r\n29=0x1A02\r\n30=0x1A03\r\n31=0x6007\r\n32=0x6040\r\n33=0x6041\r\n34=0x605A\r\n35=0x605B\r\n36=0x605C\r\n37=0x605D\r\n38=0x605E\r\n39=0x6060\r\n40=0x6061\r\n41=0x6062\r\n42=0x6063\r\n43=0x6064\r\n44=0x6065\r\n45=0x6066\r\n46=0x6067\r\n47=0x6068\r\n48=0x6069\r\n49=0x606B\r\n50=0x606C\r\n51=0x606F\r\n52=0x6071\r\n53=0x6075\r\n54=0x6077\r\n55=0x607A\r\n56=0x607B\r\n57=0x607C\r\n58=0x607D\r\n59=0x607E\r\n60=0x6081\r\n61=0x6083\r\n62=0x6085\r\n63=0x6086\r\n64=0x6087\r\n65=0x6089\r\n66=0x608A\r\n67=0x608B\r\n68=0x608C\r\n69=0x608D\r\n70=0x608E\r\n71=0x608F\r\n72=0x6091\r\n73=0x6092\r\n74=0x6093\r\n75=0x6094\r\n76=0x6096\r\n77=0x6097\r\n78=0x6098\r\n79=0x6099\r\n80=0x609A\r\n81=0x60A2\r\n82=0x60A8\r\n83=0x60A9\r\n84=0x60AA\r\n85=0x60AB\r\n86=0x60B8\r\n87=0x60B9\r\n88=0x60BA\r\n89=0x60BB\r\n90=0x60BC\r\n91=0x60BD\r\n92=0x60C0\r\n93=0x60C1\r\n94=0x60C2\r\n95=0x60F2\r\n96=0x60F4\r\n97=0x60F8\r\n98=0x60FC\r\n99=0x60FD\r\n100=0x60FE\r\n101=0x60FF\r\n102=0x6502\r\n\r\n[1002]\r\nParameterName=Manufacturer status register\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[1003]\r\nParameterName=Error Field\r\nObjectType=0x8\r\nSubNumber=6\r\n\r\n[1003sub0]\r\nParameterName=Number of errors in history\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=254\r\n\r\n[1003sub1]\r\nParameterName=Standard error field\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1003sub2]\r\nParameterName=Standard error field\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1003sub3]\r\nParameterName=Standard error field\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1003sub4]\r\nParameterName=Standard error field\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1003sub5]\r\nParameterName=Standard error field\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1005]\r\nParameterName=COB-ID SYNC Message\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x80\r\nPDOMapping=0\r\n\r\n\r\n[1006]\r\nParameterName=Communication cycle period\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n\r\n[1008]\r\nParameterName=Manufacturer device name\r\nObjectType=0x7\r\nDataType=0x0009\r\nAccessType=const\r\nDefaultValue=iPOS\r\nPDOMapping=0\r\n\r\n\r\n[100A]\r\nParameterName=Manufacturer software version\r\nObjectType=0x7\r\nDataType=0x0009\r\nAccessType=const\r\nPDOMapping=0\r\n\r\n\r\n[100C]\r\nParameterName=Guard time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n\r\n[100D]\r\nParameterName=Life time factor\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n\r\n[1010]\r\nParameterName=Store parameters\r\nObjectType=0x8\r\nSubNumber=2\r\n\r\n[1010sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=1\r\nHighLimit=1\r\n\r\n[1010sub1]\r\nParameterName=Save all Parameters\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1011]\r\nParameterName=Restore default parameters\r\nObjectType=0x8\r\nSubNumber=2\r\n\r\n[1011sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=1\r\nHighLimit=1\r\n\r\n[1011sub1]\r\nParameterName=Restore all default parameters\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n[1013]\r\nParameterName=High Resolution Time Stamp\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rwr\r\nDefaultValue=0x00000000\r\nPDOMapping=1\r\n\r\n\r\n[1014]\r\nParameterName=COB-ID EMCY Message\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80\r\nPDOMapping=0\r\n\r\n\r\n[1017]\r\nParameterName=Producer Heartbeat Time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n\r\n[1200]\r\nParameterName=Server SDO Parameter\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[1200sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=2\r\n\r\n[1200sub1]\r\nParameterName=COB-ID Client -> Server (rx)\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=$NODEID+0x600\r\nPDOMapping=0\r\n\r\n[1200sub2]\r\nParameterName=COB-ID Server -> Client (tx)\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=$NODEID+0x580\r\nPDOMapping=0\r\n\r\n[1400]\r\nParameterName=RPDO1 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[1400sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1400sub1]\r\nParameterName=COB-ID RPDO1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x200\r\nPDOMapping=0\r\n\r\n[1400sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1401]\r\nParameterName=RPDO2 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[1401sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1401sub1]\r\nParameterName=COB-ID RPDO2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x300\r\nPDOMapping=0\r\n\r\n[1401sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1402]\r\nParameterName=RPDO3 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[1402sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1402sub1]\r\nParameterName=COB-ID RPDO3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x400\r\nPDOMapping=0\r\n\r\n[1402sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1403]\r\nParameterName=RPDO4 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[1403sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1403sub1]\r\nParameterName=COB-ID RPDO4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x500\r\nPDOMapping=0\r\n\r\n[1403sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1600]\r\nParameterName=RPDO1 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1600sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1600sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1600sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1600sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601]\r\nParameterName=RPDO2 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1601sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1601sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1601sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60600008\r\nPDOMapping=0\r\n\r\n[1601sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1601sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602]\r\nParameterName=RPDO3 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1602sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1602sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1602sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x607A0020\r\nPDOMapping=0\r\n\r\n[1602sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1602sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603]\r\nParameterName=RPDO4 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1603sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1603sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60400010\r\nPDOMapping=0\r\n\r\n[1603sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60FF0020\r\nPDOMapping=0\r\n\r\n[1603sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1603sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1800]\r\nParameterName=TPDO1 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=5\r\n\r\n[1800sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=5\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1800sub1]\r\nParameterName=COB-ID TPDO1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x180\r\nPDOMapping=0\r\n\r\n[1800sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1800sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x012C\r\nPDOMapping=0\r\n\r\n[1800sub5]\r\nParameterName=Event timer\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1801]\r\nParameterName=TPDO2 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=5\r\n\r\n[1801sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=5\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1801sub1]\r\nParameterName=COB-ID TPDO2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x280\r\nPDOMapping=0\r\n\r\n[1801sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1801sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x012C\r\nPDOMapping=0\r\n\r\n[1801sub5]\r\nParameterName=Event timer\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1802]\r\nParameterName=TPDO3 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=5\r\n\r\n[1802sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=5\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1802sub1]\r\nParameterName=COB-ID TPDO3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000380\r\nPDOMapping=0\r\n\r\n[1802sub2]\r\nParameterName=Transmision type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1802sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x012C\r\nPDOMapping=0\r\n\r\n[1802sub5]\r\nParameterName=Event timer\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1803]\r\nParameterName=TPDO4 Communication Parameter\r\nObjectType=0x9\r\nSubNumber=5\r\n\r\n[1803sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=5\r\nPDOMapping=0\r\nLowLimit=2\r\nHighLimit=5\r\n\r\n[1803sub1]\r\nParameterName=COB-ID TPDO4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=$NODEID+0x80000480\r\nPDOMapping=0\r\n\r\n[1803sub2]\r\nParameterName=Transmission type\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=255\r\nPDOMapping=0\r\n\r\n[1803sub3]\r\nParameterName=Inhibit Time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0x012C\r\nPDOMapping=0\r\n\r\n[1803sub5]\r\nParameterName=Event timer\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\n\r\n[1A00]\r\nParameterName=TPDO1 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1A00sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1A00sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A00sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A00sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01]\r\nParameterName=TPDO2 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1A01sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1A01sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A01sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60610008\r\nPDOMapping=0\r\n\r\n[1A01sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A01sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02]\r\nParameterName=TPDO3 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1A02sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1A02sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A02sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60640020\r\nPDOMapping=0\r\n\r\n[1A02sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A02sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03]\r\nParameterName=TPDO4 Mapping Parameter\r\nObjectType=0x9\r\nSubNumber=9\r\n\r\n[1A03sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=8\r\n\r\n[1A03sub1]\r\nParameterName=Mapped object #1\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x60410010\r\nPDOMapping=0\r\n\r\n[1A03sub2]\r\nParameterName=Mapped object #2\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x606C0020\r\nPDOMapping=0\r\n\r\n[1A03sub3]\r\nParameterName=Mapped object #3\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03sub4]\r\nParameterName=Mapped object #4\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03sub5]\r\nParameterName=Mapped object #5\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03sub6]\r\nParameterName=Mapped object #6\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03sub7]\r\nParameterName=Mapped object #7\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[1A03sub8]\r\nParameterName=Mapped object #8\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x00000000\r\nPDOMapping=0\r\n\r\n[6007]\r\nParameterName=Abort connection option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n\r\n[6040]\r\nParameterName=Control word\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[6041]\r\nParameterName=Status word\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[605A]\r\nParameterName=Quick stop option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n[605B]\r\nParameterName=Shutdown option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n[605C]\r\nParameterName=Disable operation option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n[605D]\r\nParameterName=Halt option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=1\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n[605E]\r\nParameterName=Fault reaction option code\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rw\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n\r\n[6060]\r\nParameterName=Modes of Operation\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[6061]\r\nParameterName=Modes of Operation Display\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[6062]\r\nParameterName=Position demand value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n\r\n[6063]\r\nParameterName=Position actual internal value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n\r\n[6064]\r\nParameterName=Position actual value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n\r\n[6065]\r\nParameterName=Following error window\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[6066]\r\nParameterName=Following error time out\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[6067]\r\nParameterName=Position window\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[6068]\r\nParameterName=Position window time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[6069]\r\nParameterName=Velocity sensor actual value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[606B]\r\nParameterName=Velocity demand value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[606C]\r\nParameterName=Velocity actual value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[606F]\r\nParameterName=Velocity threshold\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[6071]\r\nParameterName=Target torque\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[6075]\r\nParameterName=Motor rated current\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6077]\r\nParameterName=Torque actual value\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[607A]\r\nParameterName=Target position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n\r\n[607B]\r\nParameterName=Position range limit\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[607Bsub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[607Bsub1]\r\nParameterName=Min position range limit\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[607Bsub2]\r\nParameterName=Max position range limit\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[607C]\r\nParameterName=Home offset\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n\r\n[607D]\r\nParameterName=Software position limit\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[607Dsub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[607Dsub1]\r\nParameterName=Minimal position limit\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[607Dsub2]\r\nParameterName=Maximal position limit\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[607E]\r\nParameterName=Polarity\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n[6081]\r\nParameterName=Profile velocity\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[6083]\r\nParameterName=Profile acceleration\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n\r\n[6085]\r\nParameterName=Quick stop deceleration\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n\r\n[6086]\r\nParameterName=Motion profile type\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n\r\n[6087]\r\nParameterName=Torque slope\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6089]\r\nParameterName=Position notation index\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[608A]\r\nParameterName=Position domension index\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n\r\n[608B]\r\nParameterName=Velocity notation index\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[608C]\r\nParameterName=Velocity dimension index\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n\r\n[608D]\r\nParameterName=Acceleration notation index\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[608E]\r\nParameterName=Acceleration dimension index\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n\r\n[608F]\r\nParameterName=Position encoder resolution\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[608Fsub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[608Fsub1]\r\nParameterName=Encoder increments\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[608Fsub2]\r\nParameterName=Motor revolutions\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6091]\r\nParameterName=Gear ratio\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6091sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6091sub1]\r\nParameterName=Motor shaft revolutions\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6091sub2]\r\nParameterName=Driving shaft revolutions\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6092]\r\nParameterName=Feed constant\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6092sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6092sub1]\r\nParameterName=Feed\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6092sub2]\r\nParameterName=Shaft revolutions\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6093]\r\nParameterName=Position factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6093sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6093sub1]\r\nParameterName=Position factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6093sub2]\r\nParameterName=Position factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6094]\r\nParameterName=Velocity encoder factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6094sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6094sub1]\r\nParameterName=Velocity encoder factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6094sub2]\r\nParameterName=Velocity encoder factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6096]\r\nParameterName=Velocity factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6096sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6096sub1]\r\nParameterName=Velocity factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6096sub2]\r\nParameterName=Velocity factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6097]\r\nParameterName=Acceleration factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6097sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6097sub1]\r\nParameterName=Acceleration factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6097sub2]\r\nParameterName=Acceleration factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[6098]\r\nParameterName=Homing method\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n\r\n[6099]\r\nParameterName=Homing speed\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[6099sub0]\r\nParameterName=number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[6099sub1]\r\nParameterName=Speed during search for switch\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n[6099sub2]\r\nParameterName=Speed during search for zero\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n[609A]\r\nParameterName=Homing acceleration\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[60A2]\r\nParameterName=Jerk factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[60A2sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[60A2sub1]\r\nParameterName=Jerk factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[60A2sub2]\r\nParameterName=Jerk factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[60A8]\r\nParameterName=SI unit position\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n[60A9]\r\nParameterName=SI unit velocity\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n[60AA]\r\nParameterName=SI unit acceleration\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n[60AB]\r\nParameterName=SI Unit jerk\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n[60B8]\r\nParameterName=Touch probe function\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60B9]\r\nParameterName=Touch probe status\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60BA]\r\nParameterName=Touch probe 1 positive edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60BB]\r\nParameterName=Touch probe 1 negative edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60BC]\r\nParameterName=Touch probe 2 positive edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60BD]\r\nParameterName=Touch probe 2 negative edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[60C0]\r\nParameterName=Interpolation sub mode select\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n\r\n[60C1]\r\nParameterName=Interpolation data record\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[60C1sub0]\r\nParameterName=number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[60C1sub1]\r\nParameterName=X1: the first parameter of ip function\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60C1sub2]\r\nParameterName=X2: the second parameter of ip function\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60C2]\r\nParameterName=Interpolation time period\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[60C2sub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[60C2sub1]\r\nParameterName=Interpolation time period value\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60C2sub2]\r\nParameterName=Interpolation time index\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60F2]\r\nParameterName=Positioning option code\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[60F4]\r\nParameterName=Following error actual value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[60F8]\r\nParameterName=Max slippage\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[60FC]\r\nParameterName=Position demand internal value\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n\r\n[60FD]\r\nParameterName=Digital inputs\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[60FE]\r\nParameterName=Digital outputs\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[60FEsub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\nLowLimit=1\r\nHighLimit=2\r\n\r\n[60FEsub1]\r\nParameterName=Physical outputs\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n[60FEsub2]\r\nParameterName=Bit mask\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n[60FF]\r\nParameterName=Target velocity\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[6502]\r\nParameterName=Supported drive modes\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nDefaultValue=0x001F0065\r\nPDOMapping=1\r\n\r\n\r\n[ManufacturerObjects]\r\nSupportedObjects=84\r\n1=0x2000\r\n2=0x2002\r\n3=0x2003\r\n4=0x2004\r\n5=0x2005\r\n6=0x2006\r\n7=0x2009\r\n8=0x2010\r\n9=0x2012\r\n10=0x2013\r\n11=0x2017\r\n12=0x2018\r\n13=0x2019\r\n14=0x201A\r\n15=0x201B\r\n16=0x201C\r\n17=0x201D\r\n18=0x2022\r\n19=0x2023\r\n20=0x2025\r\n21=0x2026\r\n22=0x2027\r\n23=0x2045\r\n24=0x2046\r\n25=0x2047\r\n26=0x2050\r\n27=0x2051\r\n28=0x2052\r\n29=0x2053\r\n30=0x2054\r\n31=0x2055\r\n32=0x2058\r\n33=0x2060\r\n34=0x2064\r\n35=0x2065\r\n36=0x2066\r\n37=0x2067\r\n38=0x2069\r\n39=0x206A\r\n40=0x206B\r\n41=0x206C\r\n42=0x206F\r\n43=0x2070\r\n44=0x2071\r\n45=0x2072\r\n46=0x2073\r\n47=0x2074\r\n48=0x2075\r\n49=0x2076\r\n50=0x2077\r\n51=0x2079\r\n52=0x207A\r\n53=0x207B\r\n54=0x207C\r\n55=0x207D\r\n56=0x207F\r\n57=0x2081\r\n58=0x2083\r\n59=0x2084\r\n60=0x2085\r\n61=0x2086\r\n62=0x2087\r\n63=0x2088\r\n64=0x208B\r\n65=0x208C\r\n66=0x208D\r\n67=0x208E\r\n68=0x208F\r\n69=0x2090\r\n70=0x2091\r\n71=0x2092\r\n72=0x20A0\r\n73=0x2100\r\n74=0x2101\r\n75=0x2102\r\n76=0x2103\r\n77=0x2104\r\n78=0x2105\r\n79=0x2106\r\n80=0x2107\r\n81=0x2108\r\n82=0x210B\r\n83=0x210F\r\n84=0x2110\r\n\r\n[2000]\r\nParameterName=Manufacturer Error Register\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2002]\r\nParameterName=Detailed Error Register\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n[2003]\r\nParameterName=Communication Error Register\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n[2004]\r\nParameterName=COB-ID High resolution time stamp\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0x100\r\nPDOMapping=0\r\n\r\n\r\n[2005]\r\nParameterName=Max slippage time out\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=0\r\n\r\n\r\n[2006]\r\nParameterName=Call TML function\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=wo\r\nPDOMapping=0\r\nLowLimit=1\r\nHighLimit=10\r\n\r\n\r\n[2009]\r\nParameterName=Detailed Error Register 2\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n[2010]\r\nParameterName=Master settings\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2012]\r\nParameterName=Master resolution\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[2013]\r\nParameterName=EGEAR multiplication factor\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[2013sub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[2013sub1]\r\nParameterName=EGEAR ratio numerator (slave)\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2013sub2]\r\nParameterName=EGEAR ratio denominator (master)\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2017]\r\nParameterName=Master actual position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[2018]\r\nParameterName=Master actual speed\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[2019]\r\nParameterName=CAM table load adress\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n\r\n[201A]\r\nParameterName=CAM table run adress\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n\r\n[201B]\r\nParameterName=CAM offset\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nDefaultValue=0\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=4294967295\r\n\r\n\r\n[201C]\r\nParameterName=External online reference\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nDefaultValue=0\r\nPDOMapping=1\r\n\r\n\r\n[201D]\r\nParameterName=External Reference Type\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n\r\n[2022]\r\nParameterName=Control effort\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[2023]\r\nParameterName=Jerk time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2025]\r\nParameterName=Stepper current in open-loop operation\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n\r\n[2026]\r\nParameterName=Stand-by current for stepper in open-loop operation\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-32768\r\nHighLimit=32767\r\n\r\n\r\n[2027]\r\nParameterName=Time out for stepper stand-by current\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2045]\r\nParameterName=Digital outputs status\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2046]\r\nParameterName=Analogue input: Reference\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2047]\r\nParameterName=Analogue input: Feedback\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2050]\r\nParameterName=Over-current protection level\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=32767\r\n\r\n\r\n[2051]\r\nParameterName=Over-current time out\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2052]\r\nParameterName=Motor nominal current\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=32767\r\n\r\n\r\n[2053]\r\nParameterName=I2t protection integrator limit\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=2147483647\r\n\r\n\r\n[2054]\r\nParameterName=I2t protection scaling factor\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rw\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2055]\r\nParameterName=Analogue input: DC-link voltage\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2058]\r\nParameterName=Analogue input for drive temperature\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n\r\n[2060]\r\nParameterName=Software version of TML application\r\nObjectType=0x7\r\nDataType=0x0009\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n\r\n[2064]\r\nParameterName=Read/Write configuration register\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0x84\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=2147483647\r\n\r\n\r\n[2065]\r\nParameterName=Write data at address set in 0x2064\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=wo\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=2147483647\r\n\r\n\r\n[2066]\r\nParameterName=Read data from address set in 0x2064\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[2067]\r\nParameterName=Write data at specified address\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=wo\r\nPDOMapping=1\r\n\r\n\r\n[2069]\r\nParameterName=Checksum configuration register\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rw\r\nPDOMapping=0\r\n\r\n\r\n[206A]\r\nParameterName=Checksum read register\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=0\r\n\r\n\r\n[206B]\r\nParameterName=CAM input scaling factor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0x00010000\r\nPDOMapping=1\r\n\r\n\r\n[206C]\r\nParameterName=CAM output scaling factor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=0x00010000\r\nPDOMapping=1\r\n\r\n\r\n[206F]\r\nParameterName=Time notation index\r\nObjectType=0x7\r\nDataType=0x0002\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=-128\r\nHighLimit=127\r\n\r\n\r\n[2070]\r\nParameterName=Time dimension index\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n\r\n[2071]\r\nParameterName=Time factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[2071sub0]\r\nParameterName=number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[2071sub1]\r\nParameterName=Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\n\r\n[2071sub2]\r\nParameterName=Feed constant\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\n\r\n[2072]\r\nParameterName=Interpolated position mode status\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n\r\n[2073]\r\nParameterName=Interpolated position buffer length\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=wo\r\nDefaultValue=7\r\nPDOMapping=0\r\n\r\n\r\n[2074]\r\nParameterName=Interpolated position buffer configuration\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=wo\r\nPDOMapping=0\r\n\r\n\r\n[2075]\r\nParameterName=Position triggers\r\nObjectType=0x8\r\nSubNumber=5\r\n\r\n[2075sub0]\r\nParameterName=Number of sub-indexes\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=4\r\nPDOMapping=0\r\n\r\n[2075sub1]\r\nParameterName=Position trigger 1\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2075sub2]\r\nParameterName=Position trigger 2\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2075sub3]\r\nParameterName=Position trigger 3\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2075sub4]\r\nParameterName=Position trigger 4\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2076]\r\nParameterName=Save current configuration\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=wo\r\nPDOMapping=0\r\n\r\n\r\n[2077]\r\nParameterName=Execute TML program\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=wo\r\nPDOMapping=0\r\n\r\n\r\n[2079]\r\nParameterName=Interpolated position initial position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n\r\n[207A]\r\nParameterName=Interpolated Position 1st order time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[207B]\r\nParameterName=Homing current threshold\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[207C]\r\nParameterName=Homing current threshold time\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[207D]\r\nParameterName=Dummy\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n[207F]\r\nParameterName=Current limit\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n[2081]\r\nParameterName=Set/change the actual motor position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=0\r\n\r\n[2083]\r\nParameterName=Encoder resolution\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2084]\r\nParameterName=Stepper resolution\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2085]\r\nParameterName=Position triggered outputs\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=65535\r\n\r\n[2086]\r\nParameterName=Speed Limitation for CSP\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=rww\r\nPDOMapping=0\r\n\r\n[2087]\r\nParameterName=Motor Speed\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2088]\r\nParameterName=Motor Position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[208B]\r\nParameterName=Sin signal AD value\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[208C]\r\nParameterName=Cos signal AD value\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[208D]\r\nParameterName=Auxiliary encoder position\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[208E]\r\nParameterName=Auxiliary Settings Register\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=0\r\n\r\n[208F]\r\nParameterName=Digital inputs 8b\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[208Fsub0]\r\nParameterName=Copy of Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[208Fsub1]\r\nParameterName=Copy of Digital inputs 8b Lo\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[208Fsub2]\r\nParameterName=Copy of Digital Inputs 8b Hi\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2090]\r\nParameterName=Digital outputs 8b\r\nObjectType=0x9\r\nSubNumber=3\r\n\r\n[2090sub0]\r\nParameterName=Copy of Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[2090sub1]\r\nParameterName=Copy of Physical outputs 8b\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2090sub2]\r\nParameterName=Copy of Bit mask 8b\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2091]\r\nParameterName=Lock EEPROM\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=0\r\nLowLimit=0\r\nHighLimit=255\r\n\r\n[2092]\r\nParameterName=User Variables\r\nObjectType=0x8\r\nSubNumber=5\r\n\r\n[2092sub0]\r\nParameterName=Number of sub-indexes\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=4\r\nPDOMapping=0\r\n\r\n[2092sub1]\r\nParameterName=UserVar1\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2092sub2]\r\nParameterName=UserVar2\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2092sub3]\r\nParameterName=UserVar3\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2092sub4]\r\nParameterName=UserVar4\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[20A0]\r\nParameterName=Load Position and Speed monitoring\r\nObjectType=0x9\r\nSubNumber=4\r\n\r\n[20A0sub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=3\r\nPDOMapping=0\r\n\r\n[20A0sub1]\r\nParameterName=Reserved\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n[20A0sub2]\r\nParameterName=Load Position Monitor\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n[20A0sub3]\r\nParameterName=Load Speed Monitor\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=-2147483648\r\nHighLimit=2147483647\r\n\r\n[2100]\r\nParameterName=Number of Steps per Revolution\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2101]\r\nParameterName=Number of microSteps per Step\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2102]\r\nParameterName=Brake status\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=1\r\nLowLimit=0\r\nHighLimit=1\r\n\r\n[2103]\r\nParameterName=Number of encoder Counts per Revolution\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2104]\r\nParameterName=Auxiliary encoder function\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2105]\r\nParameterName=Auxiliary encoder status\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2106]\r\nParameterName=Auxiliary encoder captured position positive edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2107]\r\nParameterName=Auxiliary encoder captured position negative edge\r\nObjectType=0x7\r\nDataType=0x0004\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[2108]\r\nParameterName=Filter variable 16 bit\r\nObjectType=0x9\r\nSubNumber=4\r\n\r\n[2108sub0]\r\nParameterName=Number of elements\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=3\r\nPDOMapping=0\r\n\r\n[2108sub1]\r\nParameterName=16bit variable address\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2108sub2]\r\nParameterName=Filter strength\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=1\r\n\r\n[2108sub3]\r\nParameterName=Filtered variable 16bit\r\nObjectType=0x7\r\nDataType=0x0003\r\nAccessType=ro\r\nPDOMapping=1\r\n\r\n[210B]\r\nParameterName=Auxiliary Settings Register 2\r\nObjectType=0x7\r\nDataType=0x0006\r\nAccessType=rww\r\nPDOMapping=0\r\n\r\n[210F]\r\nParameterName=Acceleration encoder factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[210Fsub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[210Fsub1]\r\nParameterName=Acceleration encoder factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[210Fsub2]\r\nParameterName=Acceleration encoder factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[2110]\r\nParameterName=Jerk encoder factor\r\nObjectType=0x8\r\nSubNumber=3\r\n\r\n[2110sub0]\r\nParameterName=Number of entries\r\nObjectType=0x7\r\nDataType=0x0005\r\nAccessType=ro\r\nDefaultValue=2\r\nPDOMapping=0\r\n\r\n[2110sub1]\r\nParameterName=Jerk encoder factor Numerator\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n\r\n[2110sub2]\r\nParameterName=Jerk encoder factor Divisor\r\nObjectType=0x7\r\nDataType=0x0007\r\nAccessType=rww\r\nDefaultValue=1\r\nPDOMapping=1\r\nHighLimit=4294967295\r\n"
  },
  {
    "path": "canopen_tests/config/robot_control/prbt_0_1.dcf",
    "content": "[FileInfo]\nCreatedBy=Dirk Osswald, SCHUNK GmbH & Co. KG\nModifiedBy=Pilz GmbH & Co. KG\nDescription=PRBT Electronic Data Sheet\nCreationTime=01:33PM\nCreationDate=05-23-2013\nModificationTime=00:00PM\nModificationDate=09-07-2018\nFileName=prbt_0_1.dcf\nFileVersion=0x03\nFileRevision=0x01\nEDSVersion=4.0\n\n[DeviceInfo]\nVendorName=Pilz GmbH & Co. KG\nOrderCode=0\nBaudRate_10=0\nBaudRate_20=0\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=0\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=8\nDynamicChannelsSupported=0\nCompactPDO=0\nGroupMessaging=0\nNrOfRXPDO=2\nNrOfTXPDO=4\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=0\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\n\n[Comments]\nLines=0\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[1000]\nParameterName=Device type\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\nObjFlags=0x0\n\n[1001]\nParameterName=Error register\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nPDOMapping=0\nObjFlags=0x0\n\n[1018]\nParameterName=Identity Object\nObjectType=0x9\nSubNumber=5\nObjFlags=0x0\n\n[1018sub0]\nParameterName=number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=4\nPDOMapping=0\nLowLimit=1\nHighLimit=4\nObjFlags=0\n\n[1018sub1]\nParameterName=Vendor ID\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\nObjFlags=0\n\n[1018sub2]\nParameterName=Product code\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\nObjFlags=0\n\n[1018sub3]\nParameterName=Revision number\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\nObjFlags=0\n\n[1018sub4]\nParameterName=Serial number\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\nObjFlags=0\n\n[OptionalObjects]\nSupportedObjects=62\n1=0x1002\n2=0x1003\n3=0x1005\n4=0x1008\n5=0x1009\n6=0x100A\n7=0x100C\n8=0x100D\n9=0x1014\n10=0x1016\n11=0x1017\n12=0x1200\n13=0x1400\n14=0x1401\n15=0x1600\n16=0x1601\n17=0x1800\n18=0x1801\n19=0x1802\n20=0x1803\n21=0x1A00\n22=0x1A01\n23=0x1A02\n24=0x1A03\n25=0x20A0\n26=0x6040\n27=0x6041\n28=0x6042\n29=0x6043\n30=0x6044\n31=0x6046\n32=0x6048\n33=0x6049\n34=0x604C\n35=0x6060\n36=0x6061\n37=0x6062\n38=0x6064\n39=0x6065\n40=0x606B\n41=0x606C\n42=0x6073\n43=0x6075\n44=0x6077\n45=0x607A\n46=0x607C\n47=0x607D\n48=0x6081\n49=0x6083\n50=0x6086\n51=0x6098\n52=0x60B2\n53=0x60C0\n54=0x60C1\n55=0x60C2\n56=0x60C3\n57=0x60C4\n58=0x60F4\n59=0x60FD\n60=0x60FE\n61=0x6502\n62=0x2060\n\n[1002]\nParameterName=Manufacturer Status Register\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=0\n\n[1003]\nParameterName=Pre-defined Error Field\nObjectType=0x8\nSubNumber=3\nObjFlags=0x0\n\n[1003sub0]\nParameterName=Number of Errors\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0\n\n[1003sub1]\nParameterName=Standard Error Field\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=0\nPDOMapping=0\nObjFlags=2\n\n[1003sub2]\nParameterName=Standard Error Field\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=0\nPDOMapping=0\nObjFlags=2\n\n[1005]\nParameterName=COB-ID SYNC message\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\nPDOMapping=0\nObjFlags=0x0\n\n[1008]\nParameterName=Manufacturer device name\nObjectType=0x7\nDataType=0x0009\nAccessType=const\nPDOMapping=0\nObjFlags=0x0\n\n[1009]\nParameterName=Manufacturer hardware version\nObjectType=0x7\nDataType=0x0009\nAccessType=const\nPDOMapping=0\nObjFlags=0x0\n\n[100A]\nParameterName=Manufacturer software version\nObjectType=0x7\nDataType=0x0009\nAccessType=const\nPDOMapping=0\nObjFlags=0x0\n\n[100C]\nParameterName=Guard time\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0x00000000\nPDOMapping=0\nObjFlags=0x0\n\n[100D]\nParameterName=Life time factor\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0x00000000\nPDOMapping=0\nObjFlags=0x0\n\n[1014]\nParameterName=COB-ID EMCY message\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x80\nPDOMapping=0\nObjFlags=0x0\n\n[1016]\nParameterName=Consumer Heartbeat Time\nObjectType=0x8\nSubNumber=4\nObjFlags=0x0\n\n[1016sub0]\nParameterName=Number of Entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=3\nPDOMapping=0\nLowLimit=1\nHighLimit=127\nObjFlags=0\n\n[1016sub1]\nParameterName=Consumer Heartbeat Time of Node-ID 1\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0\n\n[1016sub2]\nParameterName=Consumer Heartbeat Time of Node-ID 2\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0\n\n[1016sub3]\nParameterName=Consumer Heartbeat Time of Node-ID 3\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0\n\n[1017]\nParameterName=Producer heartbeat time\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0x00000000\nPDOMapping=0\nLowLimit=0\nHighLimit=32767\nObjFlags=0x0\nParameterValue=100\n\n[1200]\nParameterName=1. Server SDO parameter\nObjectType=0x9\nSubNumber=3\nObjFlags=0x0\n\n[1200sub0]\nParameterName=Number of supported Entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=2\nPDOMapping=0\nObjFlags=0\n\n[1200sub1]\nParameterName=COB-ID Client -> Server (rx)\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=$NodeID + 0x600\nPDOMapping=0\nObjFlags=0\n\n[1200sub2]\nParameterName=COB-ID Server -> Client (tx)\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=$NodeID + 0x580\nPDOMapping=0\nObjFlags=0\n\n[1400]\nParameterName=1. Receive PDO parameter\nObjectType=0x9\nSubNumber=3\nObjFlags=0x0\n\n[1400sub0]\nParameterName=Largest Sub-Index supported\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=2\nPDOMapping=0\nObjFlags=0\n\n[1400sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x200\nPDOMapping=0\nObjFlags=0\nParameterValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=Transmission Type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=255\nPDOMapping=0\nObjFlags=0\nParameterValue=0x1\n\n[1401]\nParameterName=2. Receive PDO Parameter\nObjectType=0x9\nSubNumber=3\nObjFlags=0x0\n\n[1401sub0]\nParameterName=Largest Sub-Index supported\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=2\nPDOMapping=0\nObjFlags=0\n\n[1401sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x300\nPDOMapping=0\nObjFlags=0\nParameterValue=$NODEID+0x300\n\n[1401sub2]\nParameterName=Transmission Type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=255\nPDOMapping=0\nObjFlags=0\nParameterValue=0x1\n\n[1600]\nParameterName=1. Receive PDO Mapping\nObjectType=0x9\nSubNumber=9\nObjFlags=0x0\n\n[1600sub0]\nParameterName=Number of mapped Application Objects\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=2\nPDOMapping=0\nLowLimit=0\nHighLimit=8\nObjFlags=0\nParameterValue=3\n\n[1600sub1]\nParameterName=1. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x60400010\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60400010\n\n[1600sub2]\nParameterName=2. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x60c10120\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60420010\n\n[1600sub3]\nParameterName=3. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60c10120\n\n[1600sub4]\nParameterName=4. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1600sub5]\nParameterName=5. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1600sub6]\nParameterName=6. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1600sub7]\nParameterName=7. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1600sub8]\nParameterName=8. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601]\nParameterName=2. Receive PDO mapping\nObjectType=0x9\nSubNumber=9\nObjFlags=0x0\n\n[1601sub0]\nParameterName=Number of mapped Application Objects\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=0\nHighLimit=8\nObjFlags=0\nParameterValue=2\n\n[1601sub1]\nParameterName=1. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\nParameterValue=0x607a0020\n\n[1601sub2]\nParameterName=2. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60810020\n\n[1601sub3]\nParameterName=3. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601sub4]\nParameterName=4. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601sub5]\nParameterName=5. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601sub6]\nParameterName=6. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601sub7]\nParameterName=7. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1601sub8]\nParameterName=8. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1800]\nParameterName=1. Transmit PDO Parameter\nObjectType=0x9\nSubNumber=4\nObjFlags=0x0\n\n[1800sub0]\nParameterName=Largest Sub-Index supported\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=5\nPDOMapping=0\nObjFlags=0\n\n[1800sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x180\nPDOMapping=0\nObjFlags=0\nParameterValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=1\nPDOMapping=0\nObjFlags=0\nParameterValue=0x1\n\n[1800sub5]\nParameterName=event timer\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=0\nHighLimit=32767\nObjFlags=0\n\n[1801]\nParameterName=2. Transmit PDO Parameter\nObjectType=0x9\nSubNumber=4\nObjFlags=0x0\n\n[1801sub0]\nParameterName=Largest Sub-Index supported\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=5\nPDOMapping=0\nObjFlags=0\n\n[1801sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x280\nPDOMapping=0\nObjFlags=0\n\n[1801sub2]\nParameterName=Transmission Type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=1\nPDOMapping=0\nObjFlags=0\n\n[1801sub5]\nParameterName=event timer\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0\n\n[1802]\nParameterName=3. Transmit PDO Parameter\nObjectType=0x9\nSubNumber=4\n\n[1802sub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=5\nPDOMapping=0\nLowLimit=0x02\nHighLimit=0x06\n\n[1802sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x380\nPDOMapping=0\nObjFlags=0\nParameterValue=$NODEID+0x380\n\n[1802sub2]\nParameterName=Transmission Type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=1\nPDOMapping=0\nParameterValue=0x1\n\n[1802sub5]\nParameterName=Event Timer\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[1803]\nParameterName=4. Transmit PDO Parameter\nObjectType=0x9\nSubNumber=4\n\n[1803sub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=5\nPDOMapping=0\nLowLimit=0x02\nHighLimit=0x06\n\n[1803sub1]\nParameterName=COB-ID used by PDO\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NodeID + 0x480\nPDOMapping=0\nObjFlags=0\n\n[1803sub2]\nParameterName=Transmission Type\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=254\nPDOMapping=0\n\n[1803sub5]\nParameterName=Event Timer\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[1A00]\nParameterName=1. Transmit PDO Mapping\nObjectType=0x9\nSubNumber=9\nObjFlags=0x0\n\n[1A00sub0]\nParameterName=Number of mapped Application Objects\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=3\nPDOMapping=0\nLowLimit=0\nHighLimit=8\nObjFlags=0\nParameterValue=2\n\n[1A00sub1]\nParameterName=1. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x60410010\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60410010\n\n[1A00sub2]\nParameterName=2. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x60770010\nPDOMapping=0\nObjFlags=0\nParameterValue=0x60610008\n\n[1A00sub3]\nParameterName=3. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x60640020\nPDOMapping=0\nObjFlags=0\n\n[1A00sub4]\nParameterName=4. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A00sub5]\nParameterName=5. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A00sub6]\nParameterName=6. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A00sub7]\nParameterName=7. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A00sub8]\nParameterName=8. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01]\nParameterName=2. Transmit PDO Mapping\nObjectType=0x9\nSubNumber=9\nObjFlags=0x0\n\n[1A01sub0]\nParameterName=Number of mapped Application Objects\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=2\nPDOMapping=0\nLowLimit=0\nHighLimit=8\nObjFlags=0\n\n[1A01sub1]\nParameterName=1. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x606b0020\nPDOMapping=0\nObjFlags=0\n\n[1A01sub2]\nParameterName=2. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x606c0020\nPDOMapping=0\nObjFlags=0\n\n[1A01sub3]\nParameterName=3. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01sub4]\nParameterName=4. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01sub5]\nParameterName=5. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01sub6]\nParameterName=6. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01sub7]\nParameterName=7. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A01sub8]\nParameterName=8. mapped Object\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nObjFlags=0\n\n[1A02]\nParameterName=3. Transmit PDO Mapping\nObjectType=0x9\nSubNumber=9\n\n[1A02sub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=0\nHighLimit=8\nParameterValue=2\n\n[1A02sub1]\nParameterName=PDO Mapping Entry\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nParameterValue=0x60640020\n\n[1A02sub2]\nParameterName=PDO Mapping Entry_2\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\nParameterValue=0x606c0020\n\n[1A02sub3]\nParameterName=PDO Mapping Entry_3\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A02sub4]\nParameterName=PDO Mapping Entry_4\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A02sub5]\nParameterName=PDO Mapping Entry_5\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A02sub6]\nParameterName=PDO Mapping Entry_6\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A02sub7]\nParameterName=PDO Mapping Entry_7\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A02sub8]\nParameterName=PDO Mapping Entry_8\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03]\nParameterName=4. Transmit PDO Mapping\nObjectType=0x9\nSubNumber=9\n\n[1A03sub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=0\nHighLimit=8\n\n[1A03sub1]\nParameterName=PDO Mapping Entry\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub2]\nParameterName=PDO Mapping Entry_2\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub3]\nParameterName=PDO Mapping Entry_3\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub4]\nParameterName=PDO Mapping Entry_4\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub5]\nParameterName=PDO Mapping Entry_5\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub6]\nParameterName=PDO Mapping Entry_6\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub7]\nParameterName=PDO Mapping Entry_7\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[1A03sub8]\nParameterName=PDO Mapping Entry_8\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[6040]\nParameterName=controlword\nObjectType=0x7\nDataType=0x0006\nAccessType=rww\nPDOMapping=1\n\n[6041]\nParameterName=statusword\nObjectType=0x7\nDataType=0x0006\nAccessType=ro\nPDOMapping=1\n\n[6042]\nParameterName=vl_target_velocity\nObjectType=0x7\nDataType=0x0003\nAccessType=rww\nDefaultValue=0\nPDOMapping=1\n\n[6043]\nParameterName=vl_velocity_demand\nObjectType=0x7\nDataType=0x0003\nAccessType=ro\nPDOMapping=1\n\n[6044]\nParameterName=vl_velocity_actual_value\nObjectType=0x7\nDataType=0x0003\nAccessType=ro\nPDOMapping=1\n\n[6046]\nParameterName=vl_velocity_min_max_amount\nObjectType=0x8\nSubNumber=3\n\n[6046sub0]\nParameterName=vl_velocity_min_max_amount_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[6046sub1]\nParameterName=vl_velocity_min_max_amount_vl_velocity_min_amount\nObjectType=0x7\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[6046sub2]\nParameterName=vl_velocity_min_max_amount_vl_velocity_max_amount\nObjectType=0x7\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[6048]\nParameterName=vl_velocity_acceleration\nObjectType=0x9\nSubNumber=3\n\n[6048sub0]\nParameterName=vl_velocity_acceleration_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[6048sub1]\nParameterName=vl_velocity_acceleration_delta_speed\nObjectType=0x7\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[6048sub2]\nParameterName=vl_velocity_acceleration_delta_time\nObjectType=0x7\nDataType=0x0006\nAccessType=rww\nPDOMapping=1\n\n[6049]\nParameterName=vl_velocity_deceleration\nObjectType=0x9\nSubNumber=3\n\n[6049sub0]\nParameterName=vl_velocity_deceleration_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[6049sub1]\nParameterName=vl_velocity_deceleration_delta_speed\nObjectType=0x7\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[6049sub2]\nParameterName=vl_velocity_deceleration_delta_time\nObjectType=0x7\nDataType=0x0006\nAccessType=rww\nPDOMapping=1\n\n[604C]\nParameterName=vl_dimension_factor\nObjectType=0x8\nSubNumber=3\n\n[604Csub0]\nParameterName=vl_dimension_factor_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[604Csub1]\nParameterName=vl_dimension_factor_numerator\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\nDefaultValue=1\nPDOMapping=0\n\n[604Csub2]\nParameterName=vl_dimension_factor_denominator\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\nDefaultValue=6000\nPDOMapping=0\n\n[6060]\nParameterName=modes_of_operation\nObjectType=0x7\nDataType=0x0002\nAccessType=rw\nPDOMapping=1\nParameterValue=7\n\n[6061]\nParameterName=modes_of_operation_display\nObjectType=0x7\nDataType=0x0002\nAccessType=ro\nPDOMapping=1\nObjFlags=0x1\n\n[6062]\nParameterName=position_demand_value\nObjectType=0x7\nDataType=0x0004\nAccessType=ro\nPDOMapping=1\n\n[6064]\nParameterName=position_actual_value\nObjectType=0x7\nDataType=0x0004\nAccessType=ro\nPDOMapping=1\n\n[6065]\nParameterName=following_error_window\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[606B]\nParameterName=velocity_demand_value\nObjectType=0x7\nDataType=0x0004\nAccessType=ro\nPDOMapping=1\n\n[606C]\nParameterName=velocity_actual_value\nObjectType=0x7\nDataType=0x0004\nAccessType=ro\nPDOMapping=1\n\n[6073]\nParameterName=max_current\nObjectType=0x7\nDataType=0x0006\nAccessType=rww\nPDOMapping=1\n\n[6075]\nParameterName=motor_rated_current\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[6077]\nParameterName=torque_actual_value\nObjectType=0x7\nDataType=0x0003\nAccessType=ro\nPDOMapping=1\n\n[607A]\nParameterName=target_position\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\nPDOMapping=1\n\n[607C]\nParameterName=home_offset\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[607D]\nParameterName=software_position_limit\nObjectType=0x8\nSubNumber=3\n\n[607Dsub0]\nParameterName=software_position_limit_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[607Dsub1]\nParameterName=software_position_limit_min_position_limit\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\n\n[607Dsub2]\nParameterName=software_position_limit_max_position_limit\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\n\n[6081]\nParameterName=profile_velocity\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=1\nDefaultValue=0x2710\n\n[6083]\nParameterName=profile_acceleration\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=1\n\n[6086]\nParameterName=motion_profile_type\nObjectType=0x7\nDataType=0x0003\nAccessType=rw\nPDOMapping=0\n\n[6098]\nParameterName=homing_method\nObjectType=0x7\nDataType=0x0002\nAccessType=const\nDefaultValue=0\nPDOMapping=0\nLowLimit=-128\nHighLimit=35\nParameterValue=0\n\n[60B2]\nParameterName=torque_offset\nObjectType=0x7\nDataType=0x0003\nAccessType=rww\nPDOMapping=1\n\n[60C0]\nParameterName=interpolation_sub_mode_select\nObjectType=0x7\nDataType=0x0003\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=-1\nHighLimit=0\nParameterValue=0\n\n[60C1]\nParameterName=interpolation_data_record\nObjectType=0x8\nSubNumber=2\n\n[60C1sub0]\nParameterName=interpolation_data_record_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=1\nPDOMapping=0\n\n[60C1sub1]\nParameterName=interpolation_data_record_setpoint_1\nObjectType=0x7\nDataType=0x0004\nAccessType=rww\nPDOMapping=1\n\n[60C2]\nParameterName=interpolation_time_period\nObjectType=0x9\nSubNumber=3\n\n[60C2sub0]\nParameterName=interpolation_time_period_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[60C2sub1]\nParameterName=interpolation_time_period_value\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=8\nPDOMapping=0\nParameterValue=10\n\n[60C2sub2]\nParameterName=interpolation_time_period_index\nObjectType=0x7\nDataType=0x0002\nAccessType=rw\nDefaultValue=-3\nPDOMapping=0\n\n[60C3]\nParameterName=interpolation_sync_definition\nObjectType=0x8\nSubNumber=3\n\n[60C3sub0]\nParameterName=interpolation_sync_definition_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[60C3sub1]\nParameterName=syncronize_on_group\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[60C3sub2]\nParameterName=ip_sync_every_n_event\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=1\nPDOMapping=0\nLowLimit=0\nHighLimit=255\n\n[60C4]\nParameterName=interpolation_data_configuration\nObjectType=0x9\nSubNumber=7\n\n[60C4sub0]\nParameterName=interpolation_data_configuration_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=6\nPDOMapping=0\n\n[60C4sub1]\nParameterName=interpolation_data_configuration_maximum_buffer_size\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=1\nPDOMapping=0\n\n[60C4sub2]\nParameterName=interpolation_data_configuration_actual_buffer_size\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[60C4sub3]\nParameterName=interpolation_data_configuration_buffer_organization\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nLowLimit=0\nHighLimit=1\n\n[60C4sub4]\nParameterName=interpolation_data_configuration_buffer_position\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\n\n[60C4sub5]\nParameterName=interpolation_data_configuration_size_of_data_record\nObjectType=0x7\nDataType=0x0005\nAccessType=wo\nDefaultValue=1\nPDOMapping=0\n\n[60C4sub6]\nParameterName=interpolation_data_configuration_buffer_clear\nObjectType=0x7\nDataType=0x0005\nAccessType=wo\nDefaultValue=0\nPDOMapping=0\n\n[60F4]\nParameterName=following_error_actual_value\nObjectType=0x7\nDataType=0x0004\nAccessType=ro\nPDOMapping=1\nObjFlags=0x0\n\n[60FD]\nParameterName=digital_inputs\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nPDOMapping=1\nObjFlags=0x2\n\n[60FE]\nParameterName=digital_outputs\nObjectType=0x8\nSubNumber=3\n\n[60FEsub0]\nParameterName=digital_outputs_highest_subindex\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\n\n[60FEsub1]\nParameterName=digital_outputs_physical_outputs\nObjectType=0x7\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\nObjFlags=2\n\n[60FEsub2]\nParameterName=digital_outputs_bit_mask\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nPDOMapping=0\n\n[6502]\nParameterName=supported_drive_modes\nObjectType=0x7\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000043\nPDOMapping=0\n\n[ManufacturerObjects]\nSupportedObjects=29\n1=0x2000\n2=0x2001\n3=0x2002\n4=0x2003\n5=0x2004\n6=0x2007\n7=0x2008\n8=0x2009\n9=0x200A\n10=0x200B\n11=0x200C\n12=0x200D\n13=0x200E\n14=0x2010\n15=0x2011\n16=0x2012\n17=0x2013\n18=0x2020\n19=0x2021\n20=0x2022\n21=0x2023\n22=0x2024\n23=0x2030\n24=0x2031\n25=0x2032\n26=0x2033\n27=0x2034\n28=0x2041\n29=0x2050\n\n[2000]\nParameterName=manufacturer_debug_flags\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nObjFlags=0x0\n\n[2001]\nParameterName=debug_values_int32\nObjectType=0x8\nSubNumber=5\n\n[2001sub0]\nParameterName=nb_debug_values_int32\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=4\nPDOMapping=0\n\n[2001sub1]\nParameterName=debug_value_int32_1\nObjectType=0x7\nDataType=0x0004\nAccessType=rwr\nPDOMapping=1\n\n[2001sub2]\nParameterName=debug_value_int32_2\nObjectType=0x7\nDataType=0x0004\nAccessType=rwr\nPDOMapping=1\n\n[2001sub3]\nParameterName=debug_value_int32_3\nObjectType=0x7\nDataType=0x0004\nAccessType=rwr\nPDOMapping=1\n\n[2001sub4]\nParameterName=debug_value_int32_4\nObjectType=0x7\nDataType=0x0004\nAccessType=rwr\nPDOMapping=1\n\n[2002]\nParameterName=debug_values_float\nObjectType=0x8\nSubNumber=5\n\n[2002sub0]\nParameterName=nb_debug_values_float\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=4\nPDOMapping=0\n\n[2002sub1]\nParameterName=debug_value_float_1\nObjectType=0x7\nDataType=0x0008\nAccessType=rwr\nPDOMapping=1\n\n[2002sub2]\nParameterName=debug_value_float_2\nObjectType=0x7\nDataType=0x0008\nAccessType=rwr\nPDOMapping=1\n\n[2002sub3]\nParameterName=debug_value_float_3\nObjectType=0x7\nDataType=0x0008\nAccessType=rwr\nPDOMapping=1\n\n[2002sub4]\nParameterName=debug_value_float_4\nObjectType=0x7\nDataType=0x0008\nAccessType=rwr\nPDOMapping=1\n\n[2003]\nParameterName=debug_message\nObjectType=0x7\nDataType=0x0009\nAccessType=ro\nPDOMapping=1\n\n[2004]\nParameterName=logging\nObjectType=0x9\nSubNumber=3\nObjFlags=0x3\n\n[2004sub0]\nParameterName=nb_logging\nObjectType=0x7\nDataType=0x0005\nAccessType=const\nDefaultValue=2\nPDOMapping=0\nObjFlags=3\n\n[2004sub1]\nParameterName=logging_state\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\nDefaultValue=0x8001\nPDOMapping=0\nObjFlags=3\n\n[2004sub2]\nParameterName=logging_trigger_time\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\nObjFlags=3\n\n[2007]\nParameterName=EEPROM_Parameters\nObjectType=0x9\nSubNumber=2\n\n[2007sub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=1\nPDOMapping=0\n\n[2007sub1]\nParameterName=SECT_CONFIG\nObjectType=0x7\nDataType=0x000a\nAccessType=ro\nPDOMapping=0\nObjFlags=3\n\n[2008]\nParameterName=Password\nObjectType=0x7\nDataType=0x0009\nAccessType=wo\nPDOMapping=0\nObjFlags=0x1\n\n[2009]\nParameterName=User\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=0\nPDOMapping=0\n\n[200A]\nParameterName=Disconnect_Reset\nObjectType=0x7\nDataType=0x0005\nAccessType=wo\nPDOMapping=0\nObjFlags=0x3\n\n[200B]\nParameterName=error_details\nObjectType=0x9\nSubNumber=4\nDataType=0x0008\nAccessType=ro\n\n[200Bsub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=3\nPDOMapping=0\n\n[200Bsub1]\nParameterName=detail\nObjectType=0x7\nDataType=0x0008\nAccessType=ro\nPDOMapping=0\n\n[200Bsub2]\nParameterName=file\nObjectType=0x7\nDataType=0x0009\nAccessType=ro\nPDOMapping=0\nObjFlags=2\n\n[200Bsub3]\nParameterName=line\nObjectType=0x7\nDataType=0x0006\nAccessType=ro\nPDOMapping=0\n\n[200C]\nParameterName=communication_mode\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nPDOMapping=0\n\n[200D]\nParameterName=pcb_temperature\nObjectType=0x9\nSubNumber=3\n\n[200Dsub0]\nParameterName=Number of entries\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=2\nPDOMapping=0\n\n[200Dsub1]\nParameterName=actual_pcb_temperature\nObjectType=0x7\nDataType=0x0008\nAccessType=ro\nPDOMapping=1\n\n[200Dsub2]\nParameterName=pcb_temperature_update_period_ms\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\nDefaultValue=20000\nPDOMapping=0\nLowLimit=1000\nHighLimit=3600000\n\n[200E]\nParameterName=sync_timeout_factor\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=6\nPDOMapping=0\n\n[2010]\nParameterName=KR_Current\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2011]\nParameterName=TN_Current\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2012]\nParameterName=TD_Current\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2013]\nParameterName=KC_Current\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2020]\nParameterName=KR_Speed\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2021]\nParameterName=TN_Speed\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2022]\nParameterName=TD_Speed\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2023]\nParameterName=KC_Speed\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2024]\nParameterName=KS_FeedForward\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2030]\nParameterName=KR_Pos\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2031]\nParameterName=TN_Pos\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2032]\nParameterName=TD_Pos\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2033]\nParameterName=KC_Pos\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2034]\nParameterName=KP_FeedForward\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2041]\nParameterName=Delta_Position\nObjectType=0x7\nDataType=0x0008\nAccessType=rw\nPDOMapping=0\n\n[2050]\nParameterName=extended_status\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=0\nPDOMapping=1\nObjFlags=0x1\n\n[20A0]\nParameterName=vendor_parameters_and_status\nObjectType=0x9\nSubNumber=8\n\n[20A0sub7]\nParameterName=run_permitted_status\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=0\nPDOMapping=1\nObjFlags=0x1\n\n[2060]\nParameterName=brake_test\nObjectType=0x9\nSubNumber=4\n\n[2060sub1]\nParameterName=brake_test_duration\nObjectType=0x7\nDataType=0x0006\nAccessType=ro\nDefaultValue=2500\nPDOMapping=0\nObjFlags=1\nParameterValue=2500\n\n\n[2060sub2]\nParameterName=start_brake_test\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\nDefaultValue=0\nPDOMapping=0\nParameterValue=0\n\n[2060sub3]\nParameterName=brake_test_status\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\nDefaultValue=0\nPDOMapping=0\nParameterValue=0\n"
  },
  {
    "path": "canopen_tests/config/robot_control/ros2_controllers.yaml",
    "content": "controller_manager:\n  ros__parameters:\n    update_rate: 100  # Hz\n    joint_state_broadcaster:\n      type: joint_state_broadcaster/JointStateBroadcaster\n\n    robot_controller:\n      type: canopen_ros2_controllers/Cia402RobotController\n\n    forward_position_controller:\n      type: forward_command_controller/ForwardCommandController\n\nrobot_controller:\n  ros__parameters:\n    joints:\n      - joint1\n      - joint2\n    operation_mode: 1\n    command_poll_freq: 5\n\nforward_position_controller:\n  ros__parameters:\n    joints:\n      - joint1\n      - joint2\n    interface_name: position\n\n# joint_trajectory_controller:\n#   ros__parameters:\n#     joints:\n#       - prbt_joint_1\n#       - prbt_joint_2\n#       - prbt_joint_3\n#       - prbt_joint_4\n#       - prbt_joint_5\n#       - prbt_joint_6\n#     command_interfaces:\n#       - position\n#     state_interfaces:\n#       - position\n#       - velocity\n#     state_publish_rate: 100.0\n#     action_monitor_rate: 20.0\n#     allow_partial_joints_goal: false\n#     constraints:\n#       stopped_velocity_tolerance: 0.2\n#       goal_time: 0.6\n#       stopped_velocity_tolerance: 0.05\n#       prbt_joint_1: {trajectory: 0.157, goal: 0.01}\n#       prbt_joint_2: {trajectory: 0.157, goal: 0.01}\n#       prbt_joint_3: {trajectory: 0.157, goal: 0.01}\n#       prbt_joint_4: {trajectory: 0.157, goal: 0.01}\n#       prbt_joint_5: {trajectory: 0.157, goal: 0.01}\n#       prbt_joint_6: {trajectory: 0.157, goal: 0.01}\n"
  },
  {
    "path": "canopen_tests/config/simple/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::ProxyDriver\"\n  package: \"canopen_proxy_driver\"\n  polling: true\n  period: 10\n  boot_timeout_ms: 1000\n  # namespace: \"/test1\"\n\nproxy_device_2:\n  node_id: 3\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::ProxyDriver\"\n  package: \"canopen_proxy_driver\"\n  polling: true\n  period: 10\n  boot_timeout_ms: 1000\n  # namespace: \"/test2\"\n"
  },
  {
    "path": "canopen_tests/config/simple/simple.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=11\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1A00\n\n[ManufacturerObjects]\nSupportedObjects=5\n1=0x4000\n2=0x4001\n3=0x4002\n4=0x4003\n5=0x4004\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[4002]\nParameterName=INTEGER32 test\nDataType=0x0004\nAccessType=rw\n\n[4003]\nParameterName=INTEGER16 test\nDataType=0x0003\nAccessType=rw\n\n[4004]\nParameterName=Test Data\nObjectType=0x9\nSubNumber=0x8\n\n[4004sub0]\nParameterName=Highest sub-index supported\nObjectType=0x7\nDataType=0x0005\nAccessType=ro\n\n[4004sub1]\nParameterName=BOOL test data\nObjectType=0x7\nDataType=0x0001\nAccessType=rw\n\n[4004sub2]\nParameterName=SIGNED8 test data\nObjectType=0x7\nDataType=0x0002\nAccessType=rw\n\n[4004sub3]\nParameterName=SIGNED16 test data\nObjectType=0x7\nDataType=0x0003\nAccessType=rw\n\n[4004sub4]\nParameterName=SIGNED32 test data\nObjectType=0x7\nDataType=0x0004\nAccessType=rw\n\n[4004sub5]\nParameterName=UNSIGNED8 test data\nObjectType=0x7\nDataType=0x0005\nAccessType=rw\n\n[4004sub6]\nParameterName=UNSIGNED16 test data\nObjectType=0x7\nDataType=0x0006\nAccessType=rw\n\n[4004sub7]\nParameterName=UNSIGNED32 test data\nObjectType=0x7\nDataType=0x0007\nAccessType=rw\n"
  },
  {
    "path": "canopen_tests/config/simple_diagnostics/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::MasterDriver\"\n  package: \"canopen_master_driver\"\n\ndefaults:\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::ProxyDriver\"\n  package: \"canopen_proxy_driver\"\n  polling: true\n  period: 10\n  diagnostics:\n    enable: true\n    period: 1000 # in milliseconds\n\nnodes:\n  proxy_device_1:\n    node_id: 2\n  proxy_device_2:\n    node_id: 3\n"
  },
  {
    "path": "canopen_tests/config/simple_diagnostics/simple.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=11\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1A00\n\n[ManufacturerObjects]\nSupportedObjects=4\n1=0x4000\n2=0x4001\n3=0x4002\n4=0x4003\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n\n[4002]\nParameterName=INTEGER32 test\nDataType=0x0004\nAccessType=rw\n\n[4003]\nParameterName=INTEGER16 test\nDataType=0x0003\nAccessType=rw\n"
  },
  {
    "path": "canopen_tests/config/simple_lifecycle/bus.yml",
    "content": "options:\n  dcf_path: \"@BUS_CONFIG_PATH@\"\n\nmaster:\n  node_id: 1\n  driver: \"ros2_canopen::LifecycleMasterDriver\"\n  package: \"canopen_master_driver\"\n\nproxy_device_1:\n  node_id: 2\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::LifecycleProxyDriver\"\n  package: \"canopen_proxy_driver\"\n\nproxy_device_2:\n  node_id: 3\n  dcf: \"simple.eds\"\n  driver: \"ros2_canopen::LifecycleProxyDriver\"\n  package: \"canopen_proxy_driver\"\n"
  },
  {
    "path": "canopen_tests/config/simple_lifecycle/simple.eds",
    "content": "[DeviceInfo]\nVendorName=Lely Industries N.V.\nVendorNumber=0x00000360\nProductName=\nProductNumber=0x00000000\nRevisionNumber=0x00000000\nOrderCode=\nBaudRate_10=1\nBaudRate_20=1\nBaudRate_50=1\nBaudRate_125=1\nBaudRate_250=1\nBaudRate_500=1\nBaudRate_800=1\nBaudRate_1000=1\nSimpleBootUpMaster=0\nSimpleBootUpSlave=1\nGranularity=1\nDynamicChannelsSupported=0\nGroupMessaging=0\nNrOfRxPDO=1\nNrOfTxPDO=1\nLSS_Supported=1\n\n[DummyUsage]\nDummy0001=1\nDummy0002=1\nDummy0003=1\nDummy0004=1\nDummy0005=1\nDummy0006=1\nDummy0007=1\nDummy0010=1\nDummy0011=1\nDummy0012=1\nDummy0013=1\nDummy0014=1\nDummy0015=1\nDummy0016=1\nDummy0018=1\nDummy0019=1\nDummy001A=1\nDummy001B=1\n\n[MandatoryObjects]\nSupportedObjects=3\n1=0x1000\n2=0x1001\n3=0x1018\n\n[OptionalObjects]\nSupportedObjects=11\n1=0x1003\n2=0x1005\n3=0x1014\n4=0x1015\n5=0x1016\n6=0x1017\n7=0x1029\n8=0x1400\n9=0x1600\n10=0x1800\n11=0x1A00\n\n[ManufacturerObjects]\nSupportedObjects=2\n1=0x4000\n2=0x4001\n\n[1000]\nParameterName=Device type\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000000\n\n[1001]\nParameterName=Error register\nDataType=0x0005\nAccessType=ro\n\n[1003]\nParameterName=Pre-defined error field\nObjectType=0x08\nDataType=0x0007\nAccessType=ro\nCompactSubObj=254\n\n[1005]\nParameterName=COB-ID SYNC message\nDataType=0x0007\nAccessType=rw\nDefaultValue=0x00000080\n\n[1014]\nParameterName=COB-ID EMCY\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x80\n\n[1015]\nParameterName=Inhibit time EMCY\nDataType=0x0006\nAccessType=rw\nDefaultValue=0\n\n[1016]\nParameterName=Consumer heartbeat time\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1017]\nParameterName=Producer heartbeat time\nDataType=0x0006\nAccessType=rw\n\n[1018]\nSubNumber=5\nParameterName=Identity object\nObjectType=0x09\n\n[1018sub0]\nParameterName=Highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=4\n\n[1018sub1]\nParameterName=Vendor-ID\nDataType=0x0007\nAccessType=ro\nDefaultValue=0x00000360\n\n[1018sub2]\nParameterName=Product code\nDataType=0x0007\nAccessType=ro\n\n[1018sub3]\nParameterName=Revision number\nDataType=0x0007\nAccessType=ro\n\n[1018sub4]\nParameterName=Serial number\nDataType=0x0007\nAccessType=ro\n\n[1029]\nParameterName=Error behavior object\nObjectType=0x08\nDataType=0x0005\nAccessType=rw\nCompactSubObj=1\n\n[1400]\nSubNumber=6\nParameterName=RPDO communication parameter\nObjectType=0x09\n\n[1400sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=5\n\n[1400sub1]\nParameterName=COB-ID used by RPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x200\n\n[1400sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1400sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1400sub4]\nParameterName=compatibility entry\nDataType=0x0005\nAccessType=rw\n\n[1400sub5]\nParameterName=event-timer\nDataType=0x0006\nAccessType=rw\n\n[1600]\nParameterName=RPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1600Value]\nNrOfEntries=1\n1=0x40000020\n\n[1800]\nSubNumber=7\nParameterName=TPDO communication parameter\nObjectType=0x09\n\n[1800sub0]\nParameterName=highest sub-index supported\nDataType=0x0005\nAccessType=const\nDefaultValue=6\n\n[1800sub1]\nParameterName=COB-ID used by TPDO\nDataType=0x0007\nAccessType=rw\nDefaultValue=$NODEID+0x180\n\n[1800sub2]\nParameterName=transmission type\nDataType=0x0005\nAccessType=rw\nDefaultValue=0xFF\n\n[1800sub3]\nParameterName=inhibit time\nDataType=0x0006\nAccessType=rw\n\n[1800sub4]\nParameterName=reserved\nDataType=0x0005\nAccessType=rw\n\n[1800sub5]\nParameterName=event timer\nDataType=0x0006\nAccessType=rw\n\n[1800sub6]\nParameterName=SYNC start value\nDataType=0x0005\nAccessType=rw\n\n[1A00]\nParameterName=TPDO mapping parameter\nObjectType=0x08\nDataType=0x0007\nAccessType=rw\nCompactSubObj=1\n\n[1A00Value]\nNrOfEntries=1\n1=0x40010020\n\n[4000]\nParameterName=UNSIGNED32 received by slave\nDataType=0x0007\nAccessType=rww\nPDOMapping=1\n\n[4001]\nParameterName=UNSIGNED32 sent from slave\nDataType=0x0007\nAccessType=rwr\nPDOMapping=1\n"
  },
  {
    "path": "canopen_tests/launch/analyzers/cia402_diagnostic_analyzer.yaml",
    "content": "analyzers:\n  ros__parameters:\n    path: Aggregation\n    cia402_device_1:\n      type: diagnostic_aggregator/GenericAnalyzer\n      path: Cia402Device1\n      contains: [ 'cia402_device_1' ]\n    cia402_device_2:\n      type: diagnostic_aggregator/GenericAnalyzer\n      path: Cia402Device2\n      contains: [ 'cia402_device_2' ]\n    cia402_device_3:\n      type: diagnostic_aggregator/GenericAnalyzer\n      path: Cia402Device3\n      contains: [ 'cia402_device_3' ]\n"
  },
  {
    "path": "canopen_tests/launch/analyzers/proxy_diagnostic_analyzer.yaml",
    "content": "analyzers:\n  ros__parameters:\n    path: Aggregation\n    proxy_device_1:\n      type: diagnostic_aggregator/GenericAnalyzer\n      path: ProxyDevice1\n      contains: [ 'proxy_device_1' ]\n    proxy_device_2:\n      type: diagnostic_aggregator/GenericAnalyzer\n      path: ProxyDevice2\n      contains: [ 'proxy_device_2' ]\n"
  },
  {
    "path": "canopen_tests/launch/canopen_system.launch.py",
    "content": "# Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions are met:\n#\n#    * Redistributions of source code must retain the above copyright\n#      notice, this list of conditions and the following disclaimer.\n#\n#    * Redistributions in binary form must reproduce the above copyright\n#      notice, this list of conditions and the following disclaimer in the\n#      documentation and/or other materials provided with the distribution.\n#\n#    * Neither the name of the {copyright_holder} nor the names of its\n#      contributors may be used to endorse or promote products derived from\n#      this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE\n# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n#\n# Author: Lovro Ivanov lovro.ivanov@gmail.com\n\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.actions import OpaqueFunction\nfrom launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\nfrom launch_ros.actions import Node\nfrom launch_ros.substitutions import FindPackageShare\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef launch_setup(context, *args, **kwargs):\n\n    name = LaunchConfiguration(\"name\")\n    prefix = LaunchConfiguration(\"prefix\")\n\n    # bus configuration\n    bus_config_package = LaunchConfiguration(\"bus_config_package\")\n    bus_config_directory = LaunchConfiguration(\"bus_config_directory\")\n    bus_config_file = LaunchConfiguration(\"bus_config_file\")\n    # bus configuration file full path\n    bus_config = PathJoinSubstitution(\n        [FindPackageShare(bus_config_package), bus_config_directory, bus_config_file]\n    )\n\n    # master configuration\n    master_config_package = LaunchConfiguration(\"master_config_package\")\n    master_config_directory = LaunchConfiguration(\"master_config_directory\")\n    master_config_file = LaunchConfiguration(\"master_config_file\")\n    # master configuration file full path\n    master_config = PathJoinSubstitution(\n        [FindPackageShare(master_config_package), master_config_directory, master_config_file]\n    )\n\n    # can interface name\n    can_interface_name = LaunchConfiguration(\"can_interface_name\")\n\n    # robot description stuff\n    description_package = LaunchConfiguration(\"description_package\")\n    description_file = LaunchConfiguration(\"description_file\")\n    robot_description_content = Command(\n        [\n            PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n            \" \",\n            PathJoinSubstitution(\n                [FindPackageShare(description_package), \"urdf\", \"canopen_system\", description_file]\n            ),\n            \" \",\n            \"name:=\",\n            name,\n            \" \",\n            \"prefix:=\",\n            prefix,\n            \" \",\n            \"bus_config:=\",\n            bus_config,\n            \" \",\n            \"master_config:=\",\n            master_config,\n            \" \",\n            \"can_interface_name:=\",\n            can_interface_name,\n            \" \",\n        ]\n    )\n    robot_description = {\"robot_description\": robot_description_content}\n\n    # ros2 control configuration\n    ros2_control_config_package = LaunchConfiguration(\"ros2_control_config_package\")\n    ros2_control_config_directory = LaunchConfiguration(\"ros2_control_config_directory\")\n    ros2_control_config_file = LaunchConfiguration(\"ros2_control_config_file\")\n    # ros2 control configuration file full path\n    ros2_control_config = PathJoinSubstitution(\n        [\n            FindPackageShare(ros2_control_config_package),\n            ros2_control_config_directory,\n            ros2_control_config_file,\n        ]\n    )\n\n    # nodes to start are listed below\n    control_node = Node(\n        package=\"controller_manager\",\n        executable=\"ros2_control_node\",\n        parameters=[robot_description, ros2_control_config],\n        output=\"screen\",\n    )\n\n    # load one controller just to make sure it can connect to controller_manager\n    joint_state_broadcaster_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"joint_state_broadcaster\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    canopen_proxy_controller_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"node_1_controller\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    robot_state_publisher_node = Node(\n        package=\"robot_state_publisher\",\n        executable=\"robot_state_publisher\",\n        output=\"both\",\n        parameters=[robot_description],\n    )\n\n    # hardcoded slave configuration form test package\n    slave_config = PathJoinSubstitution(\n        [FindPackageShare(master_config_package), master_config_directory, \"simple.eds\"]\n    )\n\n    slave_launch = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_fake_slaves\"), \"launch\", \"basic_slave.launch.py\"]\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_3\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    nodes_to_start = [\n        control_node,\n        robot_state_publisher_node,\n        joint_state_broadcaster_spawner,\n        slave_node_1,\n        slave_node_2,\n        canopen_proxy_controller_spawner,\n    ]\n\n    return nodes_to_start\n\n\ndef generate_launch_description():\n\n    declared_arguments = []\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"name\", description=\"robot name\", default_value=\"canopen_test_system\"\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\"prefix\", description=\"Prefix.\", default_value=\"\")\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_package\",\n            description=\"Package where urdf file is stored.\",\n            default_value=\"canopen_tests\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_file\",\n            description=\"Name of the urdf file.\",\n            default_value=\"canopen_system.urdf.xacro\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_directory\",\n            default_value=\"config/canopen_system\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_file\",\n            default_value=\"ros2_controllers.yaml\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_directory\",\n            default_value=\"config/canopen_system\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_file\",\n            default_value=\"bus.yml\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_directory\",\n            default_value=\"config/canopen_system\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_file\",\n            default_value=\"master.dcf\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"can_interface_name\",\n            default_value=\"vcan0\",\n            description=\"Interface name for can\",\n        )\n    )\n\n    return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])\n"
  },
  {
    "path": "canopen_tests/launch/cia402_diagnostics_setup.launch.py",
    "content": "# Copyright 2023 ROS-Industrial\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nimport launch_ros\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"config\",\n        \"cia402_diagnostics\",\n        \"cia402_slave.eds\",\n    )\n\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/cia402_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"cia402_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/cia402_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"cia402_node_2\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n    slave_node_3 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/cia402_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"4\",\n            \"node_name\": \"cia402_node_4\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n    master_bin_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"config\",\n        \"cia402_diagnostics\",\n        \"master.bin\",\n    )\n    if not os.path.exists(master_bin_path):\n        master_bin_path = \"\"\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402_diagnostics\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": master_bin_path,\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402_diagnostics\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    diagnostics_analyzer_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"launch\",\n        \"analyzers\",\n        \"cia402_diagnostic_analyzer.yaml\",\n    )\n\n    diagnostics_aggregator_node = launch_ros.actions.Node(\n        package=\"diagnostic_aggregator\",\n        executable=\"aggregator_node\",\n        output=\"screen\",\n        parameters=[diagnostics_analyzer_path],\n    )\n\n    return LaunchDescription(\n        [slave_node_1, slave_node_2, slave_node_3, device_container, diagnostics_aggregator_node]\n    )\n"
  },
  {
    "path": "canopen_tests/launch/cia402_lifecycle_setup.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"cia402\", \"cia402_slave.eds\"\n    )\n\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/cia402_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"cia402_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n    master_bin_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"config\",\n        \"cia402_lifecycle\",\n        \"master.bin\",\n    )\n    if not os.path.exists(master_bin_path):\n        master_bin_path = \"\"\n\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402_lifecycle\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": master_bin_path,\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402_lifecycle\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    return LaunchDescription([slave_node_1, device_container])\n"
  },
  {
    "path": "canopen_tests/launch/cia402_namespaced_system.launch.py",
    "content": "# Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions are met:\n#\n#    * Redistributions of source code must retain the above copyright\n#      notice, this list of conditions and the following disclaimer.\n#\n#    * Redistributions in binary form must reproduce the above copyright\n#      notice, this list of conditions and the following disclaimer in the\n#      documentation and/or other materials provided with the distribution.\n#\n#    * Neither the name of the {copyright_holder} nor the names of its\n#      contributors may be used to endorse or promote products derived from\n#      this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE\n# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n#\n# Author: Lovro Ivanov lovro.ivanov@gmail.com\n\nfrom launch import LaunchDescription\nimport launch.actions\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.actions import OpaqueFunction\nfrom launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\nfrom launch_ros.actions import Node\nfrom launch_ros.substitutions import FindPackageShare\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\nfrom nav2_common.launch import ReplaceString\nfrom launch.actions import GroupAction\nfrom launch_ros.actions import PushROSNamespace\n\n\ndef launch_setup(context, *args, **kwargs):\n\n    name = LaunchConfiguration(\"name\")\n    prefix = LaunchConfiguration(\"prefix\")\n\n    bot_ns = LaunchConfiguration(\"bot_ns\")\n\n    # bus configuration\n    bus_config_package = LaunchConfiguration(\"bus_config_package\")\n    bus_config_directory = LaunchConfiguration(\"bus_config_directory\")\n    bus_config_file = LaunchConfiguration(\"bus_config_file\")\n    # bus configuration file full path\n    bus_config = PathJoinSubstitution(\n        [FindPackageShare(bus_config_package), bus_config_directory, bus_config_file]\n    )\n\n    # master configuration\n    master_config_package = LaunchConfiguration(\"master_config_package\")\n    master_config_directory = LaunchConfiguration(\"master_config_directory\")\n    master_config_file = LaunchConfiguration(\"master_config_file\")\n    # master configuration file full path\n    master_config = PathJoinSubstitution(\n        [FindPackageShare(master_config_package), master_config_directory, master_config_file]\n    )\n\n    # can interface name\n    can_interface_name = LaunchConfiguration(\"can_interface_name\")\n\n    # robot description stuff\n    description_package = LaunchConfiguration(\"description_package\")\n    description_file = LaunchConfiguration(\"description_file\")\n    robot_description_content = Command(\n        [\n            PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n            \" \",\n            PathJoinSubstitution(\n                [FindPackageShare(description_package), \"urdf\", \"cia402_system\", description_file]\n            ),\n            \" \",\n            \"name:=\",\n            name,\n            \" \",\n            \"prefix:=\",\n            prefix,\n            \" \",\n            \"bus_config:=\",\n            bus_config,\n            \" \",\n            \"master_config:=\",\n            master_config,\n            \" \",\n            \"can_interface_name:=\",\n            can_interface_name,\n            \" \",\n        ]\n    )\n    robot_description = {\"robot_description\": robot_description_content}\n\n    # ros2 control configuration\n    ros2_control_config_package = LaunchConfiguration(\"ros2_control_config_package\")\n    ros2_control_config_directory = LaunchConfiguration(\"ros2_control_config_directory\")\n    ros2_control_config_file = LaunchConfiguration(\"ros2_control_config_file\")\n    # ros2 control configuration file full path\n    ros2_control_config = PathJoinSubstitution(\n        [\n            FindPackageShare(ros2_control_config_package),\n            ros2_control_config_directory,\n            ros2_control_config_file,\n        ]\n    )\n\n    # Our controllers get their names from the control config, so we have to\n    # include their namespace here to get them to start up within it.\n    ros2_control_config = ReplaceString(\n        source_file=ros2_control_config, replacements={\"__namespace__/\": (bot_ns, \"/\")}\n    )\n\n    # nodes to start are listed below\n    control_node = Node(\n        package=\"controller_manager\",\n        executable=\"ros2_control_node\",\n        parameters=[robot_description, ros2_control_config],\n        output=\"screen\",\n    )\n\n    # load one controller just to make sure it can connect to controller_manager\n    joint_state_broadcaster_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"joint_state_broadcaster\"],\n    )\n\n    cia402_device_controller_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\n            \"cia402_device_1_controller\",\n        ],\n    )\n\n    forward_position_controller = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\n            \"forward_position_controller\",\n        ],\n    )\n\n    robot_state_publisher_node = Node(\n        package=\"robot_state_publisher\",\n        executable=\"robot_state_publisher\",\n        output=\"both\",\n        parameters=[robot_description],\n    )\n\n    # hardcoded slave configuration form test package\n    slave_config = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"config/cia402\", \"cia402_slave.eds\"]\n    )\n\n    slave_launch = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_fake_slaves\"), \"launch\", \"cia402_slave.launch.py\"]\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"cia402_node_1\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    namespaced_nodes = [\n        GroupAction(\n            actions=[\n                PushROSNamespace(bot_ns),\n                control_node,\n                robot_state_publisher_node,\n                joint_state_broadcaster_spawner,\n                slave_node_1,\n                cia402_device_controller_spawner,\n                forward_position_controller,\n            ]\n        )\n    ]\n    return namespaced_nodes\n\n\ndef generate_launch_description():\n\n    declared_arguments = []\n    declared_arguments.append(\n        DeclareLaunchArgument(\"bot_ns\", description=\"Namespace for these nodes\", default_value=\"\")\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"name\", description=\"robot name\", default_value=\"canopen_test_system\"\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\"prefix\", description=\"Prefix.\", default_value=\"\")\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_package\",\n            description=\"Package where urdf file is stored.\",\n            default_value=\"canopen_tests\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_file\",\n            description=\"Name of the urdf file.\",\n            default_value=\"cia402_system.urdf.xacro\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_directory\",\n            default_value=\"config/cia402_namespaced_system\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_file\",\n            default_value=\"ros2_controllers.yaml\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_directory\",\n            default_value=\"config/cia402_system\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_file\",\n            default_value=\"bus.yml\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_directory\",\n            default_value=\"config/cia402_system\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_file\",\n            default_value=\"master.dcf\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"can_interface_name\",\n            default_value=\"vcan0\",\n            description=\"Interface name for can\",\n        )\n    )\n\n    return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])\n"
  },
  {
    "path": "canopen_tests/launch/cia402_setup.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"cia402\", \"cia402_slave.eds\"\n    )\n\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/cia402_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"cia402_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n    master_bin_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"config\",\n        \"cia402_lifecycle\",\n        \"master.bin\",\n    )\n    if not os.path.exists(master_bin_path):\n        master_bin_path = \"\"\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": master_bin_path,\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"cia402\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    return LaunchDescription([slave_node_1, device_container])\n"
  },
  {
    "path": "canopen_tests/launch/cia402_system.launch.py",
    "content": "# Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt)\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions are met:\n#\n#    * Redistributions of source code must retain the above copyright\n#      notice, this list of conditions and the following disclaimer.\n#\n#    * Redistributions in binary form must reproduce the above copyright\n#      notice, this list of conditions and the following disclaimer in the\n#      documentation and/or other materials provided with the distribution.\n#\n#    * Neither the name of the {copyright_holder} nor the names of its\n#      contributors may be used to endorse or promote products derived from\n#      this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE\n# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n#\n# Author: Lovro Ivanov lovro.ivanov@gmail.com\n\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.actions import OpaqueFunction\nfrom launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\nfrom launch_ros.actions import Node\nfrom launch_ros.substitutions import FindPackageShare\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef launch_setup(context, *args, **kwargs):\n\n    name = LaunchConfiguration(\"name\")\n    prefix = LaunchConfiguration(\"prefix\")\n\n    # bus configuration\n    bus_config_package = LaunchConfiguration(\"bus_config_package\")\n    bus_config_directory = LaunchConfiguration(\"bus_config_directory\")\n    bus_config_file = LaunchConfiguration(\"bus_config_file\")\n    # bus configuration file full path\n    bus_config = PathJoinSubstitution(\n        [FindPackageShare(bus_config_package), bus_config_directory, bus_config_file]\n    )\n\n    # master configuration\n    master_config_package = LaunchConfiguration(\"master_config_package\")\n    master_config_directory = LaunchConfiguration(\"master_config_directory\")\n    master_config_file = LaunchConfiguration(\"master_config_file\")\n    # master configuration file full path\n    master_config = PathJoinSubstitution(\n        [FindPackageShare(master_config_package), master_config_directory, master_config_file]\n    )\n\n    # can interface name\n    can_interface_name = LaunchConfiguration(\"can_interface_name\")\n\n    # robot description stuff\n    description_package = LaunchConfiguration(\"description_package\")\n    description_file = LaunchConfiguration(\"description_file\")\n    robot_description_content = Command(\n        [\n            PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n            \" \",\n            PathJoinSubstitution(\n                [FindPackageShare(description_package), \"urdf\", \"cia402_system\", description_file]\n            ),\n            \" \",\n            \"name:=\",\n            name,\n            \" \",\n            \"prefix:=\",\n            prefix,\n            \" \",\n            \"bus_config:=\",\n            bus_config,\n            \" \",\n            \"master_config:=\",\n            master_config,\n            \" \",\n            \"can_interface_name:=\",\n            can_interface_name,\n            \" \",\n        ]\n    )\n    robot_description = {\"robot_description\": robot_description_content}\n\n    # ros2 control configuration\n    ros2_control_config_package = LaunchConfiguration(\"ros2_control_config_package\")\n    ros2_control_config_directory = LaunchConfiguration(\"ros2_control_config_directory\")\n    ros2_control_config_file = LaunchConfiguration(\"ros2_control_config_file\")\n    # ros2 control configuration file full path\n    ros2_control_config = PathJoinSubstitution(\n        [\n            FindPackageShare(ros2_control_config_package),\n            ros2_control_config_directory,\n            ros2_control_config_file,\n        ]\n    )\n\n    # nodes to start are listed below\n    control_node = Node(\n        package=\"controller_manager\",\n        executable=\"ros2_control_node\",\n        parameters=[robot_description, ros2_control_config],\n        output=\"screen\",\n    )\n\n    # load one controller just to make sure it can connect to controller_manager\n    joint_state_broadcaster_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"joint_state_broadcaster\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    cia402_device_controller_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"cia402_device_1_controller\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    forward_position_controller = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"forward_position_controller\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    robot_state_publisher_node = Node(\n        package=\"robot_state_publisher\",\n        executable=\"robot_state_publisher\",\n        output=\"both\",\n        parameters=[robot_description],\n    )\n\n    # hardcoded slave configuration form test package\n    slave_config = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"config/cia402\", \"cia402_slave.eds\"]\n    )\n\n    slave_launch = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_fake_slaves\"), \"launch\", \"cia402_slave.launch.py\"]\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"cia402_node_1\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    nodes_to_start = [\n        control_node,\n        robot_state_publisher_node,\n        joint_state_broadcaster_spawner,\n        slave_node_1,\n        cia402_device_controller_spawner,\n        forward_position_controller,\n    ]\n\n    return nodes_to_start\n\n\ndef generate_launch_description():\n\n    declared_arguments = []\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"name\", description=\"robot name\", default_value=\"canopen_test_system\"\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\"prefix\", description=\"Prefix.\", default_value=\"\")\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_package\",\n            description=\"Package where urdf file is stored.\",\n            default_value=\"canopen_tests\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"description_file\",\n            description=\"Name of the urdf file.\",\n            default_value=\"cia402_system.urdf.xacro\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_directory\",\n            default_value=\"config/cia402_system\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"ros2_control_config_file\",\n            default_value=\"ros2_controllers.yaml\",\n            description=\"Path to ros2_control configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_directory\",\n            default_value=\"config/cia402_system\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"bus_config_file\",\n            default_value=\"bus.yml\",\n            description=\"Path to bus configuration.\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_package\",\n            default_value=\"canopen_tests\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_directory\",\n            default_value=\"config/cia402_system\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"master_config_file\",\n            default_value=\"master.dcf\",\n            description=\"Path to master configuration file (*.dcf)\",\n        )\n    )\n\n    declared_arguments.append(\n        DeclareLaunchArgument(\n            \"can_interface_name\",\n            default_value=\"vcan0\",\n            description=\"Interface name for can\",\n        )\n    )\n\n    return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])\n"
  },
  {
    "path": "canopen_tests/launch/proxy_diagnostics_setup.launch.py",
    "content": "# Copyright 2023 ROS-Industrial\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nimport launch_ros\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"simple_diagnostics\", \"simple.eds\"\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    print(\n        os.path.join(\n            get_package_share_directory(\"canopen_tests\"),\n            \"config\",\n            \"proxy_write_sdo\",\n            \"master.dcf\",\n        )\n    )\n\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple_diagnostics\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": \"\",\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple_diagnostics\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    diagnostics_analyzer_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"),\n        \"launch\",\n        \"analyzers\",\n        \"proxy_diagnostic_analyzer.yaml\",\n    )\n\n    diagnostics_aggregator_node = launch_ros.actions.Node(\n        package=\"diagnostic_aggregator\",\n        executable=\"aggregator_node\",\n        output=\"screen\",\n        parameters=[diagnostics_analyzer_path],\n    )\n\n    return LaunchDescription(\n        [slave_node_1, slave_node_2, device_container, diagnostics_aggregator_node]\n    )\n"
  },
  {
    "path": "canopen_tests/launch/proxy_lifecycle_setup.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"simple_lifecycle\", \"simple.eds\"\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    print(\n        os.path.join(\n            get_package_share_directory(\"canopen_tests\"),\n            \"config\",\n            \"proxy_write_sdo\",\n            \"master.dcf\",\n        )\n    )\n\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple_lifecycle\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": \"\",\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple_lifecycle\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    return LaunchDescription([slave_node_1, slave_node_2, device_container])\n"
  },
  {
    "path": "canopen_tests/launch/proxy_setup.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nimport launch_ros\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"simple\", \"simple.eds\"\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    print(\n        os.path.join(\n            get_package_share_directory(\"canopen_tests\"),\n            \"config\",\n            \"proxy_write_sdo\",\n            \"master.dcf\",\n        )\n    )\n\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": \"\",\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n        }.items(),\n    )\n\n    return LaunchDescription([slave_node_1, slave_node_2, device_container])\n"
  },
  {
    "path": "canopen_tests/launch/proxy_setup_namespaced.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nimport launch_ros\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n    slave_eds_path = os.path.join(\n        get_package_share_directory(\"canopen_tests\"), \"config\", \"simple\", \"simple.eds\"\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_1\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_fake_slaves\"), \"launch\"),\n                \"/basic_slave.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_eds_path,\n        }.items(),\n    )\n\n    print(\n        os.path.join(\n            get_package_share_directory(\"canopen_tests\"),\n            \"config\",\n            \"proxy_write_sdo\",\n            \"master.dcf\",\n        )\n    )\n\n    device_container = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_core\"), \"launch\"),\n                \"/canopen.launch.py\",\n            ]\n        ),\n        launch_arguments={\n            \"master_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple\",\n                \"master.dcf\",\n            ),\n            \"master_bin\": \"\",\n            \"bus_config\": os.path.join(\n                get_package_share_directory(\"canopen_tests\"),\n                \"config\",\n                \"simple\",\n                \"bus.yml\",\n            ),\n            \"can_interface_name\": \"vcan0\",\n            \"namespace\": \"/test_ns\",\n        }.items(),\n    )\n\n    return LaunchDescription([slave_node_1, slave_node_2, device_container])\n"
  },
  {
    "path": "canopen_tests/launch/robot_control_setup.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\nfrom launch_ros.actions import Node\nfrom launch_ros.substitutions import FindPackageShare\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\n\n\ndef generate_launch_description():\n\n    robot_description_content = Command(\n        [\n            PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n            \" \",\n            PathJoinSubstitution(\n                [\n                    FindPackageShare(\"canopen_tests\"),\n                    \"urdf/robot_controller\",\n                    \"robot_controller.urdf.xacro\",\n                ]\n            ),\n        ]\n    )\n    robot_description = {\"robot_description\": robot_description_content}\n    robot_control_config = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"config/robot_control\", \"ros2_controllers.yaml\"]\n    )\n\n    rviz_config_file = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"rviz\", \"robot_controller.rviz\"]\n    )\n\n    control_node = Node(\n        package=\"controller_manager\",\n        executable=\"ros2_control_node\",\n        parameters=[robot_description, robot_control_config],\n        output=\"screen\",\n    )\n\n    joint_state_broadcaster_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"joint_state_broadcaster\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    robot_controller_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"robot_controller\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    forward_position_controller_spawner = Node(\n        package=\"controller_manager\",\n        executable=\"spawner\",\n        arguments=[\"forward_position_controller\", \"--controller-manager\", \"/controller_manager\"],\n    )\n\n    robot_state_publisher_node = Node(\n        package=\"robot_state_publisher\",\n        executable=\"robot_state_publisher\",\n        output=\"both\",\n        parameters=[robot_description],\n    )\n    rviz_node = Node(\n        package=\"rviz2\",\n        executable=\"rviz2\",\n        name=\"rviz2\",\n        output=\"log\",\n        arguments=[\"-d\", rviz_config_file],\n    )\n\n    slave_config = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"config/robot_control\", \"cia402_slave.eds\"]\n    )\n\n    slave_launch = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_fake_slaves\"), \"launch\", \"cia402_slave.launch.py\"]\n    )\n    slave_node_1 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"2\",\n            \"node_name\": \"slave_node_1\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    slave_node_2 = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(slave_launch),\n        launch_arguments={\n            \"node_id\": \"3\",\n            \"node_name\": \"slave_node_2\",\n            \"slave_config\": slave_config,\n        }.items(),\n    )\n\n    nodes_to_start = [\n        # slave_node_2,\n        # slave_node_1,\n        control_node,\n        joint_state_broadcaster_spawner,\n        # robot_controller_spawner,\n        forward_position_controller_spawner,\n        robot_state_publisher_node,\n        slave_node_1,\n        slave_node_2,\n        # rviz_node\n    ]\n\n    return LaunchDescription(nodes_to_start)\n"
  },
  {
    "path": "canopen_tests/launch/view_urdf.launch.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution\nfrom launch_ros.actions import Node\nfrom launch_ros.substitutions import FindPackageShare\n\n\ndef generate_launch_description():\n\n    robot_description_content = Command(\n        [\n            PathJoinSubstitution([FindExecutable(name=\"xacro\")]),\n            \" \",\n            PathJoinSubstitution(\n                [\n                    FindPackageShare(\"canopen_tests\"),\n                    \"urdf/robot_controller\",\n                    \"robot_controller.urdf.xacro\",\n                ]\n            ),\n        ]\n    )\n    robot_description = {\"robot_description\": robot_description_content}\n\n    rviz_config_file = PathJoinSubstitution(\n        [FindPackageShare(\"canopen_tests\"), \"rviz\", \"robot_controller.rviz\"]\n    )\n\n    joint_state_publisher_node = Node(\n        package=\"joint_state_publisher_gui\",\n        executable=\"joint_state_publisher_gui\",\n    )\n\n    robot_state_publisher_node = Node(\n        package=\"robot_state_publisher\",\n        executable=\"robot_state_publisher\",\n        output=\"both\",\n        parameters=[robot_description],\n    )\n    rviz_node = Node(\n        package=\"rviz2\",\n        executable=\"rviz2\",\n        name=\"rviz2\",\n        output=\"log\",\n        arguments=[\"-d\", rviz_config_file],\n    )\n\n    nodes_to_start = [\n        joint_state_publisher_node,\n        robot_state_publisher_node,\n        rviz_node,\n    ]\n\n    return LaunchDescription(nodes_to_start)\n"
  },
  {
    "path": "canopen_tests/launch_tests/test_cia402_driver.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom time import sleep\nimport time\nimport pytest\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nimport launch_testing\nimport threading\nimport rclpy\nfrom rclpy.node import Node\nfrom canopen_utils.launch_test_node import LaunchTestNode\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID, COTargetDouble\nfrom canopen_interfaces.msg import COData\nfrom std_srvs.srv import Trigger\nimport unittest\n\n\n@pytest.mark.rostest\ndef generate_test_description():\n\n    launch_desc = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_tests\"), \"launch\"),\n                \"/cia402_setup.launch.py\",\n            ]\n        )\n    )\n\n    ready_to_test = launch.actions.TimerAction(\n        period=5.0,\n        actions=[launch_testing.actions.ReadyToTest()],\n    )\n\n    return (LaunchDescription([launch_desc, ready_to_test]), {})\n\n\nclass TestSDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = CORead.Request()\n        req.index = 0x1000\n        req.subindex = 0\n\n        res = CORead.Response()\n        res.success = True\n        res.data = 0xFFFF0192\n\n        self.node.call_service(\"cia402_device_1/sdo_read\", CORead, req, res)\n\n    def test_init(self):\n        req = Trigger.Request()\n\n        res = Trigger.Response()\n        res.success = True\n\n        self.node.call_service(\"cia402_device_1/init\", Trigger, req, res)\n\n    def test_position_mode(self):\n        req = Trigger.Request()\n\n        res = Trigger.Response()\n        res.success = True\n\n        self.node.call_service(\"cia402_device_1/init\", Trigger, req, res)\n        self.node.call_service(\"cia402_device_1/position_mode\", Trigger, req, res)\n\n        target_req = COTargetDouble.Request()\n        target_req.target = 1.0\n        target_res = COTargetDouble.Response()\n        target_res.success = True\n\n        self.node.call_service(\"cia402_device_1/target\", COTargetDouble, target_req, target_res)\n"
  },
  {
    "path": "canopen_tests/launch_tests/test_proxy_driver.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom time import sleep\nimport time\nimport pytest\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nimport launch_testing\nimport threading\nimport rclpy\nfrom rclpy.node import Node\nfrom canopen_utils.launch_test_node import LaunchTestNode\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID\nfrom canopen_interfaces.msg import COData\nfrom std_srvs.srv import Trigger\nimport unittest\n\n\n@pytest.mark.rostest\ndef generate_test_description():\n\n    launch_desc = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_tests\"), \"launch\"),\n                \"/proxy_setup.launch.py\",\n            ]\n        )\n    )\n\n    ready_to_test = launch.actions.TimerAction(\n        period=5.0,\n        actions=[launch_testing.actions.ReadyToTest()],\n    )\n\n    return (LaunchDescription([launch_desc, ready_to_test]), {})\n\n\nclass TestNMT(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUpClass(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDownClass(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_reset_nmt(self):\n        request = Trigger.Request()\n        response = Trigger.Response()\n        response.success = True\n        self.node.call_service(\"proxy_device_2/nmt_reset_node\", Trigger, request, response)\n        time.sleep(1)\n\n\nclass TestSDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = CORead.Request()\n        req.index = 0x4000\n        req.subindex = 0\n\n        res = CORead.Response()\n        res.success = True\n        res.data = 0\n\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, req, res)\n\n    def test_sdo_write(self):\n        index = 0x4000\n        subindex = 0\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_signed8(self):\n        \"\"\"Tests SDO writing to a SIGNED8 data object.\"\"\"\n        index = 0x4004\n        subindex = 2\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_signed16(self):\n        \"\"\"Tests SDO writing to a SIGNED16 data object.\"\"\"\n        index = 0x4004\n        subindex = 3\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_signed32(self):\n        \"\"\"Tests SDO writing to a SIGNED32 data object.\"\"\"\n        index = 0x4004\n        subindex = 4\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_unsigned8(self):\n        \"\"\"Tests SDO writing to an UNSIGNED8 data object.\"\"\"\n        index = 0x4004\n        subindex = 5\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_unsigned16(self):\n        \"\"\"Tests SDO writing to an UNSIGNED16 data object.\"\"\"\n        index = 0x4004\n        subindex = 6\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n    def test_sdo_write_unsigned32(self):\n        \"\"\"Tests SDO writing to an UNSIGNED32 data object.\"\"\"\n        index = 0x4004\n        subindex = 7\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n\nclass TestSDOMaster(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = COReadID.Request()\n        req.index = 0x4000\n        req.subindex = 0\n        req.nodeid = 2\n        req.canopen_datatype = 0x7\n\n        res = COReadID.Response()\n        res.success = True\n        res.data = 0\n\n        self.node.call_service(\"/master/sdo_read\", COReadID, req, res)\n        req.nodeid = 3\n        self.node.call_service(\"/master/sdo_read\", COReadID, req, res)\n\n    def test_sdo_write(self):\n        index = 0x4000\n        subindex = 0\n        data = 100\n        req = COWriteID.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n        req.canopen_datatype = 0x7\n        req.nodeid = 2\n        res = COWriteID.Response()\n        res.success = True\n        rreq = COReadID.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n        rreq.nodeid = 2\n        rres = COReadID.Response()\n        rres.success = True\n        rres.data = data\n        rreq.canopen_datatype = 0x7\n        self.node.call_service(\"master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"master/sdo_read\", COReadID, rreq, rres)\n        self.node.call_service(\"master/sdo_read\", COReadID, rreq, rres)\n        req.data = 0\n        self.node.call_service(\"master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"master/sdo_write\", COWriteID, req, res)\n\n\nclass TestPDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_pdo(self):\n        msg = COData()\n        msg.index = 0x4000\n        msg.subindex = 0\n        msg.data = 200\n\n        pub_msg = COData()\n        pub_msg.index = 0x4001\n        pub_msg.subindex = 0\n        pub_msg.data = 200\n        thread = threading.Thread(\n            target=self.node.subscribe_and_wait_for_message,\n            args=[\"proxy_device_1/rpdo\", COData, pub_msg],\n        )\n        thread.start()\n        self.node.publish_message(\"proxy_device_1/tpdo\", COData, msg)\n        time.sleep(0.1)\n        msg.data = 0\n        self.node.publish_message(\"proxy_device_1/tpdo\", COData, msg)\n        thread.join()\n"
  },
  {
    "path": "canopen_tests/launch_tests/test_proxy_driver_namespaced.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom time import sleep\nimport time\nimport pytest\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nimport launch_testing\nimport threading\nimport rclpy\nfrom rclpy.node import Node\nfrom canopen_utils.launch_test_node import LaunchTestNode\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID\nfrom canopen_interfaces.msg import COData\nfrom std_srvs.srv import Trigger\nimport unittest\n\n\n@pytest.mark.rostest\ndef generate_test_description():\n\n    launch_desc = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_tests\"), \"launch\"),\n                \"/proxy_setup.launch.py\",\n            ]\n        )\n    )\n\n    ready_to_test = launch.actions.TimerAction(\n        period=5.0,\n        actions=[launch_testing.actions.ReadyToTest()],\n    )\n\n    return (LaunchDescription([launch_desc, ready_to_test]), {})\n\n\nclass TestNMT(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUpClass(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDownClass(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_reset_nmt(self):\n        request = Trigger.Request()\n        response = Trigger.Response()\n        response.success = True\n        self.node.call_service(\n            \"/test_ns/proxy_device_2/nmt_reset_node\", Trigger, request, response\n        )\n        time.sleep(1)\n\n\nclass TestSDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = CORead.Request()\n        req.index = 0x4000\n        req.subindex = 0\n\n        res = CORead.Response()\n        res.success = True\n        res.data = 0\n\n        self.node.call_service(\"/test_ns/proxy_device_1/sdo_read\", CORead, req, res)\n        self.node.call_service(\"/test_ns/proxy_device_2/sdo_read\", CORead, req, res)\n\n    def test_sdo_write(self):\n        index = 0x4000\n        subindex = 0\n        data = 100\n\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n\n        res = COWrite.Response()\n        res.success = True\n\n        rreq = CORead.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n\n        rres = CORead.Response()\n        rres.success = True\n        rres.data = data\n\n        self.node.call_service(\"/test_ns/proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"/test_ns/proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n        self.node.call_service(\"/test_ns/proxy_device_1/sdo_read\", CORead, rreq, rres)\n        self.node.call_service(\"/test_ns/proxy_device_2/sdo_read\", CORead, rreq, rres)\n        req.data = 0\n        time.sleep(0.01)\n        self.node.call_service(\"/test_ns/proxy_device_1/sdo_write\", COWrite, req, res)\n        self.node.call_service(\"/test_ns/proxy_device_2/sdo_write\", COWrite, req, res)\n        time.sleep(0.01)\n\n\nclass TestSDOMaster(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = COReadID.Request()\n        req.index = 0x4000\n        req.subindex = 0\n        req.nodeid = 2\n        req.canopen_datatype = 0x7\n\n        res = COReadID.Response()\n        res.success = True\n        res.data = 0\n\n        self.node.call_service(\"/test_ns/master/sdo_read\", COReadID, req, res)\n        req.nodeid = 3\n        self.node.call_service(\"/test_ns/master/sdo_read\", COReadID, req, res)\n\n    def test_sdo_write(self):\n        index = 0x4000\n        subindex = 0\n        data = 100\n        req = COWriteID.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n        req.canopen_datatype = 0x7\n        req.nodeid = 2\n        res = COWriteID.Response()\n        res.success = True\n        rreq = COReadID.Request()\n        rreq.index = index\n        rreq.subindex = subindex\n        rreq.nodeid = 2\n        rres = COReadID.Response()\n        rres.success = True\n        rres.data = data\n        rreq.canopen_datatype = 0x7\n        self.node.call_service(\"/test_ns/master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"/test_ns/master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"/test_ns/master/sdo_read\", COReadID, rreq, rres)\n        self.node.call_service(\"/test_ns/master/sdo_read\", COReadID, rreq, rres)\n        req.data = 0\n        self.node.call_service(\"/test_ns/master/sdo_write\", COWriteID, req, res)\n        self.node.call_service(\"/test_ns/master/sdo_write\", COWriteID, req, res)\n\n\nclass TestPDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_pdo(self):\n        msg = COData()\n        msg.index = 0x4000\n        msg.subindex = 0\n        msg.data = 200\n\n        pub_msg = COData()\n        pub_msg.index = 0x4001\n        pub_msg.subindex = 0\n        pub_msg.data = 200\n        thread = threading.Thread(\n            target=self.node.subscribe_and_wait_for_message,\n            args=[\"/test_ns/proxy_device_1/rpdo\", COData, pub_msg],\n        )\n        thread.start()\n        self.node.publish_message(\"/test_ns/proxy_device_1/tpdo\", COData, msg)\n        time.sleep(0.1)\n        msg.data = 0\n        self.node.publish_message(\"/test_ns/proxy_device_1/tpdo\", COData, msg)\n        thread.join()\n"
  },
  {
    "path": "canopen_tests/launch_tests/test_proxy_lifecycle_driver.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom time import sleep\nimport time\nimport pytest\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nimport launch_testing\nimport threading\nimport rclpy\nfrom canopen_utils.launch_test_node import LaunchTestNode\nfrom lifecycle_msgs.msg import Transition\nfrom lifecycle_msgs.srv import ChangeState\nimport unittest\nfrom canopen_interfaces.srv import CORead, COWrite\nfrom canopen_interfaces.msg import COData\n\n\n@pytest.mark.rostest\ndef generate_test_description():\n\n    launch_desc = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_tests\"), \"launch\"),\n                \"/proxy_lifecycle_setup.launch.py\",\n            ]\n        )\n    )\n\n    ready_to_test = launch.actions.TimerAction(\n        period=5.0,\n        actions=[launch_testing.actions.ReadyToTest()],\n    )\n\n    return (LaunchDescription([launch_desc, ready_to_test]), {})\n\n\nclass TestLifecycle(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_configure_unconfigure(self):\n        req = ChangeState.Request()\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n\n        res = ChangeState.Response()\n        res.success = True\n\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n\n    def test_full_cycle(self):\n        req = ChangeState.Request()\n\n        res = ChangeState.Response()\n        res.success = True\n\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CONFIGURE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_ACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************ACTIVATE SUCCESSFUL*************************\")\n\n        req.transition.id = Transition.TRANSITION_DEACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************DEACTIVATE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CLEANUP SUCCESSFUL*************************\")\n\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CONFIGURE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_ACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************ACTIVATE SUCCESSFUL*************************\")\n\n        req.transition.id = Transition.TRANSITION_DEACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************DEACTIVATE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CLEANUP SUCCESSFUL*************************\")\n\n\nclass TestSDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_full_cycle_sdo(self):\n        req = ChangeState.Request()\n\n        res = ChangeState.Response()\n        res.success = True\n\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CONFIGURE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_ACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************ACTIVATE SUCCESSFUL*************************\")\n\n        data = 100\n\n        readreq = CORead.Request()\n        readreq.index = 0x4000\n        readreq.subindex = 0x00\n\n        readres = CORead.Response()\n        readres.success = True\n        readres.data = data\n\n        writereq = COWrite.Request()\n        writereq.index = 0x4000\n        writereq.subindex = 0x00\n        writereq.data = data\n\n        writeres = COWrite.Response()\n        writeres.success = True\n\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, writereq, writeres)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, writereq, writeres)\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, readreq, readres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, readreq, readres)\n        data = 0\n        self.node.call_service(\"proxy_device_1/sdo_write\", COWrite, writereq, writeres)\n        self.node.call_service(\"proxy_device_2/sdo_write\", COWrite, writereq, writeres)\n\n        req.transition.id = Transition.TRANSITION_DEACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************DEACTIVATE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CLEANUP SUCCESSFUL*************************\")\n\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CONFIGURE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_ACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************ACTIVATE SUCCESSFUL*************************\")\n\n        self.node.call_service(\"proxy_device_1/sdo_read\", CORead, readreq, readres)\n        self.node.call_service(\"proxy_device_2/sdo_read\", CORead, readreq, readres)\n\n        req.transition.id = Transition.TRANSITION_DEACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************DEACTIVATE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CLEANUP SUCCESSFUL*************************\")\n\n\nclass TestPDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_full_cycle_sdo(self):\n        req = ChangeState.Request()\n\n        res = ChangeState.Response()\n        res.success = True\n\n        req.transition.id = Transition.TRANSITION_CONFIGURE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CONFIGURE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_ACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************ACTIVATE SUCCESSFUL*************************\")\n\n        msg = COData()\n        msg.index = 0x4000\n        msg.subindex = 0\n        msg.data = 200\n\n        pub_msg = COData()\n        pub_msg.index = 0x4001\n        pub_msg.subindex = 0\n        pub_msg.data = 200\n        thread = threading.Thread(\n            target=self.node.subscribe_and_wait_for_message,\n            args=[\"proxy_device_1/rpdo\", COData, pub_msg],\n        )\n        thread.start()\n        self.node.publish_message(\"proxy_device_1/tpdo\", COData, msg)\n        time.sleep(0.1)\n        msg.data = 0\n        self.node.publish_message(\"proxy_device_1/tpdo\", COData, msg)\n        thread.join()\n\n        req.transition.id = Transition.TRANSITION_DEACTIVATE\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************DEACTIVATE SUCCESSFUL*************************\")\n        req.transition.id = Transition.TRANSITION_CLEANUP\n        self.node.call_service(\"/lifecycle_manager/change_state\", ChangeState, req, res)\n        print(\"*************************CLEANUP SUCCESSFUL*************************\")\n"
  },
  {
    "path": "canopen_tests/launch_tests/test_robot_control.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport os\nfrom time import sleep\nimport time\nimport pytest\nfrom ament_index_python import get_package_share_directory\nfrom launch import LaunchDescription\nimport launch\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nimport launch_testing\nimport threading\nimport rclpy\nfrom rclpy.node import Node\nfrom canopen_utils.launch_test_node import LaunchTestNode\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID, COTargetDouble\nfrom canopen_interfaces.msg import COData\nfrom std_srvs.srv import Trigger\nfrom std_msgs.msg import Float64MultiArray\nimport unittest\n\n\n@pytest.mark.rostest\ndef generate_test_description():\n\n    launch_desc = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory(\"canopen_tests\"), \"launch\"),\n                \"/robot_control_setup.launch.py\",\n            ]\n        )\n    )\n\n    ready_to_test = launch.actions.TimerAction(\n        period=5.0,\n        actions=[launch_testing.actions.ReadyToTest()],\n    )\n\n    return (LaunchDescription([launch_desc, ready_to_test]), {})\n\n\nclass TestSDO(unittest.TestCase):\n    def run_node(self):\n        while self.ok:\n            rclpy.spin_once(self.node, timeout_sec=0.1)\n\n    @classmethod\n    def setUp(cls):\n        cls.ok = True\n        rclpy.init()\n        cls.node = LaunchTestNode()\n        cls.thread = threading.Thread(target=cls.run_node, args=[cls])\n        cls.thread.start()\n\n    @classmethod\n    def tearDown(cls):\n        cls.ok = False\n        cls.thread.join()\n        cls.node.destroy_node()\n        rclpy.shutdown()\n\n    def test_sdo_read(self):\n        req = CORead.Request()\n        req.index = 0x1000\n        req.subindex = 0\n\n        res = CORead.Response()\n        res.success = True\n        res.data = 0x60192\n\n        self.node.call_service(\"joint_1/sdo_read\", CORead, req, res)\n\n    def test_forward_control(self):\n        message = Float64MultiArray()\n        message.data = [1.0, 0.0]\n\n        self.node.publish_message(\"forward_position_controller\", Float64MultiArray, message)\n        time.sleep(1.0)\n"
  },
  {
    "path": "canopen_tests/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_tests</name>\n  <version>0.3.2</version>\n  <description>Package with tests for ros2_canopen</description>\n  <maintainer email=\"cmh@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n\n  <build_depend>lely_core_libraries</build_depend>\n\n  <exec_depend>canopen_402_driver</exec_depend>\n  <exec_depend>canopen_core</exec_depend>\n  <exec_depend>canopen_proxy_driver</exec_depend>\n\n  <exec_depend>xacro</exec_depend>\n  <exec_depend>controller_manager</exec_depend>\n  <exec_depend>robot_state_publisher</exec_depend>\n\n  <exec_depend>joint_state_broadcaster</exec_depend>\n  <exec_depend>joint_trajectory_controller</exec_depend>\n  <exec_depend>forward_command_controller</exec_depend>\n\n  <exec_depend>canopen_fake_slaves</exec_depend>\n  <exec_depend>canopen_ros2_controllers</exec_depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_tests/rviz/robot_controller.rviz",
    "content": "Panels:\n  - Class: rviz_common/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /RobotModel1\n      Splitter Ratio: 0.5\n    Tree Height: 752\n  - Class: rviz_common/Selection\n    Name: Selection\n  - Class: rviz_common/Tool Properties\n    Expanded:\n      - /2D Goal Pose1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz_common/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz_common/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: \"\"\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz_default_plugins/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Class: rviz_default_plugins/RobotModel\n      Collision Enabled: false\n      Description File: /home/ws/test.urdf\n      Description Source: Topic\n      Description Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /robot_description\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        link1:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        link2:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        link3:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        link4:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n      Mass Properties:\n        Inertia: false\n        Mass: false\n      Name: RobotModel\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz_default_plugins/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        link1:\n          Value: true\n        link2:\n          Value: true\n        link3:\n          Value: true\n        link4:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: false\n      Tree:\n        link1:\n          link2:\n            link3:\n              link4:\n                {}\n      Update Interval: 0\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: link1\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz_default_plugins/Interact\n      Hide Inactive Objects: true\n    - Class: rviz_default_plugins/MoveCamera\n    - Class: rviz_default_plugins/Select\n    - Class: rviz_default_plugins/FocusCamera\n    - Class: rviz_default_plugins/Measure\n      Line color: 128; 128; 0\n    - Class: rviz_default_plugins/SetInitialPose\n      Covariance x: 0.25\n      Covariance y: 0.25\n      Covariance yaw: 0.06853891909122467\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /initialpose\n    - Class: rviz_default_plugins/SetGoal\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /goal_pose\n    - Class: rviz_default_plugins/PublishPoint\n      Single click: true\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /clicked_point\n  Transformation:\n    Current:\n      Class: rviz_default_plugins/TF\n  Value: true\n  Views:\n    Current:\n      Class: rviz_default_plugins/Orbit\n      Distance: 10\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.05000000074505806\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Pitch: 0.785398006439209\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 0.785398006439209\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1043\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000015600000379fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000379000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000379fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b00000379000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007360000003efc0100000002fb0000000800540069006d00650100000000000007360000025300fffffffb0000000800540069006d00650100000000000004500000000000000000000004c50000037900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1846\n  X: 1994\n  Y: 0\n"
  },
  {
    "path": "canopen_tests/urdf/canopen_system/canopen_system.ros2_control.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n\n    <xacro:macro name=\"canopen_ros2_control_test\" params=\"\n      name\n      prefix\n      bus_config\n      master_config\n      can_interface_name\n      master_bin\">\n\n        <ros2_control name=\"${name}\" type=\"system\">\n            <hardware>\n              <plugin>canopen_ros2_control/CanopenSystem</plugin>\n              <param name=\"bus_config\">${bus_config}</param>\n              <param name=\"master_config\">${master_config}</param>\n              <param name=\"can_interface_name\">${can_interface_name}</param>\n              <param name=\"master_bin\">\"${master_bin}\"</param>\n            </hardware>\n            <joint name=\"${prefix}node_1\">\n                <param name=\"node_id\">2</param>\n            </joint>\n            <joint name=\"${prefix}node_2\">\n                <param name=\"node_id\">3</param>\n            </joint>\n        </ros2_control>\n\n    </xacro:macro>\n\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/canopen_system/canopen_system.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\" name=\"$(arg name)\">\n\n    <xacro:arg name=\"name\" default=\"canopen_test_system\"/>\n\n    <xacro:arg name=\"prefix\" default=\"\" />\n\n    <xacro:arg name=\"bus_config\" default=\"$(find canopen_proxy_driver)/config/pdo_test/pdo.yml\"/>\n    <xacro:arg name=\"master_config\" default=\"$(find canopen_proxy_driver)/config/pdo_test/master.dcf\"/>\n    <xacro:arg name=\"can_interface_name\" default=\"vcan0\"/>\n    <xacro:arg name=\"master_bin\" default=\"\"/>\n\n\n    <!-- ros2 control include -->\n    <xacro:include filename=\"$(find canopen_tests)/urdf/canopen_system/canopen_system.ros2_control.xacro\"/>\n\n    <xacro:canopen_ros2_control_test\n      name=\"$(arg name)\"\n      prefix=\"$(arg prefix)\"\n      bus_config=\"$(arg bus_config)\"\n      master_config=\"$(arg master_config)\"\n      can_interface_name=\"$(arg can_interface_name)\"\n      master_bin=\"$(arg master_bin)\"\n    />\n\n    <link name=\"$(arg prefix)base_link\"/>\n    <link name=\"$(arg prefix)node_1_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <geometry>\n          <cylinder radius=\"0.1\" length=\"1.0\"/>\n        </geometry>\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <geometry>\n          <cylinder radius=\"0.1\" length=\"1.0\"/>\n        </geometry>\n      </collision>\n    </link>\n\n    <joint name=\"$(arg prefix)node_1\" type=\"revolute\">\n        <parent link=\"$(arg prefix)base_link\" />\n        <child link=\"$(arg prefix)node_1_link\" />\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n        <axis xyz=\"0 0 1\" />\n        <limit lower=\"${-2*pi}\" upper=\"${2*pi}\" effort=\"10.0\" velocity=\"0.5\"/>\n    </joint>\n\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/cia402_system/cia402_system.ros2_control.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n\n    <xacro:macro name=\"cia402_ros2_control_test\" params=\"\n      name\n      prefix\n      bus_config\n      master_config\n      can_interface_name\n      master_bin\">\n\n        <ros2_control name=\"${name}\" type=\"system\">\n            <hardware>\n              <plugin>canopen_ros2_control/Cia402System</plugin>\n              <param name=\"bus_config\">${bus_config}</param>\n              <param name=\"master_config\">${master_config}</param>\n              <param name=\"can_interface_name\">${can_interface_name}</param>\n              <param name=\"master_bin\">\"${master_bin}\"</param>\n            </hardware>\n            <joint name=\"${prefix}node_1\">\n                <param name=\"node_id\">2</param>\n            </joint>\n<!--            <joint name=\"${prefix}node_2\">-->\n<!--                <param name=\"node_id\">3</param>-->\n<!--            </joint>-->\n        </ros2_control>\n\n    </xacro:macro>\n\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/cia402_system/cia402_system.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\" name=\"$(arg name)\">\n\n    <xacro:arg name=\"name\" default=\"cia402_test_system\"/>\n\n    <xacro:arg name=\"prefix\" default=\"\" />\n\n    <xacro:arg name=\"bus_config\" default=\"$(find canopen_tests)/config/cia402/bus.yml\"/>\n    <xacro:arg name=\"master_config\" default=\"$(find canopen_tests)/config/cia402/master.dcf\"/>\n    <xacro:arg name=\"can_interface_name\" default=\"vcan0\"/>\n    <xacro:arg name=\"master_bin\" default=\"\"/>\n\n\n    <!-- ros2 control include -->\n    <xacro:include filename=\"$(find canopen_tests)/urdf/cia402_system/cia402_system.ros2_control.xacro\"/>\n\n    <xacro:cia402_ros2_control_test\n      name=\"$(arg name)\"\n      prefix=\"$(arg prefix)\"\n      bus_config=\"$(arg bus_config)\"\n      master_config=\"$(arg master_config)\"\n      can_interface_name=\"$(arg can_interface_name)\"\n      master_bin=\"$(arg master_bin)\"\n    />\n\n    <link name=\"$(arg prefix)base_link\"/>\n    <link name=\"$(arg prefix)node_1_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <geometry>\n          <cylinder radius=\"0.1\" length=\"1.0\"/>\n        </geometry>\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <geometry>\n          <cylinder radius=\"0.1\" length=\"1.0\"/>\n        </geometry>\n      </collision>\n    </link>\n\n    <joint name=\"$(arg prefix)node_1\" type=\"revolute\">\n        <parent link=\"$(arg prefix)base_link\" />\n        <child link=\"$(arg prefix)node_1_link\" />\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n        <axis xyz=\"0 0 1\" />\n        <limit lower=\"${-2*pi}\" upper=\"${2*pi}\" effort=\"10.0\" velocity=\"0.5\"/>\n    </joint>\n\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/robot_controller/robot_controller.macro.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n\n    <xacro:macro name=\"robot_control_robot\" params=\"\n        name\n        prefix\n        parent\n        *origin\n        \" >\n\n\n    <link name=\"${prefix}link1\">\n        <visual>\n            <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n            <geometry>\n                <cylinder radius=\"0.2\" length=\"0.5\"/>\n            </geometry>\n        </visual>\n    </link>\n    <link name=\"${prefix}link2\">\n        <visual>\n            <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n            <geometry>\n                <cylinder radius=\"0.2\" length=\"0.5\"/>\n            </geometry>\n        </visual>\n    </link>\n    <link name=\"${prefix}link3\">\n        <visual>\n            <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n            <geometry>\n                <cylinder radius=\"0.2\" length=\"0.5\"/>\n            </geometry>\n        </visual>\n    </link>\n    <link name=\"${prefix}link4\">\n        <visual>\n            <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n            <geometry>\n                <cylinder radius=\"0.2\" length=\"0.5\"/>\n            </geometry>\n        </visual>\n    </link>\n    <joint name=\"${prefix}base_joint\" type=\"fixed\">\n        <xacro:insert_block name=\"origin\" />\n        <parent link=\"${parent}\"/>\n        <child link=\"${prefix}link1\"/>\n    </joint>\n    <joint name=\"${prefix}joint1\" type=\"revolute\">\n        <parent link=\"${prefix}link1\"/>\n        <child link=\"${prefix}link2\"/>\n        <origin xyz=\"0 0 0.5\" rpy=\"0 0 0\"/>\n        <axis xyz=\"0 1 0\" />\n        <limit lower=\"${-2*pi}\" upper=\"${2*pi}\" effort=\"10.0\" velocity=\"0.5\"/>\n    </joint>\n    <joint name=\"${prefix}joint2\" type=\"revolute\">\n        <parent link=\"${prefix}link2\"/>\n        <child link=\"${prefix}link3\"/>\n        <origin xyz=\"0 0 0.5\" rpy=\"0 0 0\"/>\n        <axis xyz=\"0 1 0\" />\n        <limit lower=\"${-2*pi}\" upper=\"${2*pi}\" effort=\"10.0\" velocity=\"0.5\"/>\n    </joint>\n    <joint name=\"${prefix}joint3\" type=\"fixed\">\n        <parent link=\"${prefix}link3\"/>\n        <child link=\"${prefix}link4\"/>\n        <origin xyz=\"0 0 0.5\" rpy=\"0 0 0\"/>\n        <axis xyz=\"0 1 0\" />\n    </joint>\n\n    </xacro:macro>\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/robot_controller/robot_controller.ros2_control.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://www.ros.org/wiki/xacro\">\n    <xacro:macro name=\"robot_control_control\" params=\"\n      name\n      prefix\n      bus_config\n      master_config\n      can_interface_name\n      master_bin\">\n\n        <ros2_control name=\"${name}\" type=\"system\">\n            <hardware>\n              <plugin>canopen_ros2_control/RobotSystem</plugin>\n              <param name=\"bus_config\">${bus_config}</param>\n              <param name=\"master_config\">${master_config}</param>\n              <param name=\"can_interface_name\">${can_interface_name}</param>\n              <param name=\"master_bin\">\"${master_bin}\"</param>\n            </hardware>\n            <joint name=\"${prefix}joint1\">\n                <param name=\"device_name\">joint_1</param>\n                <state_interface name=\"position\" />\n            </joint>\n            <joint name=\"${prefix}joint2\">\n                <param name=\"device_name\">joint_2</param>\n                <state_interface name=\"position\" />\n            </joint>\n        </ros2_control>\n    </xacro:macro>\n</robot>\n"
  },
  {
    "path": "canopen_tests/urdf/robot_controller/robot_controller.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://wiki.ros.org/xacro\" name=\"test_robot\">\n    <xacro:include filename=\"$(find canopen_tests)/urdf/robot_controller/robot_controller.macro.xacro\"/>\n    <xacro:include filename=\"$(find canopen_tests)/urdf/robot_controller/robot_controller.ros2_control.xacro\"/>\n\n    <link name=\"world\" />\n\n    <xacro:robot_control_robot\n        name=\"test_robot\"\n        prefix=\"\"\n        parent=\"world\"\n        >\n            <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    </xacro:robot_control_robot>\n\n    <xacro:robot_control_control\n        name=\"test_robot\"\n        prefix=\"\"\n        bus_config=\"$(find canopen_tests)/config/robot_control/bus.yml\"\n        master_config=\"$(find canopen_tests)/config/robot_control/master.dcf\"\n        can_interface_name=\"vcan0\"\n        master_bin=\"\" />\n</robot>\n"
  },
  {
    "path": "canopen_utils/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package canopen_utils\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n* Enhance SimpleSlave class with vendor ID parsing and adjust bus configuration timeouts\n* Contributors: ipa-vsp\n\n0.2.9 (2024-04-16)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n\n0.3.0 (2024-12-12)\n------------------\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Contributors: ipa-vsp\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix maintainer naming\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n\n0.2.5 (2023-06-23)\n------------------\n\n0.2.4 (2023-06-22)\n------------------\n\n0.2.3 (2023-06-22)\n------------------\n\n0.2.2 (2023-06-21)\n------------------\n\n0.2.1 (2023-06-21)\n------------------\n* Add more tidy launch_test_node.py\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos, Vishnuprasad Prachandabhanu\n"
  },
  {
    "path": "canopen_utils/LICENSE",
    "content": "\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "canopen_utils/canopen_utils/__init__.py",
    "content": ""
  },
  {
    "path": "canopen_utils/canopen_utils/cyclic_tester.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport rclpy\nfrom rclpy.callback_groups import MutuallyExclusiveCallbackGroup\nfrom rclpy.executors import MultiThreadedExecutor\nfrom rclpy.node import Node\nfrom canopen_interfaces.srv import COTargetDouble\n\n\nclass DoubleTalker(Node):\n    \"\"\"Publish messages to a topic using two publishers at different rates.\"\"\"\n\n    def __init__(self):\n        super().__init__(\"double_talker\")\n\n        self.i = 0\n        self.cli = self.create_client(COTargetDouble, \"trinamic_pd42/target\")\n        while not self.cli.wait_for_service(timeout_sec=1.0):\n            self.get_logger().info(\"service not available, waiting again...\")\n        self.increment = 1000.0\n        self.period = 0.1\n        self.value = 0.0\n        self.group = MutuallyExclusiveCallbackGroup()\n        self.timer = self.create_timer(self.period, self.timer_callback, callback_group=self.group)\n        self.req = COTargetDouble.Request()\n\n    def timer_callback(self):\n        self.value = self.value + self.increment\n        self.req.target = self.value\n        req = self.cli.call(self.req)\n        if req.success:\n            self.get_logger().info(\"Success\")\n        else:\n            self.get_logger().info(\"Failure\")\n\n\ndef main(args=None):\n    rclpy.init(args=args)\n    try:\n        talker = DoubleTalker()\n        # MultiThreadedExecutor executes callbacks with a thread pool. If num_threads is not\n        # specified then num_threads will be multiprocessing.cpu_count() if it is implemented.\n        # Otherwise it will use a single thread. This executor will allow callbacks to happen in\n        # parallel, however the MutuallyExclusiveCallbackGroup in DoubleTalker will only allow its\n        # callbacks to be executed one at a time. The callbacks in Listener are free to execute in\n        # parallel to the ones in DoubleTalker however.\n        executor = MultiThreadedExecutor(num_threads=4)\n        executor.add_node(talker)\n\n        try:\n            executor.spin()\n        finally:\n            executor.shutdown()\n            talker.destroy_node()\n    finally:\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "canopen_utils/canopen_utils/launch_test_node.py",
    "content": "# Copyright 2023 ROS-Industrial\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nimport time\nimport re\n\nimport launch_testing\nimport launch_testing.asserts\nimport launch_testing.actions\nimport launch_testing.util\nimport launch_testing.tools\nfrom launch_testing.asserts import assertSequentialStdout\n\nfrom rclpy.node import Node\nfrom rclpy.publisher import Publisher\nfrom rclpy.subscription import Subscription\nfrom rclpy.client import Client\nfrom rclpy.qos import QoSProfile\nfrom threading import Condition\n\n\nclass Ros2ActiveIoHandler:\n    def __init__(self, proc_output: launch_testing.ActiveIoHandler):\n        self.proc_output = proc_output\n\n    def checkInRos2Stream(self, process, expected_output: str):\n        resolved_procs = launch_testing.util.resolveProcesses(\n            info_obj=self.proc_output, process=process, cmd_args=None, strict_proc_matching=True\n        )\n\n        pat = re.compile(r\".*\\]: \" + expected_output)\n\n        for proc in resolved_procs:\n            for output in self.proc_output[proc]:\n                text = output.text.decode()\n                print(\"recceived: \" + text)\n                res = pat.search(text)\n                if res is not None:\n                    return True\n        return False\n\n    def waitFor(self, process, expected_output: str, timeout: float = 1.0):\n        success = False\n\n        with self.proc_output._sync_lock:\n            # TODO(pete.baughman): Searching through all of the IO can be time consuming/wasteful.\n            # We can optimize this by making a note of where we left off searching and only\n            # searching new messages when we return from the wait.\n            success = self.proc_output._sync_lock.wait_for(\n                lambda: self.checkInRos2Stream(process=process, expected_output=expected_output),\n                timeout=timeout,\n            )\n\n        return success\n\n    def assertWaitFor(self, process, expected_output: str, timeout: float = 1.0):\n        success = self.waitFor(process=process, expected_output=expected_output, timeout=timeout)\n        assert success, f\"Waiting for output {expected_output} timed out\"\n\n\nclass LaunchTestNode(Node):\n    def __init__(self):\n        super().__init__(\"launch_test_node\")\n        self.get_logger().info(\"launch_test_node initialized\")\n\n    def publish_delayed(self, publisher: Publisher, msg, delay: float):\n        publisher.publish(msg)\n        time.sleep(delay)\n\n    def publish_and_check_output(\n        self,\n        publisher: Publisher,\n        msg,\n        expected_output: str,\n        proc_output: launch_testing.ActiveIoHandler,\n        process=None,\n    ):\n\n        self.publish_delayed(publisher, msg, 0.1)\n        Ros2ActiveIoHandler(proc_output).assertWaitFor(\n            process=process, expected_output=expected_output\n        )\n\n    def subscribe_and_wait_for_message(self, topic: str, msg_type, msg, timeout: float = 2.5):\n        condition = Condition()\n        self.received = False\n\n        def callback(rec_msg):\n            with condition:\n                if not self.received:\n                    self.received = msg == rec_msg\n                if self.received:\n                    condition.notify()\n\n        subscription: Subscription = self.create_subscription(msg_type, topic, callback, 1)\n        with condition:\n            condition.wait(timeout=timeout)\n        self.destroy_subscription(subscription)\n        assert self.received, \"Did not receive the expected message.\"\n\n    def call_service(\n        self, service_name: str, srv_type, service_request, expected_response, timeout: float = 2.0\n    ):\n        condition = Condition()\n\n        def callback(arg):\n            with condition:\n                condition.notify()\n\n        client: Client = self.create_client(\n            srv_type, service_name, qos_profile=QoSProfile(depth=1)\n        )\n        if not client.wait_for_service(timeout_sec=timeout):\n            assert False, \"Service server not available.\"\n        future = client.call_async(service_request)\n        future.add_done_callback(callback=callback)\n        with condition:\n            if not condition.wait(timeout=timeout):\n                assert False, \"Service call timed out.\"\n\n        res = future.result()\n        assert res == expected_response, \"Did not receive the expected response.\"\n        self.destroy_client(client)\n\n    def publish_message(self, topic_name: str, topic_type, msg):\n        publisher = self.create_publisher(topic_type, topic_name, 10)\n        publisher.publish(msg)\n        self.destroy_publisher(publisher)\n"
  },
  {
    "path": "canopen_utils/canopen_utils/simple_rpdo_tpdo_tester.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport rclpy\nfrom rclpy.node import Node\nfrom rclpy.qos import QoSProfile\nfrom lifecycle_msgs.srv import GetState, ChangeState\nfrom lifecycle_msgs.msg import State, Transition\nfrom std_srvs.srv import Trigger\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID\nfrom canopen_interfaces.msg import COData\n\n\nclass SimpleTestNode(Node):\n    def __init__(self, name=\"test_node\"):\n        super().__init__(name)\n\n    def checkRpdoTpdo(self, node_name, index: int, subindex: int, type: int, data: int) -> bool:\n        publisher = self.create_publisher(COData, \"/\" + node_name + \"/tpdo\", 10)\n        subscriber = self.create_subscription(\n            COData, \"/\" + node_name + \"/rpdo\", self.rpdo_callback, 10\n        )\n        target = COData()\n        target.index = index\n        target.subindex = subindex\n        target.type = type\n        target.data = data\n        publisher.publish(target)\n        print(\"Published tpdo\")\n        # Wait for topic to be published\n        self.rpdo_data = None\n        while not (self.rpdo_data):\n            print(\"Waiting for subscriber to connect. \")\n            rclpy.spin_once(self, timeout_sec=0.1)\n\n        if self.rpdo_data.data == data:\n            result = True\n        else:\n            result = False\n\n        self.destroy_publisher(publisher)\n        self.destroy_subscription(subscriber)\n\n        return result\n\n    def rpdo_callback(self, msg):\n        print(\"RPDO Callback\")\n        print(msg)\n        self.rpdo_data = msg\n\n\ndef main(args=None):\n    rclpy.init(args=args)\n    node = SimpleTestNode()\n\n    result = node.checkRpdoTpdo(\"proxy_device_1\", index=0x4000, subindex=0, type=32, data=999)\n    print(\"RESULT: \" + str(result))\n\n    result = node.checkRpdoTpdo(\"proxy_device_2\", index=0x4000, subindex=0, type=32, data=999)\n    print(\"RESULT: \" + str(result))\n\n    node.destroy_node()\n    rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "canopen_utils/canopen_utils/test_node.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport rclpy\nfrom rclpy.node import Node\nfrom lifecycle_msgs.srv import GetState, ChangeState\nfrom lifecycle_msgs.msg import State, Transition\nfrom std_srvs.srv import Trigger\nfrom canopen_interfaces.srv import CORead, COWrite, COReadID, COWriteID\nfrom canopen_interfaces.msg import COData\n\n\nclass TestNode(Node):\n    def __init__(self, name=\"test_node\"):\n        super().__init__(name)\n\n    def checkTransition(self, node_name: str, state: int, tranisition: int) -> bool:\n        get_state_client = self.create_client(GetState, node_name + \"/get_state\")\n        change_state_client = self.create_client(ChangeState, node_name + \"/change_state\")\n        if not get_state_client.wait_for_service(timeout_sec=3.0):\n            get_state_client.destroy()\n            change_state_client.destroy()\n            return False\n        if not change_state_client.wait_for_service(timeout_sec=3.0):\n            get_state_client.destroy()\n            change_state_client.destroy()\n            return False\n        req = GetState.Request()\n        result = get_state_client.call(req)\n        if result.current_state.id != state:\n            return False\n\n        req = ChangeState.Request()\n        req.transition.id = tranisition\n        result = change_state_client.call(req)\n        if not result.success:\n            get_state_client.destroy()\n            change_state_client.destroy()\n            return False\n        get_state_client.destroy()\n        change_state_client.destroy()\n        return True\n\n    def checkTrigger(self, node_name, service_name) -> bool:\n        trigger_client = self.create_client(Trigger, \"/\" + node_name + \"/\" + service_name)\n        if not trigger_client.wait_for_service(timeout_sec=3.0):\n            return False\n        req = Trigger.Request()\n        result = trigger_client.call(req)\n        trigger_client.destroy()\n        if result.success:\n            return True\n        return False\n\n    def checkSDORead(self, node_name, index: int, subindex: int, data: int) -> bool:\n        client = self.create_client(CORead, \"/\" + node_name + \"/sdo_read\")\n        if not client.wait_for_service(timeout_sec=3.0):\n            return False\n        req = CORead.Request()\n        req.index = index\n        req.subindex = subindex\n        result = client.call(req)\n        client.destroy()\n        if result.success and (data == result.data):\n            return True\n        return False\n\n    def checkSDOWrite(self, node_name, index: int, subindex: int, data: int) -> bool:\n        client = self.create_client(COWrite, \"/\" + node_name + \"/sdo_write\")\n        if not client.wait_for_service(timeout_sec=3.0):\n            return False\n        req = COWrite.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n        result = client.call(req)\n        client.destroy()\n        if result.success:\n            return True\n        return False\n\n    def checkSDOReadID(\n        self, node_id: int, index: int, subindex: int, type: int, data: int\n    ) -> bool:\n        client = self.create_client(COReadID, \"/master/sdo_read\")\n        if not client.wait_for_service(timeout_sec=3.0):\n            return False\n        req = COReadID.Request()\n        req.index = index\n        req.subindex = subindex\n        req.canopen_datatype = type\n        req.nodeid = node_id\n        result = client.call(req)\n        client.destroy()\n        if result.success and (data == result.data):\n            return True\n        return False\n\n    def checkSDOWriteID(\n        self, node_id: int, index: int, subindex: int, type: int, data: int\n    ) -> bool:\n        client = self.create_client(COWriteID, \"/master/sdo_write\")\n        if not client.wait_for_service(timeout_sec=3.0):\n            return False\n        req = COWriteID.Request()\n        req.index = index\n        req.subindex = subindex\n        req.data = data\n        req.canopen_datatype = type\n        req.nodeid = node_id\n        result = client.call(req)\n        client.destroy()\n        if result.success:\n            return True\n        return False\n\n    def checkRpdoTpdo(self, node_name, index: int, subindex: int, data: int) -> bool:\n        publisher = self.create_publisher(COData, \"/\" + node_name + \"/tpdo\", 10)\n        subscriber = self.create_subscription(\n            COData, \"/\" + node_name + \"/rpdo\", self.rpdo_callback, 10\n        )\n        target = COData()\n        target.index = index\n        target.subindex = subindex\n        target.data = data\n        publisher.publish(target)\n        print(\"Published tpdo to topic: \" + \"/\" + node_name + \"/tpdo\")\n        self.rpdo_data = None\n        # Wait for topic to be published\n        while not self.rpdo_data:\n            rclpy.spin_once(self, timeout_sec=0.5)\n\n        self.destroy_publisher(publisher)\n        self.destroy_subscription(subscriber)\n\n        if self.rpdo_data.data == data:\n            return True\n        return False\n\n    def rpdo_callback(self, msg):\n        print(msg)\n        self.rpdo_data = msg\n"
  },
  {
    "path": "canopen_utils/no_tests/_test_copyright.py",
    "content": "# Copyright 2015 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_copyright.main import main\nimport pytest\n\n\n@pytest.mark.copyright\n@pytest.mark.linter\ndef test_copyright():\n    rc = main(argv=[\".\", \"test\"])\n    assert rc == 0, \"Found errors\"\n"
  },
  {
    "path": "canopen_utils/no_tests/_test_flake8.py",
    "content": "# Copyright 2017 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_flake8.main import main_with_errors\nimport pytest\n\n\n@pytest.mark.flake8\n@pytest.mark.linter\ndef test_flake8():\n    rc, errors = main_with_errors(argv=[])\n    assert rc == 0, \"Found %d code style errors / warnings:\\n\" % len(errors) + \"\\n\".join(errors)\n"
  },
  {
    "path": "canopen_utils/no_tests/_test_pep257.py",
    "content": "# Copyright 2015 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_pep257.main import main\nimport pytest\n\n\n@pytest.mark.linter\n@pytest.mark.pep257\ndef test_pep257():\n    rc = main(argv=[\".\", \"test\"])\n    assert rc == 0, \"Found code style errors / warnings\"\n"
  },
  {
    "path": "canopen_utils/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>canopen_utils</name>\n  <version>0.3.2</version>\n  <description>Utils for working with ros2_canopen.</description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n  <depend>rclpy</depend>\n  <depend>canopen_interfaces</depend>\n  <depend>lifecycle_msgs</depend>\n  <depend>std_msgs</depend>\n  <test_depend>ament_lint_auto</test_depend>\n  <export>\n    <build_type>ament_python</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "canopen_utils/resource/canopen_utils",
    "content": ""
  },
  {
    "path": "canopen_utils/setup.cfg",
    "content": "[develop]\nscript_dir=$base/lib/canopen_utils\n[install]\ninstall_scripts=$base/lib/canopen_utils\n"
  },
  {
    "path": "canopen_utils/setup.py",
    "content": "# Copyright 2023 ROS-Industrial\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom setuptools import setup\n\npackage_name = \"canopen_utils\"\n\nsetup(\n    name=package_name,\n    version=\"0.3.2\",\n    packages=[package_name],\n    data_files=[\n        (\"share/ament_index/resource_index/packages\", [\"resource/\" + package_name]),\n        (\"share/\" + package_name, [\"package.xml\"]),\n    ],\n    install_requires=[\"setuptools\"],\n    zip_safe=True,\n    maintainer=\"christoph\",\n    maintainer_email=\"christoph.hellmann.santos@ipa.fraunhofer.de\",\n    description=\"TODO: Package description\",\n    license=\"Apache-2.0\",\n    tests_require=[\"pytest\"],\n    entry_points={\n        \"console_scripts\": [\n            \"cyclic_tester = canopen_utils.cyclic_tester:main\",\n            \"simple_tester = canopen_utils.simple_rpdo_tpdo_tester:main\",\n        ],\n    },\n)\n"
  },
  {
    "path": "lely_core_libraries/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package lely_core_libraries\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.3.2 (2025-12-05)\n------------------\n\n0.3.1 (2025-06-23)\n------------------\n* Do not export deprecated Lely IO library (`#318 <https://github.com/ros-industrial/ros2_canopen/issues/318>`_)\n* Contributors: Gerry Salinas, Patrick Roncagliolo\n\n0.3.0 (2024-12-12)\n------------------\n* Add yaml dependency to package.xml of `lely_core_libraries` (`#290 <https://github.com/ros-industrial/ros2_canopen/issues/290>`_)\n\n0.2.12 (2024-04-22)\n-------------------\n* 0.2.9\n* forthcoming\n* Merge pull request `#267 <https://github.com/ros-industrial/ros2_canopen/issues/267>`_ from clalancette/clalancette/update-lely-core-hash\n  Update the lely_core_libraries hash to the latest.\n* Update the lely_core_libraries hash to the latest.\n  This will fix the building of the lely_core_libraries\n  on Ubuntu 24.04.\n* Contributors: Chris Lalancette, Vishnuprasad Prachandabhanu, ipa-vsp\n\n0.2.9 (2024-04-16)\n------------------\n* Update the lely_core_libraries hash to the latest.\n* Contributors: Chris Lalancette, Vishnuprasad Prachandabhanu\n\n0.2.8 (2024-01-19)\n------------------\n\n0.2.7 (2023-06-30)\n------------------\n* Add missing license headers and activate ament_copyright\n* Fix python versions\n* Contributors: Christoph Hellmann Santos\n\n0.2.6 (2023-06-24)\n------------------\n* Move install from external project to cmake main\n* Contributors: Christoph Hellmann Santos\n\n0.2.5 (2023-06-23)\n------------------\n* Directly install lely\n* Contributors: Christoph Hellmann Santos\n\n0.2.4 (2023-06-22)\n------------------\n* Add empy dependency for dcfgen\n* Clean up lely build folder after install for rpm build\n* Contributors: Christoph Hellmann Santos\n\n0.2.3 (2023-06-22)\n------------------\n* Fix manual dcfgen python installation on buildfarm\n* Solve buildfarm dependency issues\n* Contributors: Christoph Hellmann Santos\n\n0.2.2 (2023-06-21)\n------------------\n* Reset hard before patch applicaiton\n* Contributors: Christoph Hellmann Santos\n\n0.2.1 (2023-06-21)\n------------------\n* Do not build dcf-tools bdist in lely_core_libraries anymore, fixes buildfarm issue\n* Contributors: Christoph Hellmann Santos\n\n0.2.0 (2023-06-14)\n------------------\n* Created package\n* Contributors: Błażej Sowa, Christoph Hellmann Santos\n"
  },
  {
    "path": "lely_core_libraries/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(lely_core_libraries)\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_python REQUIRED)\nset(python_version \"python${Python3_VERSION_MAJOR}.${Python3_VERSION_MINOR}\")\n\ninclude(ExternalProject)\nExternalProject_Add(upstr_lely_core_libraries    # Name for custom target\n  #--Download step--------------\n  SOURCE_DIR ${CMAKE_CURRENT_BINARY_DIR}/upstream\n  INSTALL_DIR \"${CMAKE_INSTALL_PREFIX}\"  # Installation prefix\n  BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/build\n  GIT_REPOSITORY https://gitlab.com/lely_industries/lely-core.git\n  GIT_TAG fb735b79cab5f0cdda45bc5087414d405ef8f3ab\n  TIMEOUT 60\n  #UPDATE step apply patch to fix dcf-tools install\n  UPDATE_COMMAND\n  COMMAND git reset --hard\n  COMMAND git apply --whitespace=fix --reject ${CMAKE_CURRENT_SOURCE_DIR}/patches/0001-Fix-dcf-tools.patch\n  #CONFIGURE step execute autoreconf and configure\n  CONFIGURE_COMMAND autoreconf -i <SOURCE_DIR>\n  COMMAND <SOURCE_DIR>/configure --prefix=<INSTALL_DIR> --disable-cython --disable-doc --disable-tests --disable-static --disable-diag\n  #BUILD STEP execute make\n  BUILD_COMMAND $(MAKE) -C ${CMAKE_CURRENT_BINARY_DIR}/build\n  #INSTALL STEP do nothing as we install in main\n  INSTALL_COMMAND \"\"\n)\n\n#INSTALL lely_core_libraries - execute make install\ninstall(CODE \"execute_process(COMMAND ${CMAKE_MAKE_PROGRAM} install VERBOSE=1 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/build)\")\n\nset(lely_core_cmake_DIR \"${CMAKE_CURRENT_SOURCE_DIR}/cmake\")\ninclude(\"cmake/lely_core_libraries-extras.cmake\" NO_POLICY_SCOPE)\n\n\ninstall(\n  DIRECTORY cmake\n  DESTINATION share/${PROJECT_NAME}\n)\n\nament_python_install_package(cogen SCRIPTS_DESTINATION lib/cogen)\n\n# install entry-point script(s) in bin as well\ninstall(\n    DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/ament_cmake_python/cogen/scripts/\n    DESTINATION ${CMAKE_INSTALL_PREFIX}/bin/\n    USE_SOURCE_PERMISSIONS)\n\nament_export_include_directories(include)\nament_export_libraries(lely-can lely-co lely-coapp lely-ev lely-io2 lely-libc lely-tap lely-util)\nament_package(\n  CONFIG_EXTRAS\n  \"cmake/lely_core_libraries-extras.cmake\"\n)\n"
  },
  {
    "path": "lely_core_libraries/LICENSE",
    "content": "                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright 2022 Christoph Hellmann Santos\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n"
  },
  {
    "path": "lely_core_libraries/cmake/lely_core_libraries-extras.cmake",
    "content": "#   Copyright (c) 2023 Christoph Hellmann Santos\n#                      Błażej Sowa\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n#\nmacro(\n    generate_dcf\n    TARGET)\n    add_custom_target(\n        ${TARGET}_prepare ALL\n        COMMAND rm -rf ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/*\n        COMMAND rm -rf ${CMAKE_BINARY_DIR}/config/${TARGET}/*\n        COMMAND mkdir -p ${CMAKE_BINARY_DIR}/config/${TARGET}\n        #COMMAND mkdir -p ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/\n    )\n\n    add_custom_target(\n        ${TARGET} ALL\n        DEPENDS ${TARGET}_prepare\n    )\n\n    add_custom_command(\n        TARGET ${TARGET} POST_BUILD\n        COMMAND sed 's|@BUS_CONFIG_PATH@|${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}|g'\n            ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/bus.yml > ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml\n        COMMAND dcfgen -v -d ${CMAKE_BINARY_DIR}/config/${TARGET}/ -rS ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml\n        WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/\n    )\n\n    install(DIRECTORY\n        ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/\n        DESTINATION share/${PROJECT_NAME}/config/${TARGET}/\n        PATTERN \"bus.yml\" EXCLUDE\n    )\n\n    install(DIRECTORY\n        ${CMAKE_BINARY_DIR}/config/${TARGET}/\n        DESTINATION share/${PROJECT_NAME}/config/${TARGET}/\n    )\n\nendmacro()\n\nmacro(\n    cogen_dcf\n    TARGET)\n    add_custom_target(\n        ${TARGET}_prepare ALL\n        COMMAND rm -rf ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/*\n        COMMAND rm -rf ${CMAKE_BINARY_DIR}/config/${TARGET}/*\n        COMMAND mkdir -p ${CMAKE_BINARY_DIR}/config/${TARGET}\n        #COMMAND mkdir -p ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}/\n    )\n\n    add_custom_target(\n        ${TARGET} ALL\n        DEPENDS ${TARGET}_prepare\n    )\n\n    add_custom_command(\n        TARGET ${TARGET} POST_BUILD\n        COMMAND cogen --input-file ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/bus.yml --output-file ${CMAKE_BINARY_DIR}/config/${TARGET}/preprocessed_bus.yml\n        COMMAND sed 's|@BUS_CONFIG_PATH@|${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/config/${TARGET}|g'\n            ${CMAKE_BINARY_DIR}/config/${TARGET}/preprocessed_bus.yml > ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml\n        COMMAND dcfgen -v -d ${CMAKE_BINARY_DIR}/config/${TARGET}/ -rS ${CMAKE_BINARY_DIR}/config/${TARGET}/bus.yml\n        WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/\n    )\n\n    install(DIRECTORY\n        ${CMAKE_CURRENT_SOURCE_DIR}/config/${TARGET}/\n        DESTINATION share/${PROJECT_NAME}/config/${TARGET}/\n        PATTERN \"bus.yml\" EXCLUDE\n    )\n\n    install(DIRECTORY\n        ${CMAKE_BINARY_DIR}/config/${TARGET}/\n        DESTINATION share/${PROJECT_NAME}/config/${TARGET}/\n    )\n\nendmacro()\n\nmacro(dcfgen INPUT_DIR FILE OUTPUT_DIR)\n    message(DEPRECATION \"dcfgen macro is depreciated and will be remove in beta version. Use generate_dcf instead.\")\n    make_directory(${OUTPUT_DIR})\n    add_custom_target(\n        ${FILE} ALL\n        COMMAND \"dcfgen\" \"-d\" ${OUTPUT_DIR} \"-rS\" ${INPUT_DIR}${FILE}\n        WORKING_DIRECTORY ${INPUT_DIR}\n        )\nendmacro()\n"
  },
  {
    "path": "lely_core_libraries/cogen/__init__.py",
    "content": ""
  },
  {
    "path": "lely_core_libraries/cogen/cogen.py",
    "content": "#    Copyright 2022 Christoph Hellmann Santos\n#\n#    Licensed under the Apache License, Version 2.0 (the \"License\");\n#    you may not use this file except in compliance with the License.\n#    You may obtain a copy of the License at\n#\n#        http://www.apache.org/licenses/LICENSE-2.0\n#\n#    Unless required by applicable law or agreed to in writing, software\n#    distributed under the License is distributed on an \"AS IS\" BASIS,\n#    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#    See the License for the specific language governing permissions and\n#    limitations under the License.\n\nimport yaml\nimport argparse\nfrom dataclasses import dataclass\nfrom dcfgen.cli import Master, Slave\n\n\ndef main():\n    parser = argparse.ArgumentParser(\n        description=\"Expands the CANopen bus.yml for further processing.\"\n    )\n    parser.add_argument(\"--input-file\", type=str, help=\"The name of the input file\", required=True)\n    parser.add_argument(\n        \"--output-file\", type=str, help=\"The name of the output file\", required=True\n    )\n    args = parser.parse_args()\n\n    with open(args.input_file) as input:\n        cfg = yaml.load(input, yaml.FullLoader)\n\n    master = {}\n    if \"master\" not in cfg:\n        print(\"Found no master.\")\n        return\n    else:\n        master = cfg[\"master\"]\n\n    nodes = {}\n    if \"nodes\" not in cfg:\n        print(\"Found no nodes entry.\")\n        return\n    else:\n        nodes = cfg[\"nodes\"]\n\n    options = {}\n    if \"options\" in cfg:\n        options = cfg[\"options\"]\n\n    defaults = {}\n    if \"defaults\" in cfg:\n        defaults = cfg[\"defaults\"]\n\n    # add defaults to each node\n    for node_name in nodes:\n        for entry_name in defaults:\n            nodes[node_name][entry_name] = defaults[entry_name]\n\n    modified_file = {}\n    modified_file[\"options\"] = options\n    # modified_file[\"defaults\"] = defaults\n    modified_file[\"master\"] = master\n    for node_name in nodes:\n        modified_file[node_name] = nodes[node_name]\n\n    with open(args.output_file, mode=\"w\") as output:\n        yaml.dump(modified_file, output)\n\n    return\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "lely_core_libraries/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>lely_core_libraries</name>\n  <version>0.3.2</version>\n  <description>\n    ROS wrapper for lely-core-libraries\n  </description>\n  <maintainer email=\"christoph.hellmann.santos@ipa.fraunhofer.de\">Christoph Hellmann Santos</maintainer>\n  <license>Apache-2.0</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <build_depend>git</build_depend>\n  <build_depend>autoconf</build_depend>\n  <build_depend>automake</build_depend>\n  <build_depend>libtool</build_depend>\n  <depend>python3-empy</depend>\n  <depend>python3-yaml</depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "lely_core_libraries/patches/0001-Fix-dcf-tools.patch",
    "content": "From 1fcc088cdf64bee181f1141077af01267cc224ad Mon Sep 17 00:00:00 2001\nFrom: Christoph Hellmann Santos <christoph.hellmann.santos@ipa.fraunhofer.de>\nDate: Tue, 27 Jun 2023 10:15:06 +0200\nSubject: [PATCH] Fix dcf-tools\n\n---\n configure.ac                 | 10 +++-------\n python/dcf-tools/Makefile.am | 23 +++++------------------\n 2 files changed, 8 insertions(+), 25 deletions(-)\n\ndiff --git a/configure.ac b/configure.ac\nindex 1dd9410d..c274636b 100644\n--- a/configure.ac\n+++ b/configure.ac\n@@ -569,19 +569,15 @@ AC_ARG_ENABLE([python],\n \tAS_HELP_STRING([--disable-python], [disable Python tools and bindings]))\n \n AM_CONDITIONAL([HAVE_PYTHON2], [false])\n-AC_ARG_ENABLE([python2],\n-\tAS_HELP_STRING([--disable-python2], [disable Python 2 tools and bindings]))\n-AS_IF([test \"$enable_python\" == \"no\"], [enable_python2=no])\n-AS_IF([test \"$enable_python2\" != \"no\"], [\n-\tAX_CHECK_PYTHON([2], [AM_CONDITIONAL([HAVE_PYTHON2], [true])])\n-])\n \n AM_CONDITIONAL([HAVE_PYTHON3], [false])\n AC_ARG_ENABLE([python3],\n \tAS_HELP_STRING([--disable-python3], [disable Python 3 tools and bindings]))\n AS_IF([test \"$enable_python\" == \"no\"], [enable_python3=no])\n AS_IF([test \"$enable_python3\" != \"no\"], [\n-\tAX_CHECK_PYTHON([3], [AM_CONDITIONAL([HAVE_PYTHON3], [true])])\n+\tAM_PATH_PYTHON([3.3],, [:])\n+\tAC_SUBST(PYTHON3, \"$PYTHON\")\n+\tAM_CONDITIONAL([HAVE_PYTHON3], [test \"$PYTHON\" != :])\n ])\n \n AM_CONDITIONAL([NO_CYTHON], [false])\ndiff --git a/python/dcf-tools/Makefile.am b/python/dcf-tools/Makefile.am\nindex 9852c84a..dd5cdfa0 100644\n--- a/python/dcf-tools/Makefile.am\n+++ b/python/dcf-tools/Makefile.am\n@@ -23,30 +23,17 @@ EXTRA_DIST += setup.py\n build_base = $(realpath $(builddir))/build\n dist_dir = $(realpath $(builddir))/dist\n \n-all-local: python-sdist python-bdist_wheel\n-\n clean-local:\n \trm -rf $(build_base) $(dist_dir) $(srcdir)/*.egg-info $(builddir)/*.egg-info\n \n install-exec-local: python-install\n \n-.PHONY: python-bdist_wheel\n-python-bdist_wheel:\n-if HAVE_PYTHON3\n-\t@$(PYTHON3_ENV) $(PYTHON3) $(srcdir)/setup.py \\\n-\t\tbdist_wheel --dist-dir $(dist_dir)\n-endif\n-\n .PHONY: python-install\n python-install:\n if HAVE_PYTHON3\n-\t@$(PYTHON3_ENV) $(PYTHON3) $(srcdir)/setup.py \\\n-\t\tinstall --prefix $(DESTDIR)$(prefix) --root /\n-endif\n-\n-.PHONY: python-sdist\n-python-sdist:\n-if HAVE_PYTHON3\n-\t@cd $(srcdir); $(PYTHON3_ENV) $(PYTHON3) setup.py \\\n-\t\tsdist --dist-dir $(dist_dir)\n+\t@cd $(srcdir) && $(PYTHON3_ENV) $(PYTHON3) setup.py \\\n+\t\tegg_info build install --record install.log \\\n+\t\t--install-scripts $(DESTDIR)$(prefix)/bin/ \\\n+\t\t--install-lib $(DESTDIR)$(prefix)/lib/python$(PYTHON_VERSION)/site-packages/ \\\n+\t\t--single-version-externally-managed\n endif\n-- \n2.34.1\n\n"
  },
  {
    "path": "lely_core_libraries/setup.cfg",
    "content": "[options.entry_points]\nconsole_scripts =\n    cogen = cogen.cogen:main\n"
  }
]