[
  {
    "path": ".clang-format",
    "content": "---\nBasedOnStyle:  Google\nColumnLimit:    120\nMaxEmptyLinesToKeep: 1\nSortIncludes: false\n\nStandard:        Auto\nIndentWidth:     2\nTabWidth:        2\nUseTab:          Never\nAccessModifierOffset: -2\nConstructorInitializerIndentWidth: 2\nNamespaceIndentation: None\nContinuationIndentWidth: 4\nIndentCaseLabels: true\nIndentFunctionDeclarationAfterType: false\n\nAlignEscapedNewlinesLeft: false\nAlignTrailingComments: true\n\nAllowAllParametersOfDeclarationOnNextLine: false\nExperimentalAutoDetectBinPacking: false\nObjCSpaceBeforeProtocolList: true\nCpp11BracedListStyle: false\n\nAllowShortBlocksOnASingleLine: true\nAllowShortIfStatementsOnASingleLine: false\nAllowShortLoopsOnASingleLine: false\nAllowShortFunctionsOnASingleLine: None\nAllowShortCaseLabelsOnASingleLine: false\n\nAlwaysBreakTemplateDeclarations: true\nAlwaysBreakBeforeMultilineStrings: false\nBreakBeforeBinaryOperators: false\nBreakBeforeTernaryOperators: false\nBreakConstructorInitializersBeforeComma: true\n\nBinPackParameters: true\nConstructorInitializerAllOnOneLineOrOnePerLine: true\nDerivePointerBinding: false\nPointerBindsToType: true\n\nPenaltyExcessCharacter: 50\nPenaltyBreakBeforeFirstCallParameter: 30\nPenaltyBreakComment: 1000\nPenaltyBreakFirstLessLess: 10\nPenaltyBreakString: 100\nPenaltyReturnTypeOnItsOwnLine: 50\n\nSpacesBeforeTrailingComments: 2\nSpacesInParentheses: false\nSpacesInAngles:  false\nSpaceInEmptyParentheses: false\nSpacesInCStyleCastParentheses: false\nSpaceAfterCStyleCast: false\nSpaceAfterControlStatementKeyword: true\nSpaceBeforeAssignmentOperators: true\n\n# Configure each individual brace in BraceWrapping\nBreakBeforeBraces: Custom\n\n# Control of individual brace wrapping cases\nBraceWrapping:\n    AfterCaseLabel: true\n    AfterClass: true\n    AfterControlStatement: true\n    AfterEnum: true\n    AfterFunction: true\n    AfterNamespace: true\n    AfterStruct: true\n    AfterUnion: true\n    BeforeCatch: true\n    BeforeElse: true\n    IndentBraces: false\n...\n"
  },
  {
    "path": ".dockerfilelintrc",
    "content": "rules:\n  apt-get-update_require_install: off\n"
  },
  {
    "path": ".flake8",
    "content": "[flake8]\n# The line length here has to match the black config in pyproject.toml\nmax-line-length = 120\nexclude =\n    .git,\n    __pycache__\nextend-ignore =\n    # See https://github.com/PyCQA/pycodestyle/issues/373\n    E203,\n    E741,\n"
  },
  {
    "path": ".github/workflows/github-actions.yml",
    "content": "name: Build and run ROS tests\non:\n  push:\n  pull_request:\n  workflow_dispatch:\n    inputs:\n      debug_enabled:\n        type: boolean\n        description: 'Run the build with tmate debugging enabled (https://github.com/marketplace/actions/debugging-with-tmate)'\n        required: false\n        default: false\njobs:\n  build:\n    strategy:\n      matrix:\n        rosdistro: [noetic]\n    runs-on: ubuntu-latest\n    container:\n      image: ros:${{ matrix.rosdistro }}-ros-core\n    steps:\n    # Enable tmate debugging of manually-triggered workflows if the input option was provided\n    - name: Setup tmate session\n      uses: mxschmitt/action-tmate@v3\n      if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }}\n      with:\n        detached: true\n    - name: Install apt dependencies\n      run: |\n        sudo apt-get update\n        sudo apt-get install -y build-essential clang-format-10 file git python3-catkin-lint python3-catkin-tools python3-pip python3-rosdep\n    - name: Install pip dependencies\n      run: pip install pre-commit\n    - name: Checkout repository\n      uses: actions/checkout@v5\n      with:\n        path: src/mir_robot\n    - name: Use rosdep to install remaining dependencies\n      run: |\n        sudo rosdep init\n        rosdep update --include-eol-distros\n        rosdep install --from-paths src -i -y --rosdistro ${{ matrix.rosdistro }}\n    - name: Build\n      run: |\n        . /opt/ros/${{ matrix.rosdistro }}/setup.sh\n        catkin init\n        catkin config -j 1 -p 1\n        catkin build --limit-status-rate 0.1 --no-notify\n        catkin build --limit-status-rate 0.1 --no-notify --make-args tests\n    - name: Run tests\n      run: |\n        . devel/setup.sh\n        catkin run_tests\n        catkin_test_results\n    - name: Run pre-commit hooks\n      run: |\n        cd src/mir_robot\n        pre-commit run -a\n"
  },
  {
    "path": ".gitignore",
    "content": "*.pyc\n"
  },
  {
    "path": ".markdownlint.yaml",
    "content": "## Default state for all rules\n#default: true\n\n## Path to configuration file to extend\n#extends: null\n\n## MD001/heading-increment : Heading levels should only increment by one level at a time : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md001.md\n#MD001: true\n\n## MD003/heading-style : Heading style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md003.md\nMD003: false\n#MD003:\n#  # Heading style\n#  style: \"consistent\"\n\n## MD004/ul-style : Unordered list style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md004.md\nMD004:\n  # List style\n  style: \"sublist\"\n\n## MD005/list-indent : Inconsistent indentation for list items at the same level : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md005.md\n#MD005: true\n\n## MD007/ul-indent : Unordered list indentation : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md007.md\n#MD007:\n#  # Spaces for indent\n#  indent: 2\n#  # Whether to indent the first level of the list\n#  start_indented: false\n#  # Spaces for first level indent (when start_indented is set)\n#  start_indent: 2\n\n## MD009/no-trailing-spaces : Trailing spaces : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md009.md\n#MD009:\n#  # Spaces for line break\n#  br_spaces: 2\n#  # Allow spaces for empty lines in list items\n#  list_item_empty_lines: false\n#  # Include unnecessary breaks\n#  strict: false\n\n## MD010/no-hard-tabs : Hard tabs : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md010.md\n#MD010:\n#  # Include code blocks\n#  code_blocks: true\n#  # Fenced code languages to ignore\n#  ignore_code_languages: []\n#  # Number of spaces for each hard tab\n#  spaces_per_tab: 1\n\n## MD011/no-reversed-links : Reversed link syntax : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md011.md\n#MD011: true\n\n## MD012/no-multiple-blanks : Multiple consecutive blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md012.md\nMD012:\n  # Consecutive blank lines\n  maximum: 2\n\n## MD013/line-length : Line length : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md013.md\nMD013:\n  # Number of characters\n  line_length: 120\n  # Number of characters for headings\n  heading_line_length: 80\n  # Number of characters for code blocks\n  code_block_line_length: 80\n  # Include code blocks\n  code_blocks: false\n  # Include tables\n  tables: false\n  # Include headings\n  headings: true\n  # Strict length checking\n  strict: false\n  # Stern length checking\n  stern: false\n\n## MD014/commands-show-output : Dollar signs used before commands without showing output : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md014.md\n#MD014: true\n\n## MD018/no-missing-space-atx : No space after hash on atx style heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md018.md\n#MD018: true\n\n## MD019/no-multiple-space-atx : Multiple spaces after hash on atx style heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md019.md\n#MD019: true\n\n## MD020/no-missing-space-closed-atx : No space inside hashes on closed atx style heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md020.md\n#MD020: true\n\n## MD021/no-multiple-space-closed-atx : Multiple spaces inside hashes on closed atx style heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md021.md\n#MD021: true\n\n## MD022/blanks-around-headings : Headings should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md022.md\n#MD022:\n#  # Blank lines above heading\n#  lines_above: 1\n#  # Blank lines below heading\n#  lines_below: 1\n\n## MD023/heading-start-left : Headings must start at the beginning of the line : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md023.md\n#MD023: true\n\n## MD024/no-duplicate-heading : Multiple headings with the same content : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md024.md\nMD024:\n  # Only check sibling headings\n  siblings_only: true\n\n## MD025/single-title/single-h1 : Multiple top-level headings in the same document : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md025.md\n#MD025:\n#  # RegExp for matching title in front matter\n#  front_matter_title: \"^\\\\s*title\\\\s*[:=]\"\n#  # Heading level\n#  level: 1\n\n## MD026/no-trailing-punctuation : Trailing punctuation in heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md026.md\n#MD026:\n#  # Punctuation characters\n#  punctuation: \".,;:!。，；：！\"\n\n## MD027/no-multiple-space-blockquote : Multiple spaces after blockquote symbol : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md027.md\n#MD027:\n#  # Include list items\n#  list_items: true\n\n## MD028/no-blanks-blockquote : Blank line inside blockquote : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md028.md\n#MD028: true\n\n## MD029/ol-prefix : Ordered list item prefix : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md029.md\nMD029:\n  # List style\n  style: \"ordered\"\n\n## MD030/list-marker-space : Spaces after list markers : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md030.md\n#MD030:\n#  # Spaces for single-line unordered list items\n#  ul_single: 1\n#  # Spaces for single-line ordered list items\n#  ol_single: 1\n#  # Spaces for multi-line unordered list items\n#  ul_multi: 1\n#  # Spaces for multi-line ordered list items\n#  ol_multi: 1\n\n## MD031/blanks-around-fences : Fenced code blocks should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md031.md\n#MD031:\n#  # Include list items\n#  list_items: true\n\n## MD032/blanks-around-lists : Lists should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md032.md\n#MD032: true\n\n## MD033/no-inline-html : Inline HTML : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md033.md\n#MD033:\n#  # Allowed elements\n#  allowed_elements: []\n\n## MD034/no-bare-urls : Bare URL used : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md034.md\nMD034: false\n\n## MD035/hr-style : Horizontal rule style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md035.md\n#MD035:\n#  # Horizontal rule style\n#  style: \"consistent\"\n\n## MD036/no-emphasis-as-heading : Emphasis used instead of a heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md036.md\n#MD036:\n#  # Punctuation characters\n#  punctuation: \".,;:!?。，；：！？\"\n\n## MD037/no-space-in-emphasis : Spaces inside emphasis markers : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md037.md\n#MD037: true\n\n## MD038/no-space-in-code : Spaces inside code span elements : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md038.md\n#MD038: true\n\n## MD039/no-space-in-links : Spaces inside link text : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md039.md\n#MD039: true\n\n## MD040/fenced-code-language : Fenced code blocks should have a language specified : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md040.md\n#MD040:\n#  # List of languages\n#  allowed_languages: []\n#  # Require language only\n#  language_only: false\n\n## MD041/first-line-heading/first-line-h1 : First line in a file should be a top-level heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md041.md\n#MD041:\n#  # Allow content before first heading\n#  allow_preamble: false\n#  # RegExp for matching title in front matter\n#  front_matter_title: \"^\\\\s*title\\\\s*[:=]\"\n#  # Heading level\n#  level: 1\n\n## MD042/no-empty-links : No empty links : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md042.md\n#MD042: true\n\n## MD043/required-headings : Required heading structure : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md043.md\n#MD043:\n#  # List of headings\n#  headings: []\n#  # Match case of headings\n#  match_case: false\n\n## MD044/proper-names : Proper names should have the correct capitalization : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md044.md\n#MD044:\n#  # List of proper names\n#  names: []\n#  # Include code blocks\n#  code_blocks: true\n#  # Include HTML elements\n#  html_elements: true\n\n## MD045/no-alt-text : Images should have alternate text (alt text) : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md045.md\nMD045: true\n\n## MD046/code-block-style : Code block style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md046.md\n#MD046:\n#  # Block style\n#  style: \"consistent\"\n\n## MD047/single-trailing-newline : Files should end with a single newline character : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md047.md\n#MD047: true\n\n## MD048/code-fence-style : Code fence style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md048.md\n#MD048:\n#  # Code fence style\n#  style: \"consistent\"\n\n## MD049/emphasis-style : Emphasis style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md049.md\n#MD049:\n#  # Emphasis style\n#  style: \"consistent\"\n\n## MD050/strong-style : Strong style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md050.md\n#MD050:\n#  # Strong style\n#  style: \"consistent\"\n\n## MD051/link-fragments : Link fragments should be valid : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md051.md\n#MD051:\n#  # Ignore case of fragments\n#  ignore_case: false\n#  # Pattern for ignoring additional fragments\n#  ignored_pattern: \"\"\n\n## MD052/reference-links-images : Reference links and images should use a label that is defined : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md052.md\n#MD052:\n#  # Ignored link labels\n#  ignored_labels:\n#    - \"x\"\n#  # Include shortcut syntax\n#  shortcut_syntax: false\n\n## MD053/link-image-reference-definitions : Link and image reference definitions should be needed : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md053.md\n#MD053:\n#  # Ignored definitions\n#  ignored_definitions:\n#    - \"//\"\n\n## MD054/link-image-style : Link and image style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md054.md\n#MD054:\n#  # Allow autolinks\n#  autolink: true\n#  # Allow inline links and images\n#  inline: true\n#  # Allow full reference links and images\n#  full: true\n#  # Allow collapsed reference links and images\n#  collapsed: true\n#  # Allow shortcut reference links and images\n#  shortcut: true\n#  # Allow URLs as inline links\n#  url_inline: true\n\n## MD055/table-pipe-style : Table pipe style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md055.md\n#MD055:\n#  # Table pipe style\n#  style: \"consistent\"\n\n## MD056/table-column-count : Table column count : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md056.md\n#MD056: true\n\n## MD058/blanks-around-tables : Tables should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md058.md\n#MD058: true\n\n## MD059/descriptive-link-text : Link text should be descriptive : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md059.md\n#MD059:\n#  # Prohibited link texts\n#  prohibited_texts:\n#    - \"click here\"\n#    - \"here\"\n#    - \"link\"\n#    - \"more\"\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\n\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-case-conflict\n      - id: check-executables-have-shebangs\n      - id: check-docstring-first\n      - id: check-merge-conflict\n      - id: check-shebang-scripts-are-executable\n      - id: check-symlinks\n      - id: check-vcs-permalinks\n      - id: check-xml\n      - id: check-yaml\n      - id: debug-statements\n      - id: end-of-file-fixer\n        exclude: &excludes |\n          (?x)^(\n              .*\\.blend|\n              .*\\.dae|\n              .*\\.mtl|\n              .*\\.obj|\n              .*\\.pgm|\n              .*\\.step|\n              .*\\.stl\n          )$\n      - id: fix-byte-order-marker\n      - id: mixed-line-ending\n        exclude: *excludes\n      - id: trailing-whitespace\n        exclude: *excludes\n\n  - repo: https://github.com/psf/black\n    rev: 24.3.0\n    hooks:\n      - id: black\n\n  - repo: https://github.com/PyCQA/flake8.git\n    rev: 7.0.0\n    hooks:\n    - id: flake8\n\n  - repo: https://github.com/detailyang/pre-commit-shell.git\n    rev: v1.0.6\n    hooks:\n    - id: shell-lint\n      args: [--external-sources]\n\n  - repo: https://github.com/igorshubovych/markdownlint-cli\n    rev: v0.45.0\n    hooks:\n    - id: markdownlint\n      language_version: 24.2.0\n\n  - repo: https://github.com/pryorda/dockerfilelint-precommit-hooks\n    rev: v0.1.0\n    hooks:\n    - id: dockerfilelint\n\n  - repo: https://github.com/Lucas-C/pre-commit-hooks\n    rev: v1.5.1\n    hooks:\n      - id: insert-license\n        files: \\.py$\n        exclude: |\n          (?x)^(\n              .*setup\\.py|\n              .*__init__\\.py|\n              .*test_copyright\\.py|\n              .*test_pep257\\.py|\n              mir_driver/nodes/tf_remove_child_frames\\.py|\n              mir_navigation/mprim/genmprim_unicycle_highcost_5cm\\.py\n          )$\n        args:\n          - --license-filepath\n          - LICENSE\n\n  - repo: https://github.com/pycqa/pydocstyle\n    rev: 6.3.0\n    hooks:\n      - id: pydocstyle\n        args:\n        - --ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404   # same as https://github.com/ament/ament_lint/blob/bbdaa17224f3b8dfece53662b65d7d18b7404b6a/ament_pep257/ament_pep257/main.py#L43-L55\n\n  - repo: local\n    hooks:\n      - id: clang-format\n        name: clang-format\n        description: Format files with ClangFormat.\n        entry: clang-format-10\n        language: system\n        files: \\.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|proto|vert)$\n        args: [ \"-fallback-style=none\", \"-i\" ]\n      - id: catkin_lint\n        name: catkin_lint\n        description: Check package.xml and cmake files\n        entry: catkin_lint .\n        language: system\n        always_run: true\n        pass_filenames: false\n        args: [ \"--strict\" ]\n"
  },
  {
    "path": "Dockerfile-noetic",
    "content": "FROM ros:noetic-ros-core\n\nRUN apt-get update \\\n    && apt-get install -y --no-install-recommends build-essential python3-rosdep python3-catkin-lint python3-catkin-tools \\\n    && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/*\n\n# Install pre-commit hooks to /root/.cache/pre-commit/\nRUN apt-get update -qq \\\n    && apt-get install -y -qq --no-install-recommends git python3-pip ruby shellcheck clang-format-10 python3-catkin-lint \\\n    && rm -rf /var/lib/apt/lists/*\nRUN pip3 install pre-commit\nRUN mkdir -p /tmp/pre-commit\nCOPY .pre-commit-config.yaml /tmp/pre-commit/\nRUN cd /tmp/pre-commit \\\n    && git init \\\n    && pre-commit install-hooks \\\n    && rm -rf /tmp/pre-commit\n\n# Create ROS workspace\nCOPY . /ws/src/mir_robot\nWORKDIR /ws\n\n# Use rosdep to install all dependencies (including ROS itself)\nRUN rosdep init \\\n    && rosdep update --include-eol-distros \\\n    && apt-get update \\\n    && DEBIAN_FRONTEND=noninteractive rosdep install --from-paths src -i -y --rosdistro noetic \\\n    && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/*\n\nRUN /bin/bash -c \"source /opt/ros/noetic/setup.bash && \\\n    catkin init && \\\n    catkin config --install -j 1 -p 1 && \\\n    catkin build --limit-status-rate 0.1 --no-notify && \\\n    catkin build --limit-status-rate 0.1 --no-notify --make-args tests\"\n"
  },
  {
    "path": "LICENSE",
    "content": "Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n\nRedistribution and use in source and binary forms, with or without\nmodification, 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\nTHIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\nAND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\nARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE\nLIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\nCONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\nSUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\nINTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\nCONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\nARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\nPOSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "README.md",
    "content": "mir_robot\n=========\n\nThis repo contains a ROS driver and ROS configuration files (URDF description,\nGazebo launch files, move_base config, bringup launch files, message and action\ndescriptions) for the [MiR robots](http://www.mobile-industrial-robots.com/).\nThis is a community project created by us ([DFKI](https://www.dfki.de/), the\nGerman Research Center for Artificial Intelligence) to use the MiR Robots with\nROS. We are not affiliated with Mobile Industrial Robots. If you find a bug or\nmissing feature in this software, please report it on the\n[issue tracker](https://github.com/DFKI-NI/mir_robot/issues).\n\nSupported MiR robots and software versions\n------------------------------------------\n\nThis repo has been confirmed to work with the following robots:\n\n* MiR 100\n* MiR 200\n* MiR 250\n* MiR 500\n\nIt probably also works with the MiR1000. If you can test it on one\nof those, please let us know if it works.\n\nThis repo has been tested with the following MiR software versions:\n\n* 2.8.3.1\n* 2.13.4.1\n* 2.13.5.3\n\nYou can try if it works with other versions, but these are the ones that are\nknown to work.\n\n:warning: **Do NOT update to the upcoming version 3.0; it is very well possible\nthat this repo will no longer work with this version!**\n\n\nPackage overview\n----------------\n\n* `mir_actions`: Action definitions for the MiR robot\n* `mir_description`: URDF description of the MiR robot\n* `mir_dwb_critics`: Plugins for the dwb_local_planner used in Gazebo\n* `mir_driver`: A reverse ROS bridge for the MiR robot\n* `mir_gazebo`: Simulation specific launch and configuration files for the MiR robot\n* `mir_msgs`: Message definitions for the MiR robot\n* `mir_navigation`: move_base launch and configuration files\n\n\nInstallation\n------------\n\nYou can chose between binary and source install below. If you don't want to\nmodify the source, the binary install is preferred (if `mir_robot` binary\npackages are available for your ROS distro). The instructions below use the ROS\ndistro `noetic` as an example; if you use a different distro (e.g.  `melodic`),\nreplace all occurrences of the string `noetic` by your distro name in the\ninstructions.\n\n### Preliminaries\n\nIf you haven't already installed ROS on your PC, you need to add the ROS apt\nrepository. This step is necessary for either binary or source install.\n\n```bash\nsudo sh -c 'echo \"deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main\" > /etc/apt/sources.list.d/ros-latest.list'\nwget http://packages.ros.org/ros.key -O - | sudo apt-key add -\nsudo apt-get update -qq\n```\n\n### Binary install\n\nFor a binary install, it suffices to run this command:\n\n```bash\nsudo apt install ros-noetic-mir-robot\n```\n\nSee the tables at the end of this README for a list of ROS distros for which\nbinary packages are available.\n\n### Source install\n\nFor a source install, run the commands below instead of the command from the\n\"binary install\" section.\n\n```bash\n# create a catkin workspace\nmkdir -p ~/catkin_ws/src\ncd ~/catkin_ws/src/\n\n# clone mir_robot into the catkin workspace\ngit clone -b noetic https://github.com/DFKI-NI/mir_robot.git\n\n# use rosdep to install all dependencies (including ROS itself)\nsudo apt-get update -qq\nsudo apt-get install -qq -y python-rosdep\nsudo rosdep init\nrosdep update --include-eol-distros\nrosdep install --from-paths ./ -i -y --rosdistro noetic\n\n# build all packages in the catkin workspace\nsource /opt/ros/noetic/setup.bash\ncatkin_init_workspace\ncd ~/catkin_ws\ncatkin_make -DCMAKE_BUILD_TYPE=RelWithDebugInfo\n```\n\nIn case you encounter problems, please compare the commands above to the build\nstep in [`.github/workflows/github-actions.yml`](.github/workflows/github-actions.yml); that should always have the most\nrecent list of commands.\n\nYou should add the following line to the end of your `~/.bashrc`, and then\nclose and reopen all terminals:\n\n```bash\nsource ~/catkin_ws/devel/setup.bash\n```\n\nGazebo demo (existing map)\n--------------------------\n\nhttps://user-images.githubusercontent.com/320188/145610491-2afeb46c-3729-4106-ab9c-6681b5dd9d2e.mp4\n\n```bash\n### gazebo:\nroslaunch mir_gazebo mir_maze_world.launch\nrosservice call /gazebo/unpause_physics   # or click the \"start\" button in the Gazebo GUI\n\n### localization:\nroslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0\n# or alternatively: roslaunch mir_gazebo fake_localization.launch delta_x:=-10.0 delta_y:=-10.0\n\n# navigation:\nroslaunch mir_navigation start_planner.launch \\\n    map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \\\n    virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml\nrviz -d $(rospack find mir_navigation)/rviz/navigation.rviz\n```\n\nNow, you can use the \"2D Nav Goal\" tool in RViz to set a navigation goal for move_base.\n\n\nGazebo demo (mapping)\n---------------------\n\n```bash\n### gazebo:\nroslaunch mir_gazebo mir_maze_world.launch\nrosservice call /gazebo/unpause_physics   # or click the \"start\" button in the Gazebo GUI\n\n### mapping:\nroslaunch mir_navigation hector_mapping.launch\n\n# navigation:\nroslaunch mir_navigation move_base.xml with_virtual_walls:=false\nrviz -d $(rospack find mir_navigation)/rviz/navigation.rviz\n```\n\nGazebo demo (MiR 250 in warehouse Gazebo world)\n-----------------------------------------------\n\nhttps://user-images.githubusercontent.com/320188/171613044-639f3ab2-fe84-4839-acfc-d0642f8869b3.mp4\n\nThis repo contains URDF descriptions for the MiR 100 (default) and the MiR 250.\nYou can switch to the MiR 250 by adding **`mir_type:=mir_250`** to the gazebo\nroslaunch command. You can also select another Gazebo world using the\n**`world_name`** argument. For example, the video above was generated using the\nfollowing commands:\n\n```bash\ncd <your catkin workspace>\ngit clone -b ros1 https://github.com/aws-robotics/aws-robomaker-small-warehouse-world.git\ncatkin build\n\nroslaunch mir_gazebo mir_empty_world.launch \\\n        world_name:=$(rospack find aws_robomaker_small_warehouse_world)/worlds/no_roof_small_warehouse.world \\\n        mir_type:=mir_250\n```\n\n... and then running the remaining commands from the \"mapping\" section above.\n\n\nGazebo demo (multiple robots)\n-----------------------------\n\nIf you want to spawn multiple robots into Gazebo, you unfortunately have to\nhard-code the name of the second robot into the `mir_empty_world.launch` file,\nlike this:\n\n```diff\ndiff --git i/mir_gazebo/launch/mir_empty_world.launch w/mir_gazebo/launch/mir_empty_world.launch\nindex 27b9159..7773fae 100644\n--- i/mir_gazebo/launch/mir_empty_world.launch\n+++ w/mir_gazebo/launch/mir_empty_world.launch\n@@ -17,6 +17,10 @@\n       <remap from=\"$(arg namespace)/mobile_base_controller/cmd_vel\" to=\"$(arg namespace)/cmd_vel\" />\n       <remap from=\"$(arg namespace)/mobile_base_controller/odom\"    to=\"$(arg namespace)/odom\" />\n\n+      <remap from=\"mir2/joint_states\"                   to=\"mir2/mir/joint_states\" />\n+      <remap from=\"mir2/mobile_base_controller/cmd_vel\" to=\"mir2/cmd_vel\" />\n+      <remap from=\"mir2/mobile_base_controller/odom\"    to=\"mir2/odom\" />\n+\n       <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\n         <arg name=\"world_name\" value=\"$(arg world_name)\"/>\n         <arg name=\"paused\" value=\"true\" />\n```\n\nThen you can run the simulation like this:\n\n```bash\n# start Gazebo + first MiR\nroslaunch mir_gazebo mir_maze_world.launch tf_prefix:=mir\n\n# first MiR: start localization, navigation + rviz\nroslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 tf_prefix:=mir\nroslaunch mir_navigation start_planner.launch \\\n        map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \\\n        virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir/\nROS_NAMESPACE=mir rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz\n\n# spawn second MiR into Gazebo\nroslaunch mir_gazebo mir_gazebo_common.launch robot_x:=-2 robot_y:=-2 tf_prefix:=mir2 model_name:=mir2 __ns:=mir2\n\n# second MiR: start localization, navigation + rviz\nroslaunch mir_navigation amcl.launch initial_pose_x:=8.0 initial_pose_y:=8.0 tf_prefix:=mir2\nroslaunch mir_navigation start_planner.launch \\\n        map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \\\n        virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir2/\nROS_NAMESPACE=mir2 rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz\n```\n\n\nRunning the driver on the real robot\n------------------------------------\n\n### Start up the robot\n\n* switch on MiR base\n\n\n### Connect to the MiR web interface\n\n* connect to MiR_R??? wifi (password \"mirex4you\"), for example from your Android phone/tablet\n* disable other network connections (mobile data / LAN / etc.)\n* open mir.com (192.168.12.20) in Chrome (!)\n* log in (admin/mir4you)\n\n\n### Synchronize system time\n\nThe internal robot PC's is not synchronized (for example via NTP), so it tends\nto get out of sync quickly (about 1 second per day!). This causes TF transforms\ntiming out etc. and can be seen using `tf_monitor` (the \"Max Delay\" is about\n3.3 seconds, but should be less than 0.1 seconds):\n\n```text\n$ rosrun tf tf_monitor\nFrames:\nFrame: /back_laser_link published by unknown_publisher Average Delay: 3.22686 Max Delay: 3.34766\nFrame: /base_footprint published by unknown_publisher Average Delay: 3.34273 Max Delay: 3.38062\nFrame: /base_link published by unknown_publisher Average Delay: 3.22751 Max Delay: 3.34844\nFrame: /front_laser_link published by unknown_publisher Average Delay: 3.22661 Max Delay: 3.34159\nFrame: /imu_link published by unknown_publisher Average Delay: 3.22739 Max Delay: 3.34738\nFrame: /odom published by unknown_publisher Average Delay: 3.16493 Max Delay: 3.28667\n[...]\n\nAll Broadcasters:\nNode: unknown_publisher 418.344 Hz, Average Delay: 0.827575 Max Delay: 3.35237\nNode: unknown_publisher(static) 465.362 Hz, Average Delay: 0 Max Delay: 0\n```\n\nTo fix this:\n\n* go to \"Service\" -> \"Configuration\" -> \"System settings\" -> \"Time settings\" -> \"Set device time on robot\"\n\nAfterwards, the ROS software on the robot will restart, so you'll have to start `move_base` again (see below).\n\nIf you have an external PC on the MiR platform, you can use `chrony` to automatically synchronize system time (see below).\n\n\n### Start `move_base` on the robot\n\n* go to \"Service\" -> \"Configuration\" -> \"Launch menu\", start \"Planner\"; this starts `move_base` and `amcl` on the robot\n\n\n### Teleoperate the robot (optional)\n\n* go to \"Manual\", press yellow button (LEDs change from yellow to blue); now the robot can be teleoperated\n\n\n### Relocalize robot (optional)\n\nIf the robot's localization is lost:\n\n* go to \"Service\" -> \"Command view\" -> \"Set start position\" and click + drag to current position of robot in the map\n* click \"Adjust\"\n\n\n### Start the ROS driver\n\n```bash\nroslaunch mir_driver mir.launch\n```\n\nAdvanced\n--------\n\n### Installing chrony to synchronize system time automatically\n\nIf you have an external PC integrated into your robot that is on the same wired\nnetwork as the MiR PC, you can use `chrony` to automatically synchronize the\nMiR's system time. Unfortunately, this method is not easy to install.\n\nLet's call the external PC `external-pc`. That PC's clock is our reference\nclock. It is synced to an NTP clock whenever the `external-pc` has access to\nthe internet. To implement this synchronization solution, install `chrony` on\nboth the `external-pc` and the internal PC of the MiR, and set up the\n`external-pc` as the chrony server and the internal MiR PC as the chrony\nclient. This way, the clocks on these systems always stay in sync without any\nmanual interaction.\n\nTo install things on the internal MiR PC:\n\n* Connect a monitor, keyboard and USB stick with a live Linux system to the\n  ports that are exposed on one corner of the MiR.\n* Boot into the live USB Linux system.\n* `chroot` into the MiR PC:\n\n    1. Mount MiR partition and bind /dev, /run etc.\n       You can use fdisk -l to figure out which partition to mount.\n       (Here it's `sda3`):\n\n       ```bash\n       sudo mkdir -p /media/mir\n       sudo mount /dev/sda3 /media/mir\n\n       for dir in /dev /dev/pts /proc /sys /run; do sudo mount --bind $dir /media/mir/@$dir; done\n       ```\n\n    2. `chroot` into the MiR PC:\n\n       ```bash\n       sudo chroot /media/mir/@/\n       ```\n\n* Create user:\n\n   ```bash\n   adduser newuser\n   usermod -aG sudo newuser\n   ```\n\n* Reboot and log into MiR PC via SSH and the newly created user name.\n* Install Chrony:\n\n   ```bash\n   sudo apt update\n   sudo apt install chrony\n\n   # if not installable (to fix broken dependencies):\n   sudo apt -f install\n   sudo apt install chrony\n   ```\n\n* Set up `/etc/chrony/chrony.conf`.\n* Make sure all old ntp configs are configured in chrony. For this, add the\n  following to your chrony.conf (the old ntp.conf part is commented out):\n\n```bash\n# Clients from this subnet have unlimited access, but only if\n# cryptographically authenticated.\n#restrict 192.168.12.255 mask 255.255.255.0 nomodify notrap nopeer\nallow 192.168.12.0/24 nomodify notrap nopeer\n```\n\n* Restart chrony service.\n\n\nTroubleshooting\n---------------\n\n### Got a result when we were already in the DONE state\n\nSometimes the move_base action will print the warning \"Got a result when we\nwere already in the DONE state\". This is caused by a race condition between the\n`/move_base/result` and `/move_base/status` topics. When a status message with\nstatus `SUCCEEDED` arrives before the corresponding result message, this\nwarning will be printed. It can be safely ignored.\n\n\n### Gazebo prints errors: \"No p gain specified for pid.\"\n\nThese errors are expected and can be ignored.\n\nUnfortunately, we cannot set the PID gains (to silence the error) due to the\nfollowing behavior of Gazebo:\n\n1. When using the `PositionJointInterface`, you *must* set the PID values for the\n   joints using that interface, otherwise you will run into\n   [this bug](https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612).\n2. When using the `VelocityJointInterface`, if you omit the PID values, Gazebo\n   just perfectly follows the commanded velocities. If you specify PID values,\n   Gazebo will use a PID controller to approximate following the commanded\n   velocities, so you have to tune the PID controllers.\n\nSince we just want Gazebo to follow our commanded velocities, we cannot set the\nPID values for joints using the VelocityJointInterface, so the errors get\nprinted (but can be ignored).\n\n\npre-commit Formatting Checks\n----------------------------\n\nThis repo has a [pre-commit](https://pre-commit.com/) check that runs in CI.\nYou can use this locally and set it up to run automatically before you commit\nsomething. To install, use pip:\n\n```bash\npip3 install --user pre-commit\n```\n\nTo run over all the files in the repo manually:\n\n```bash\npre-commit run -a\n```\n\nTo run pre-commit automatically before committing in the local repo, install the git hooks:\n\n```bash\npre-commit install\n```\n\n\nGitHub Actions - Continuous Integration\n---------------------------------------\n\n| Noetic                                                                                                                                                                               |\n|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|\n| [![Build Status](https://github.com/DFKI-NI/mir_robot/actions/workflows/github-actions.yml/badge.svg)](https://github.com/DFKI-NI/mir_robot/actions/workflows/github-actions.yml/) |\n\n\nROS Buildfarm\n-------------\n\n|                                                        | Noetic source deb                                                                                                                                                                     | Noetic binary deb                                                                                                                                                                                     |\n|--------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|\n| [mir_actions](http://wiki.ros.org/mir_actions)         | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_actions__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_actions__ubuntu_focal__source/)         | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_actions__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_actions__ubuntu_focal_amd64__binary/)         |\n| [mir_description](http://wiki.ros.org/mir_description) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_description__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_description__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_description__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_description__ubuntu_focal_amd64__binary/) |\n| [mir_driver](http://wiki.ros.org/mir_driver)           | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_driver__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_driver__ubuntu_focal__source/)           | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_driver__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_driver__ubuntu_focal_amd64__binary/)           |\n| [mir_dwb_critics](http://wiki.ros.org/mir_dwb_critics) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_dwb_critics__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_dwb_critics__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_dwb_critics__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_dwb_critics__ubuntu_focal_amd64__binary/) |\n| [mir_gazebo](http://wiki.ros.org/mir_gazebo)           | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_gazebo__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_gazebo__ubuntu_focal__source/)           | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_gazebo__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_gazebo__ubuntu_focal_amd64__binary/)           |\n| [mir_msgs](http://wiki.ros.org/mir_msgs)               | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_msgs__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_msgs__ubuntu_focal__source/)               | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_msgs__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_msgs__ubuntu_focal_amd64__binary/)               |\n| [mir_navigation](http://wiki.ros.org/mir_navigation)   | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_navigation__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_navigation__ubuntu_focal__source/)   | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_navigation__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_navigation__ubuntu_focal_amd64__binary/)   |\n| [mir_robot](http://wiki.ros.org/mir_robot)             | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_robot__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_robot__ubuntu_focal__source/)             | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_robot__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_robot__ubuntu_focal_amd64__binary/)             |\n| [sdc21x0](http://wiki.ros.org/sdc21x0)                 | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__sdc21x0__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__sdc21x0__ubuntu_focal__source/)                 | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__sdc21x0__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__sdc21x0__ubuntu_focal_amd64__binary/)                 |\n\n|                                            | Noetic devel                                                                                                                                                   | Noetic doc                                                                                                                                                     |\n|--------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------|\n| [mir_robot](http://wiki.ros.org/mir_robot) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndev__mir_robot__ubuntu_focal_amd64)](http://build.ros.org/job/Ndev__mir_robot__ubuntu_focal_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndoc__mir_robot__ubuntu_focal_amd64)](http://build.ros.org/job/Ndoc__mir_robot__ubuntu_focal_amd64) |\n"
  },
  {
    "path": "mir_actions/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_actions\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Update MirMoveBase action to 2.10.3.1\n* Don't set cmake_policy CMP0048\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n* Rename mir_100 -> mir\n  This is in preparation of mir_250 support.\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Remove RelativeMove action\n  It was removed in MiR software 2.4.0.\n* Update mir_actions to MiR 2.8.3\n* Adjust to changed MirMoveBase action (MiR >= 2.4.0)\n  See `#45 <https://github.com/DFKI-NI/mir_robot/issues/45>`_.\n* Contributors: Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n\n1.0.4 (2019-05-06)\n------------------\n* Update mir_msgs and mir_actions to MiR 2.3.1\n* Contributors: Martin Günther\n\n1.0.3 (2019-03-04)\n------------------\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_actions/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_actions)\n\nfind_package(catkin REQUIRED COMPONENTS\n  actionlib\n  geometry_msgs\n  message_generation\n  mir_msgs\n  nav_msgs\n)\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n# Generate actions in the 'action' folder\nadd_action_files(\n  FILES\n    MirMoveBase.action\n)\n\n# Generate added messages and services with any dependencies listed here\ngenerate_messages(\n  DEPENDENCIES\n    geometry_msgs\n    mir_msgs\n    nav_msgs\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package(\n  CATKIN_DEPENDS\n    actionlib\n    geometry_msgs\n    message_runtime\n    mir_msgs\n    nav_msgs\n)\n"
  },
  {
    "path": "mir_actions/action/MirMoveBase.action",
    "content": "#goal definition\n#move type\nint16 BASE_MOVE = 0\nint16 GLOBAL_MOVE = 1\nint16 RELATIVE_MOVE = 2\nint16 RELATIVE_MARKER_MOVE = 3\nint16 DOCKING_MOVE = 4\nint16 DOCKING_GLOBAL_MOVE = 5\nint16 PATH_TYPE = 6\nint16 move_task\n\n#shared parameters\ngeometry_msgs/PoseStamped target_pose\nstring target_guid\n\n#global move parameters\nfloat64 goal_dist_threshold\nfloat64 goal_orientation_threshold\nnav_msgs/Path path\nfloat32 max_plan_time\nbool clear_costmaps\nbool pause_command\nbool continue_command\n\n#relative move parameters\nfloat64 yaw\nbool collision_detection\nbool collision_avoidance\nfloat64 disable_collision_check_dist\nfloat64 max_linear_speed\nfloat64 max_rotational_speed\nfloat64 pid_dist_offset\nfloat64 target_offset\nbool only_collision_detection\nfloat64 timeout\n\n#docking move parameters\nint32 pattern_type\nint32 pattern_value\nbool only_track\nbool same_goal\nstring pose_frame\ngeometry_msgs/Pose2D pose\ngeometry_msgs/Pose2D offset\nfloat64 bar_length\nfloat64 bar_distance\nfloat64 shelf_leg_asymmetry_x\nfloat64 tolerance\n\n#Path type\nmir_msgs/MirLocalPlannerPathTypes path_type\ngeometry_msgs/PoseStamped start_pose\n# float64 timeout\n\n\n---\n#result definition\n\n#shared states\nint16 UNDEFINED = 0\nint16 GOAL_REACHED = 1\nint16 FAILED = -1\n\n#global move states\nint16 MARKER_VISIBLE = 2\nint16 FAILED_NO_PATH = -2\nint16 FAILED_GOAL_IN_STATIC_OBSTACLE = -3\nint16 FAILED_GOAL_IN_FORBIDDEN_AREA = -4\nint16 FAILED_GOAL_IN_DYNAMIC_OBSTACLE = -5\nint16 FAILED_ROBOT_IN_COLLISION = -6\nint16 FAILED_ROBOT_IN_FORBIDDEN_AREA = -7\nint16 FAILED_UNKNOWN_TRAILER = -8\nint16 FAILED_TO_PASS_GLOBAL_PLAN = -9\nint16 FAILED_NO_VALID_RECOVERY_CONTROL = -10\nint16 FAILED_UNKNOWN_PLANNER_ERROR = -11\nint16 FAILED_ROBOT_OSCILLATING = -12\nint16 FAILED_SOFTWARE_ERROR = -13\n\n#relative move states\nint16 FAILED_TIMEOUT = -14\nint16 FAILED_COLLISION = -15\nint16 INVALID_GOAL = -16\n\n#docking move states\nint16 FAILED_MARKER_TRACKING_ERROR = -17\n\n#shared results\nint16 end_state\ngeometry_msgs/PoseStamped end_pose\n\n#docking results\ngeometry_msgs/Pose2D pose\n\n#feedback for UI\nstring message\n\n---\n#feedback\n#shared\nint8 NOT_READY = -1\nint8 UNKNOWN = -2\nint8 WAITING_FOR_FLEET = -3\nint8 COLLISION = -4\n\n#global move states\nint8 PLANNING = 0\nint8 CONTROLLING = 1\nint8 CLEARING = 2\n\n#relative move states\nint8 DOCKING = 3\n\n#shared feedback\nint8 state\n\n#global move feedback\ngeometry_msgs/PoseStamped base_position\n\n#relative move feedback\ngeometry_msgs/PoseStamped current_goal\ngeometry_msgs/PoseStamped dist_to_goal\n\n#docking move feedback\ngeometry_msgs/Pose2D pose\nbool marker_inversion\n\n#path_types\n    #reverse_trolly\nint8 MOVING_FORWARD = 10\nint8 MOVING_BACKWARD = 11\n"
  },
  {
    "path": "mir_actions/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_actions</name>\n  <version>1.1.8</version>\n  <description>Action definitions for the MiR robot</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>actionlib</depend>\n  <depend>geometry_msgs</depend>\n  <depend>mir_msgs</depend>\n  <depend>nav_msgs</depend>\n\n  <build_depend>message_generation</build_depend>\n  <exec_depend>message_runtime</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_description/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_description\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n* URDF: Downsize inertia box, move to lower back\n* URDF: Pull out inertia properties\n* URDF: Update masses according to data sheet\n* URDF: Add mir_250\n* Add arg mir_type to launch files and urdfs\n* Add mir_250 meshes\n* URDF: Make wheels black\n* Add mir_100_v1.urdf.xacro for backwards compatibility\n* Rename mir_100 -> mir\n* Refactor URDF to prepare for MiR250 support\n* Gazebo: Don't manually specify wheel params for diffdrive controller\n* Simplify mir_100 collision mesh further\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n* Remove xacro comment to work around xacro bug\n  Since xacro 1.14.11, xacro now also evaluates expressions in comments\n  and throws an error if the substition argument is undefined. In xacro\n  1.14.12, this error was changed to a warning.\n  This commit removes that warning.\n  Workaround for https://github.com/ros/xacro/issues/309 .\n* xacro: drop --inorder option\n  In-order processing became default in ROS Melodic.\n* Add gazebo_plugins to dependency list (`#103 <https://github.com/DFKI-NI/mir_robot/issues/103>`_)\n  This is needed for the ground truth pose via p3d plugin.\n* Contributors: Martin Günther, moooeeeep\n\n1.1.4 (2021-12-10)\n------------------\n* Replace gazebo_plugins IMU with hector_gazebo_plugins\n* Use cylinders instead of STLs for wheel collision geometries\n  Fixes `#99 <https://github.com/DFKI-NI/mir_robot/issues/99>`_.\n* mir_debug_urdf.launch: Fix GUI display\n* Contributors: Martin Günther\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Rename tf frame and topic 'odom_comb' -> 'odom'\n  This is how they are called on the real MiR since MiR software 2.0.\n* Contributors: Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n* Fix laser scan frame_id with gazebo_plugins 2.9.2\n* Contributors: Martin Günther\n\n1.1.1 (2021-02-11)\n------------------\n* Add prepend_prefix_to_laser_frame to URDF and launch files\n  Fixes `#65 <https://github.com/DFKI-NI/mir_robot/issues/65>`_.\n* Add tf_prefix to URDF and launch files\n* Fix typo in robot_namespace\n* Add missing 'xacro:' xml namespace prefixes\n  Macro calls without 'xacro:' prefix are deprecated in Melodic and will\n  be forbidden in Noetic.\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Update to non-deprecated robot_state_publisher node\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n* Switch from Gazebo GPU laser to normal laser plugin\n  The GPU laser plugin has caused multiple people problems before, because\n  it is not compatible with all GPUS: `#1 <https://github.com/DFKI-NI/mir_robot/issues/1>`_\n  `#32 <https://github.com/DFKI-NI/mir_robot/issues/32>`_\n  `#46 <https://github.com/DFKI-NI/mir_robot/issues/46>`_\n  `#52 <https://github.com/DFKI-NI/mir_robot/issues/52>`_\n  The normal laser plugin directly uses the physics engine, so it doesn't\n  depend on any specific GPU. Also, it doesn't slow down the simulation\n  noticeably (maybe 1-2%).\n* Contributors: Martin Günther\n\n1.0.4 (2019-05-06)\n------------------\n* Add legacyModeNS param to gazebo_ros_control plugin\n  This enables the new behavior of the plugin (pid_gains parameter are now\n  in the proper namespace).\n* re-added gazebo friction parameters for the wheels (`#19 <https://github.com/DFKI-NI/mir_robot/issues/19>`_)\n* Contributors: Martin Günther, niniemann\n\n1.0.3 (2019-03-04)\n------------------\n* Merge pull request `#16 <https://github.com/DFKI-NI/mir_robot/issues/16>`_ from niniemann/add-prefix-argument-to-configs\n  Add prefix argument to configs\n* removed prefix from plugin frameName in sick urdf\n  The gazebo plugins automatically use tf_prefix, even if none is set\n  (in that case it defaults to the robot namespace). That's why we can\n  remove the prefix from the plugins configuration, assuming that the\n  robot namespace will be equal to the prefix.\n* adds $(arg prefix) to a lot of configs\n  This is an important step to be able to re-parameterize move base,\n  the diffdrive controller, ekf, amcl and the costmaps for adding a\n  tf prefix to the robots links\n* workaround eval in xacro for indigo support\n* adds tf_prefix argument to imu.gazebo.urdf.xacro\n* Add TFs for ultrasound sensors\n* Contributors: Martin Günther, Nils Niemann\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n* gazebo: Remove leading slashes in TF frames\n  TF2 doesn't like it (e.g., robot_localization).\n* Contributors: Martin Günther\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_description/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_description)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package()\n\n#############\n## Install ##\n#############\n\n# Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(DIRECTORY\n  config\n  launch\n  meshes\n  rviz\n  urdf\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\nroslaunch_add_file_check(launch)\n"
  },
  {
    "path": "mir_description/config/diffdrive_controller.yaml",
    "content": "# -----------------------------------\nmobile_base_controller:\n  type        : \"diff_drive_controller/DiffDriveController\"\n  left_wheel  : '$(arg prefix)left_wheel_joint'\n  right_wheel : '$(arg prefix)right_wheel_joint'\n  publish_rate: 41.2               # this is what the real MiR platform publishes (default: 50)\n  # These covariances are exactly what the real MiR platform publishes\n  pose_covariance_diagonal : [0.00001, 0.00001, 1000000.0, 1000000.0, 1000000.0, 1000.0]\n  twist_covariance_diagonal: [0.1, 0.1, 1000000.0, 1000000.0, 1000000.0, 1000.0]\n  enable_odom_tf: false\n\n  # Wheel separation and diameter. These are both optional.\n  # diff_drive_controller will attempt to read either one or both from the\n  # URDF if not specified as a parameter.\n  # We don't set the value here because it's different for each MiR type (100, 250, ...), and\n  # the plugin figures out the correct values.\n  #wheel_separation : 0.445208\n  #wheel_radius : 0.0625\n\n  # Wheel separation and radius multipliers\n  wheel_separation_multiplier: 1.0 # default: 1.0\n  wheel_radius_multiplier    : 1.0 # default: 1.0\n\n  # Velocity commands timeout [s], default 0.5\n  cmd_vel_timeout: 0.5\n\n  # frame_ids (same as real MiR platform)\n  base_frame_id: $(arg prefix)base_footprint # default: base_link\n  odom_frame_id: $(arg prefix)odom           # default: odom\n\n  # Velocity and acceleration limits\n  # Whenever a min_* is unspecified, default to -max_*\n  linear:\n    x:\n      has_velocity_limits    : true\n      max_velocity           : 1.0  # m/s; move_base max_vel_x: 0.8\n      has_acceleration_limits: true\n      max_acceleration       : 2.0  # m/s^2; move_base acc_lim_x: 1.5\n  angular:\n    z:\n      has_velocity_limits    : true\n      max_velocity           : 1.5  # rad/s; move_base max_rot_vel: 1.0\n      has_acceleration_limits: true\n      max_acceleration       : 2.5  # rad/s^2; move_base acc_lim_th: 2.0\n"
  },
  {
    "path": "mir_description/config/joint_state_controller.yaml",
    "content": "# Publish all joint states -----------------------------------\njoint_state_controller:\n  type: joint_state_controller/JointStateController\n  publish_rate: 50\n"
  },
  {
    "path": "mir_description/launch/mir_debug_urdf.launch",
    "content": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n  <arg name=\"gui\" default=\"true\" />\n\n  <!-- load MiR URDF -->\n  <include file=\"$(find mir_description)/launch/upload_mir_urdf.launch\">\n    <arg name=\"mir_type\" value=\"$(arg mir_type)\" />\n  </include>\n\n  <node if=\"$(arg gui)\"     name=\"joint_state_publisher\" pkg=\"joint_state_publisher_gui\" type=\"joint_state_publisher_gui\" />\n  <node unless=\"$(arg gui)\" name=\"joint_state_publisher\" pkg=\"joint_state_publisher\"     type=\"joint_state_publisher\" />\n\n  <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\" />\n\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find mir_description)/rviz/mir_description.rviz\" required=\"true\" />\n</launch>\n"
  },
  {
    "path": "mir_description/launch/upload_mir_urdf.launch",
    "content": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"mir_type\"  default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n  <arg name=\"tf_prefix\" default=\"\" doc=\"TF prefix to use for all of the MiR's TF frames\"/>\n\n  <param name=\"robot_description\" command=\"$(find xacro)/xacro $(find mir_description)/urdf/mir.urdf.xacro mir_type:=$(arg mir_type) tf_prefix:=$(arg tf_prefix)\" />\n</launch>\n"
  },
  {
    "path": "mir_description/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_description</name>\n  <version>1.1.8</version>\n  <description>URDF description of the MiR robot</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roslaunch</build_depend>\n\n  <exec_depend>diff_drive_controller</exec_depend>\n  <exec_depend>gazebo_plugins</exec_depend>\n  <exec_depend>gazebo_ros_control</exec_depend>\n  <exec_depend>hector_gazebo_plugins</exec_depend>\n  <exec_depend>joint_state_controller</exec_depend>\n  <exec_depend>joint_state_publisher</exec_depend>\n  <exec_depend>joint_state_publisher_gui</exec_depend>\n  <exec_depend>position_controllers</exec_depend>\n  <exec_depend>robot_state_publisher</exec_depend>\n  <exec_depend>rviz</exec_depend>\n  <exec_depend>urdf</exec_depend>\n  <exec_depend>xacro</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_description/rviz/mir_description.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 81\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n      Splitter Ratio: 0.5\n    Tree Height: 535\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/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/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\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/RobotModel\n      Collision Enabled: false\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        back_laser_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_footprint:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        bl_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        bl_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        br_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        br_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fl_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fl_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fr_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fr_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_frame:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        surface:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: base_footprint\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 2.20704937\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0.023150593\n        Y: -0.0341755934\n        Z: -2.6775524e-09\n      Focal Shape Fixed Size: false\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 0.515398085\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 0.490397513\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 846\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006700fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000043000002a9000000e300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002a9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000043000002a9000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000022300fffffffb0000000800540069006d006501000000000000045000000000000000000000022b000002a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1200\n  X: 59\n  Y: 29\n"
  },
  {
    "path": "mir_description/urdf/include/common.gazebo.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"controller_plugin_gazebo\" params=\"robot_namespace\">\n    <gazebo>\n      <plugin name=\"gazebo_ros_control\" filename=\"libgazebo_ros_control.so\">\n        <xacro:unless value=\"${robot_namespace == ''}\">\n          <robotNamespace>${robot_namespace}</robotNamespace>\n        </xacro:unless>\n        <controlPeriod>0.001</controlPeriod>\n        <legacyModeNS>false</legacyModeNS>\n      </plugin>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/common_properties.urdf.xacro",
    "content": "<?xml version=\"1.0\" ?>\n<!--\n  Various useful properties such as constants and materials\n -->\n<robot name=\"xacro_properties\" xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <!-- #################### RViz materials #################### -->\n  <xacro:property name=\"material_white\">\n    <material name=\"white\">\n      <color rgba=\"1 1 1 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_yellow\">\n    <material name=\"yellow\">\n      <color rgba=\"${255/255} ${226/255} ${0/255} 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_almost_white\">\n    <material name=\"almost_white\">\n      <color rgba=\"0.9 0.9 0.9 1\" />\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_grey\">\n    <material name=\"grey\">\n      <color rgba=\"0.5 0.5 0.5 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_light_grey\">\n    <material name=\"light_grey\">\n      <color rgba=\"0.6 0.6 0.6 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_dark_grey\">\n    <material name=\"dark_grey\">\n      <color rgba=\"0.3 0.3 0.3 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_black\">\n    <material name=\"black\">\n      <color rgba=\"0.1 0.1 0.1 1\"/>\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_aluminum\">\n    <material name=\"aluminum\">\n      <color rgba=\"0.8 0.8 0.8 1\" />\n    </material>\n  </xacro:property>\n  <xacro:property name=\"material_silver\">\n    <material name=\"silver\">\n      <color rgba=\"0.79 0.82 0.93 1\" />\n    </material>\n  </xacro:property>\n\n  <!-- #################### inertials with origin #################### -->\n  <!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->\n  <xacro:macro name=\"sphere_inertial\" params=\"radius mass *origin\">\n    <inertial>\n      <mass value=\"${mass}\" />\n      <xacro:insert_block name=\"origin\" />\n      <inertia ixx=\"${0.4 * mass * radius * radius}\" ixy=\"0.0\" ixz=\"0.0\"\n        iyy=\"${0.4 * mass * radius * radius}\" iyz=\"0.0\"\n        izz=\"${0.4 * mass * radius * radius}\" />\n    </inertial>\n  </xacro:macro>\n\n  <xacro:macro name=\"cylinder_inertial\" params=\"radius length mass *origin\">\n    <inertial>\n      <mass value=\"${mass}\" />\n      <xacro:insert_block name=\"origin\" />\n      <inertia ixx=\"${0.0833333 * mass * (3 * radius * radius + length * length)}\" ixy=\"0.0\" ixz=\"0.0\"\n        iyy=\"${0.0833333 * mass * (3 * radius * radius + length * length)}\" iyz=\"0.0\"\n        izz=\"${0.5 * mass * radius * radius}\" />\n    </inertial>\n  </xacro:macro>\n\n  <xacro:macro name=\"box_inertial\" params=\"x y z mass *origin\">\n    <inertial>\n      <mass value=\"${mass}\" />\n      <xacro:insert_block name=\"origin\" />\n      <inertia ixx=\"${0.0833333 * mass * (y*y + z*z)}\" ixy=\"0.0\" ixz=\"0.0\"\n        iyy=\"${0.0833333 * mass * (x*x + z*z)}\" iyz=\"0.0\"\n        izz=\"${0.0833333 * mass * (x*x + y*y)}\" />\n    </inertial>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/imu.gazebo.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <!-- If tf_prefix is given, use \"frame tf_prefix/imu_frame\", else \"imu_frame\" -->\n  <xacro:arg name=\"tf_prefix\" default=\"\" />\n  <xacro:property name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n  <xacro:if value=\"${tf_prefix == ''}\">\n      <xacro:property name=\"imu_frame\" value=\"imu_frame\" />\n  </xacro:if>\n  <xacro:unless value=\"${tf_prefix == ''}\">\n      <xacro:property name=\"imu_frame\" value=\"$(arg tf_prefix)/imu_frame\" />\n  </xacro:unless>\n\n\n  <xacro:macro name=\"imu_gazebo\" params=\"link imu_topic update_rate\">\n    <gazebo>\n      <plugin name=\"imu_plugin\" filename=\"libhector_gazebo_ros_imu.so\">\n        <updateRate>${update_rate}</updateRate>\n        <bodyName>${link}</bodyName>\n        <frameId>${imu_frame}</frameId>  <!-- from real MiR -->\n        <topicName>${imu_topic}</topicName>\n        <accelDrift>0.0 0.0 0.0</accelDrift>\n        <accelGaussianNoise>${sqrt(5e-05)} ${sqrt(0.0001)} ${sqrt(0.00013)}</accelGaussianNoise>    <!-- real MiR linear_acceleration_covariance: [5e-05, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.00013] -->\n        <rateDrift>0.0 0.0 0.0</rateDrift>\n        <rateGaussianNoise>${sqrt(8e-06)} ${sqrt(8e-06)} ${sqrt(3e-07)}</rateGaussianNoise>         <!-- real MiR angular_velocity_covariance: [8e-06, 0.0, 0.0, 0.0, 8e-06, 0.0, 0.0, 0.0, 3e-07] -->\n        <yawDrift>0.0</yawDrift>\n        <yawGaussianNoise>${sqrt(0.1)}</yawGaussianNoise>                                           <!-- real MiR orientation_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1] -->\n      </plugin>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/mir.gazebo.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"diff_controller_plugin_gazebo\" params=\"prefix left_wheel_joint right_wheel_joint wheel_separation wheel_radius\">\n    <gazebo>\n      <plugin name=\"diff_drive_controller\" filename=\"libgazebo_ros_diff_drive.so\">\n        <legacyMode>false</legacyMode>\n        <alwaysOn>true</alwaysOn>\n        <updateRate>1000.0</updateRate>\n        <leftJoint>${left_wheel_joint}</leftJoint>\n        <rightJoint>${right_wheel_joint}</rightJoint>\n        <wheelSeparation>${wheel_separation}</wheelSeparation>\n        <wheelDiameter>${2*wheel_radius}</wheelDiameter>\n        <wheelTorque>10</wheelTorque>\n        <publishTf>1</publishTf>\n        <odometryFrame>map</odometryFrame>\n        <commandTopic>mobile_base_controller/cmd_vel</commandTopic>\n        <odometryTopic>mobile_base_controller/odom</odometryTopic>\n        <robotBaseFrame>base_footprint</robotBaseFrame>\n        <wheelAcceleration>2.8</wheelAcceleration>\n        <publishWheelJointState>true</publishWheelJointState>\n        <publishWheelTF>false</publishWheelTF>\n        <odometrySource>world</odometrySource>\n        <rosDebugLevel>Debug</rosDebugLevel>\n      </plugin>\n    </gazebo>\n  </xacro:macro>\n\n  <xacro:macro name=\"set_wheel_friction\" params=\"link friction\">\n    <gazebo reference=\"${link}\">\n      <mu1 value=\"${friction}\"/>\n      <mu2 value=\"${friction}\"/>\n      <kp value=\"10000000.0\"/>\n      <kd value=\"1.0\"/>\n      <minDepth>0.01</minDepth>\n    </gazebo>\n  </xacro:macro>\n\n  <xacro:macro name=\"set_all_wheel_frictions\" params=\"prefix\">\n    <xacro:set_wheel_friction link=\"${prefix}left_wheel_link\" friction=\"200\"/>\n    <xacro:set_wheel_friction link=\"${prefix}right_wheel_link\" friction=\"200\"/>\n    <xacro:set_wheel_friction link=\"${prefix}fl_caster_wheel_link\" friction=\"1\"/>\n    <xacro:set_wheel_friction link=\"${prefix}fr_caster_wheel_link\" friction=\"1\"/>\n    <xacro:set_wheel_friction link=\"${prefix}bl_caster_wheel_link\" friction=\"1\"/>\n    <xacro:set_wheel_friction link=\"${prefix}br_caster_wheel_link\" friction=\"1\"/>\n  </xacro:macro>\n\n  <xacro:macro name=\"p3d_base_controller\" params=\"prefix\">\n    <gazebo>\n      <plugin name=\"p3d_base_controller\" filename=\"libgazebo_ros_p3d.so\">\n        <alwaysOn>true</alwaysOn>\n        <updateRate>50.0</updateRate>\n        <bodyName>${prefix}base_footprint</bodyName>\n        <topicName>base_pose_ground_truth</topicName>\n        <gaussianNoise>0.01</gaussianNoise>\n        <frameName>map</frameName>\n        <xyzOffsets>0 0 0</xyzOffsets>\n        <rpyOffsets>0 0 0</rpyOffsets>\n      </plugin>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/mir.transmission.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"mir_wheel_transmission\" params=\"prefix locationprefix\">\n    <transmission name=\"${prefix}${locationprefix}_wheel_trans\">\n      <type>transmission_interface/SimpleTransmission</type>\n      <joint name=\"${prefix}${locationprefix}_wheel_joint\">\n        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>\n      </joint>\n      <actuator name=\"${prefix}${locationprefix}_wheel_motor\">\n        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>\n        <mechanicalReduction>1</mechanicalReduction>\n      </actuator>\n    </transmission>\n  </xacro:macro>\n\n  <xacro:macro name=\"mir_wheel_transmissions\" params=\"prefix\">\n    <xacro:mir_wheel_transmission prefix=\"${prefix}\" locationprefix=\"left\"/>\n    <xacro:mir_wheel_transmission prefix=\"${prefix}\" locationprefix=\"right\"/>\n  </xacro:macro>\n\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/mir_100_v1.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\"\n       name=\"mir_100\" >\n\n  <!-- This file is only for backward compatibility before the \"mir_100\" to \"mir\" rename. -->\n\n  <xacro:include filename=\"$(find mir_description)/urdf/include/mir_v1.urdf.xacro\" />\n\n  <xacro:macro name=\"mir_100\" params=\"prefix\">\n    <xacro:mir prefix=\"${prefix}\" />\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/mir_v1.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <xacro:arg name=\"mir_type\" default=\"mir_100\" />      <!-- The MiR variant. Can be \"mir_100\" or \"mir_250\" for now.-->\n  <xacro:property name=\"mir_type\" value=\"$(arg mir_type)\" />  <!-- necessary because args cannot be accessed inside ${} expressions -->\n\n  <xacro:include filename=\"$(find mir_description)/urdf/include/common_properties.urdf.xacro\" />\n  <xacro:include filename=\"$(find mir_description)/urdf/include/imu.gazebo.urdf.xacro\" />\n  <xacro:include filename=\"$(find mir_description)/urdf/include/mir.gazebo.xacro\" />\n  <xacro:include filename=\"$(find mir_description)/urdf/include/mir.transmission.xacro\" />\n  <xacro:include filename=\"$(find mir_description)/urdf/include/sick_s300.urdf.xacro\" />\n\n  <xacro:property name=\"deg_to_rad\" value=\"0.017453293\" />\n\n  <!-- The inertia for the MiR platform is intentionally chosen to be smaller than\n       the bounding box and also shifted a bit to the back, because most of the mass\n       is in the lower center back (because of the batteries). -->\n  <xacro:property name=\"mir_base_inertial_x\" value=\"-0.05\" />\n  <xacro:property name=\"mir_base_inertial_y\" value=\"0.0\" />\n  <xacro:property name=\"mir_base_inertial_z\" value=\"0.15\" />\n  <xacro:property name=\"mir_base_inertial_x_length\" value=\"0.50\" />\n  <xacro:property name=\"mir_base_inertial_y_length\" value=\"0.30\" />\n  <xacro:property name=\"mir_base_inertial_z_length\" value=\"0.20\" />\n\n  <xacro:if value=\"${mir_type == 'mir_100'}\">\n    <xacro:property name=\"mir_base_mass\" value=\"77.0\" />\n    <xacro:property name=\"mir_act_wheel_radius\" value=\"0.0625\" />\n    <xacro:property name=\"mir_act_wheel_width\" value=\"0.032\" />\n    <xacro:property name=\"mir_act_wheel_mass\" value=\"1.0\" />\n    <xacro:property name=\"mir_act_wheel_dx\" value=\"0.037646\" />\n    <xacro:property name=\"mir_act_wheel_dy\" value=\"0.222604\" />\n  </xacro:if>\n\n  <xacro:if value=\"${mir_type == 'mir_250'}\">\n    <xacro:property name=\"mir_base_mass\" value=\"97.0\" />\n    <xacro:property name=\"mir_act_wheel_radius\" value=\"0.100\" />\n    <xacro:property name=\"mir_act_wheel_width\" value=\"0.038\" />\n    <xacro:property name=\"mir_act_wheel_mass\" value=\"1.0\" />\n    <xacro:property name=\"mir_act_wheel_dx\" value=\"-0.004485\" />\n    <xacro:property name=\"mir_act_wheel_dy\" value=\"0.2015\" />\n  </xacro:if>\n\n  <xacro:property name=\"mir_caster_wheel_radius\" value=\"0.0625\" />\n  <xacro:property name=\"mir_caster_wheel_width\" value=\"0.032\" />\n  <xacro:property name=\"mir_caster_wheel_mass\" value=\"1.0\" />\n  <xacro:property name=\"mir_caster_wheel_dx\" value=\"-0.0382\" />\n  <xacro:property name=\"mir_caster_wheel_dy\" value=\"0\" />\n  <xacro:property name=\"mir_caster_wheel_dz\" value=\"-0.094\" />\n  <xacro:property name=\"mir_front_caster_wheel_base_dx\" value=\"0.3037\" />\n  <xacro:if value=\"${mir_type == 'mir_100'}\">\n    <xacro:property name=\"mir_back_caster_wheel_base_dx\"  value=\"0.3078\" />\n    <xacro:property name=\"mir_caster_wheel_base_dy\" value=\"0.203\" />\n  </xacro:if>\n\n  <xacro:if value=\"${mir_type == 'mir_250'}\">\n    <xacro:property name=\"mir_back_caster_wheel_base_dx\"  value=\"0.296\" />\n    <xacro:property name=\"mir_caster_wheel_base_dy\" value=\"0.188\" />\n  </xacro:if>\n  <xacro:property name=\"mir_caster_wheel_base_dz\" value=\"${mir_caster_wheel_radius - mir_caster_wheel_dz}\" />\n\n  <!-- from visually matching up the meshes of the MiR and the laser scanner -->\n  <xacro:if value=\"${mir_type == 'mir_100'}\">\n    <xacro:property name=\"laser_dx\" value=\"0.392\" />\n    <xacro:property name=\"laser_dy\" value=\"0.2358\" />\n  </xacro:if>\n\n  <xacro:if value=\"${mir_type == 'mir_250'}\">\n    <xacro:property name=\"laser_dx\" value=\"0.315\" />\n    <xacro:property name=\"laser_dy\" value=\"0.205\" />\n  </xacro:if>\n  <xacro:property name=\"laser_dz\" value=\"0.1914\" />\n\n  <xacro:macro name=\"actuated_wheel\" params=\"prefix locationprefix locationright\">\n    <joint name=\"${prefix}${locationprefix}_wheel_joint\" type=\"continuous\">\n      <origin xyz=\"0.0 ${-mir_act_wheel_dy * locationright} ${mir_act_wheel_radius}\" rpy=\"0 0 0\" />\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}${locationprefix}_wheel_link\" />\n      <axis xyz=\"0 1 0\" />\n      <limit effort=\"100\" velocity=\"20.0\" />\n    </joint>\n\n    <link name=\"${prefix}${locationprefix}_wheel_link\">\n      <xacro:cylinder_inertial mass=\"${mir_act_wheel_mass}\" radius=\"${mir_act_wheel_radius}\" length=\"${mir_act_wheel_width}\">\n        <origin xyz=\"0 0 0\" rpy=\"${0.5 * pi} 0 0\" />\n      </xacro:cylinder_inertial>\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${pi/2} 0 0\" />\n        <geometry>\n          <cylinder radius=\"${mir_act_wheel_radius}\" length=\"${mir_act_wheel_width}\" />\n        </geometry>\n        <xacro:insert_block name=\"material_black\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"${pi/2} 0 0\" />\n        <geometry>\n          <cylinder radius=\"${mir_act_wheel_radius}\" length=\"${mir_act_wheel_width}\" />\n        </geometry>\n      </collision>\n    </link>\n    <gazebo reference=\"${prefix}${locationprefix}_wheel_link\">\n      <material>Gazebo/FlatBlack</material>\n    </gazebo>\n  </xacro:macro>\n\n  <xacro:macro name=\"caster_wheel\" params=\"prefix locationprefix locationright wheel_base_dx\">\n    <!-- caster hub -->\n    <joint name=\"${prefix}${locationprefix}_caster_rotation_joint\" type=\"continuous\">\n      <origin xyz=\"${wheel_base_dx} ${-mir_caster_wheel_base_dy * locationright} ${mir_caster_wheel_base_dz}\" rpy=\"0 0 0\" />\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}${locationprefix}_caster_rotation_link\" />\n      <axis xyz=\"0 0 1\" />\n      <dynamics damping=\"0.01\" friction=\"0.0\"/>\n    </joint>\n\n    <link name=\"${prefix}${locationprefix}_caster_rotation_link\">\n      <inertial>\n        <!-- <origin xyz=\"0 0 -0.042500000044\" rpy=\"${0.5 * pi} ${24 * deg_to_rad} ${1.5 * pi}\" /> -->\n        <origin xyz=\"0 0 -0.042500000044\" rpy=\"${24 * deg_to_rad} 0 ${0.5 * pi} \" />\n        <mass value=\"0.3097539019\" />\n        <inertia\n          ixx=\"0.0005844517978\"\n          ixy=\"0\"\n          ixz=\"0\"\n          iyy=\"0.00052872551237\"\n          iyz=\"0\"\n          izz=\"0.00017923555074\" />\n      </inertial>\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/visual/caster_wheel_base.stl\" />\n        </geometry>\n        <xacro:if value=\"${mir_type == 'mir_100'}\">\n          <xacro:insert_block name=\"material_silver\" />\n        </xacro:if>\n        <xacro:if value=\"${mir_type == 'mir_250'}\">\n          <xacro:insert_block name=\"material_black\" />\n        </xacro:if>\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/collision/caster_wheel_base.stl\" />\n        </geometry>\n      </collision>\n    </link>\n    <gazebo reference=\"${prefix}${locationprefix}_caster_rotation_link\">\n      <xacro:if value=\"${mir_type == 'mir_100'}\">\n        <material>Gazebo/Grey</material>\n      </xacro:if>\n      <xacro:if value=\"${mir_type == 'mir_250'}\">\n        <material>Gazebo/FlatBlack</material>\n      </xacro:if>\n    </gazebo>\n\n    <!-- caster wheel -->\n    <joint name=\"${prefix}${locationprefix}_caster_wheel_joint\" type=\"continuous\">\n      <origin xyz=\"${mir_caster_wheel_dx} ${-mir_caster_wheel_dy * locationright} ${mir_caster_wheel_dz}\" rpy=\"0 0 0\" />\n      <parent link=\"${prefix}${locationprefix}_caster_rotation_link\" />\n      <child link=\"${prefix}${locationprefix}_caster_wheel_link\" />\n      <axis xyz=\"0 1 0\" />\n    </joint>\n\n    <link name=\"${prefix}${locationprefix}_caster_wheel_link\">\n      <xacro:cylinder_inertial mass=\"${mir_caster_wheel_mass}\" radius=\"${mir_caster_wheel_radius}\" length=\"${mir_caster_wheel_width}\">\n        <origin xyz=\"0 0 0\" rpy=\"${0.5 * pi} 0 0\" />\n      </xacro:cylinder_inertial>\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${pi/2} 0 0\" />\n        <geometry>\n          <cylinder radius=\"${mir_caster_wheel_radius}\" length=\"${mir_caster_wheel_width}\" />\n        </geometry>\n        <xacro:insert_block name=\"material_black\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"${pi/2} 0 0\" />\n        <geometry>\n          <cylinder radius=\"${mir_caster_wheel_radius}\" length=\"${mir_caster_wheel_width}\" />\n        </geometry>\n      </collision>\n    </link>\n    <gazebo reference=\"${prefix}${locationprefix}_caster_wheel_link\">\n      <material>Gazebo/FlatBlack</material>\n    </gazebo>\n  </xacro:macro>\n\n  <xacro:macro name=\"mir\" params=\"prefix\">\n    <link name=\"${prefix}base_footprint\" />\n\n    <joint name=\"${prefix}base_joint\" type=\"fixed\">\n      <parent link=\"${prefix}base_footprint\" />\n      <child link=\"${prefix}base_link\" />\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    </joint>\n\n    <link name=\"${prefix}base_link\">\n      <xacro:box_inertial mass=\"${mir_base_mass}\" x=\"${mir_base_inertial_x_length}\" y=\"${mir_base_inertial_y_length}\" z=\"${mir_base_inertial_z_length}\">\n        <origin xyz=\"${mir_base_inertial_x + mir_act_wheel_dx} ${mir_base_inertial_y} ${mir_base_inertial_z}\" rpy=\"0 0 0\" />\n      </xacro:box_inertial>\n      <visual>\n        <origin xyz=\"${mir_act_wheel_dx} 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/visual/${mir_type}_base.stl\" />\n        </geometry>\n        <xacro:if value=\"${mir_type == 'mir_100'}\">\n          <xacro:insert_block name=\"material_white\" />\n        </xacro:if>\n        <xacro:if value=\"${mir_type == 'mir_250'}\">\n          <xacro:insert_block name=\"material_dark_grey\" />\n        </xacro:if>\n      </visual>\n      <collision>\n        <origin xyz=\"${mir_act_wheel_dx} 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/collision/${mir_type}_base.stl\" />\n        </geometry>\n      </collision>\n    </link>\n    <gazebo reference=\"${prefix}base_link\">\n      <xacro:if value=\"${mir_type == 'mir_100'}\">\n        <material>Gazebo/White</material>\n      </xacro:if>\n      <xacro:if value=\"${mir_type == 'mir_250'}\">\n        <material>Gazebo/DarkGrey</material>\n      </xacro:if>\n    </gazebo>\n\n    <!-- IMU -->\n    <joint name=\"${prefix}base_link_to_imu_joint\" type=\"fixed\">\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}imu_link\" />\n      <origin xyz=\"0.0 0.0 0.25\" rpy=\"0 0 0\" />  <!-- same as real MiR -->\n    </joint>\n\n    <link name=\"${prefix}imu_link\" />\n\n    <xacro:imu_gazebo link=\"${prefix}imu_link\" imu_topic=\"imu_data\" update_rate=\"50.0\" />\n\n    <!-- Create an alias for imu_link. This is necessary because the real MiR's\n         TF has imu_link, but the imu_data topic is published in the imu_frame\n         frame. -->\n    <joint name=\"${prefix}imu_link_to_imu_frame_joint\" type=\"fixed\">\n      <parent link=\"${prefix}imu_link\" />\n      <child link=\"${prefix}imu_frame\" />\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    </joint>\n\n    <link name=\"${prefix}imu_frame\" />\n\n    <!-- Laser scanners -->\n    <joint name=\"${prefix}base_link_to_front_laser_joint\" type=\"fixed\">\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}front_laser_link\" />\n      <origin xyz=\"${laser_dx + mir_act_wheel_dx} ${laser_dy} ${laser_dz}\" rpy=\"0.0 0.0 ${0.25 * pi}\" />\n    </joint>\n    <xacro:sick_s300 prefix=\"${prefix}\" link=\"front_laser_link\" topic=\"f_scan\" />\n\n    <joint name=\"${prefix}base_link_to_back_laser_joint\" type=\"fixed\">\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}back_laser_link\" />\n      <origin xyz=\"${-laser_dx + mir_act_wheel_dx} ${-laser_dy} ${laser_dz}\" rpy=\"0.0 0.0 ${-0.75 * pi}\" />\n    </joint>\n\n    <xacro:sick_s300 prefix=\"${prefix}\" link=\"back_laser_link\" topic=\"b_scan\" />\n\n    <!-- Ultrasound sensors -->\n    <joint name=\"${prefix}us_1_joint\" type=\"fixed\">   <!-- right ultrasound -->\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}us_1_frame\" />\n      <origin xyz=\"0.45 -0.12 0.16 \" rpy=\"0 0 0\" />  <!-- from visually matching to the mesh of the MiR -->\n    </joint>\n\n    <link name=\"${prefix}us_1_frame\" />\n\n    <joint name=\"${prefix}us_2_joint\" type=\"fixed\">   <!-- left ultrasound -->\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}us_2_frame\" />\n      <origin xyz=\"0.45 0.12 0.16 \" rpy=\"0 0 0\" />  <!-- from visually matching to the mesh of the MiR -->\n    </joint>\n\n    <link name=\"${prefix}us_2_frame\" />\n\n    <!-- wheels -->\n    <xacro:actuated_wheel prefix=\"${prefix}\" locationprefix=\"left\" locationright=\"-1\"/>\n    <xacro:actuated_wheel prefix=\"${prefix}\" locationprefix=\"right\" locationright=\"1\"/>\n    <xacro:caster_wheel prefix=\"${prefix}\" locationprefix=\"fl\" locationright=\"-1\" wheel_base_dx=\"${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}\"/>\n    <xacro:caster_wheel prefix=\"${prefix}\" locationprefix=\"fr\" locationright=\"1\" wheel_base_dx=\"${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}\"/>\n    <xacro:caster_wheel prefix=\"${prefix}\" locationprefix=\"bl\" locationright=\"-1\" wheel_base_dx=\"${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}\"/>\n    <xacro:caster_wheel prefix=\"${prefix}\" locationprefix=\"br\" locationright=\"1\" wheel_base_dx=\"${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}\"/>\n\n    <joint name=\"${prefix}base_link_surface_joint\" type=\"fixed\">\n      <origin xyz=\"${mir_act_wheel_dx} 0 0.352\" rpy=\"0 0 0\" />\n      <parent link=\"${prefix}base_link\" />\n      <child link=\"${prefix}surface\" />\n      <axis xyz=\"0 0 1\" />\n    </joint>\n\n    <link name=\"${prefix}surface\"/>\n\n    <xacro:mir_wheel_transmissions prefix=\"${prefix}\"/>\n\n    <!-- set the gazebo friction parameters for the wheels -->\n    <xacro:set_all_wheel_frictions prefix=\"${prefix}\"/>\n\n    <xacro:p3d_base_controller prefix=\"${prefix}\" />\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/include/sick_s300.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:include filename=\"$(find mir_description)/urdf/include/common_properties.urdf.xacro\" />\n\n  <xacro:property name=\"laser_x\" value=\"0.156\" />\n  <xacro:property name=\"laser_y\" value=\"0.155\" />\n  <xacro:property name=\"laser_z\" value=\"0.185\" />\n  <xacro:property name=\"laser_mass\" value=\"1.2\" />\n\n  <xacro:macro name=\"sick_s300\" params=\"link topic prefix\">\n    <link name=\"${prefix}${link}\">\n      <visual>\n        <origin xyz=\"0.0 0.0 0.0\" rpy=\"${pi} 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/visual/sick_lms-100.stl\" />\n        </geometry>\n        <!-- <xacro:insert_block name=\"material_yellow\" /> -->\n        <xacro:insert_block name=\"material_black\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0.0 0.0 0.0\" rpy=\"${pi} 0 0\" />\n        <geometry>\n          <mesh filename=\"package://mir_description/meshes/visual/sick_lms-100.stl\" />\n        </geometry>\n      </collision>\n      <xacro:box_inertial x=\"${laser_x}\" y=\"${laser_y}\" z=\"${laser_z}\" mass=\"${laser_mass}\">\n        <origin xyz=\"0 0 0\" />\n      </xacro:box_inertial>\n    </link>\n\n    <gazebo reference=\"${prefix}${link}\">\n      <!-- <material value=\"Gazebo/Yellow\" /> -->\n      <material value=\"Gazebo/FlatBlack\" />\n\n      <sensor type=\"ray\" name=\"${prefix}${link}\">\n        <pose>0 0 0 0 0 0</pose>\n        <visualize>false</visualize>\n        <update_rate>12.5</update_rate>\n        <ray>\n          <scan>\n            <horizontal>\n              <samples>541</samples>\n              <resolution>1</resolution>  <!-- has to be 1; actual resolution will be computed from number of samples + min_angle/max_angle -->\n              <min_angle>-2.35619449615</min_angle>\n              <max_angle>2.35619449615</max_angle>\n            </horizontal>\n          </scan>\n          <range>\n            <min>0.05</min>\n            <max>29.0</max>\n            <resolution>0.01</resolution>\n          </range>\n          <noise>\n            <type>gaussian</type>\n            <!-- Noise parameters based on published spec for S300 achieving\n                 \"+-29mm\" accuracy at range < 3m (~0.01 of the range) at\n                 1 sigma. -->\n            <mean>0.0</mean>\n            <stddev>0.01</stddev>\n          </noise>\n        </ray>\n        <plugin name=\"gazebo_ros_${link}_controller\" filename=\"libgazebo_ros_laser.so\">\n          <frameName>${prefix}${link}</frameName>\n          <topicName>${topic}</topicName>\n        </plugin>\n      </sensor>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "mir_description/urdf/mir.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\"\n       name=\"mir\" >\n\n  <!-- MiR base -->\n  <xacro:include filename=\"$(find mir_description)/urdf/include/mir_v1.urdf.xacro\" />\n  <xacro:include filename=\"$(find mir_description)/urdf/include/common.gazebo.xacro\" />\n\n  <xacro:arg name=\"tf_prefix\" default=\"\" />\n  <xacro:property name=\"tf_prefix_\" value=\"$(arg tf_prefix)\" />\n  <xacro:if value=\"${tf_prefix_ == ''}\">\n    <xacro:property name=\"prefix\" value=\"\" />\n  </xacro:if>\n  <xacro:unless value=\"${tf_prefix_ == ''}\">\n    <xacro:property name=\"prefix\" value=\"${tf_prefix_}/\" />\n  </xacro:unless>\n\n  <xacro:mir prefix=\"${prefix}\" />\n  <xacro:controller_plugin_gazebo robot_namespace=\"\"/>\n\n  <!-- instead of the controller_plugin_gazebo, you can use the diffdrive controller like this:\n    <xacro:diff_controller_plugin_gazebo prefix=\"\"\n      left_wheel_joint=\"left_wheel_joint\"\n      right_wheel_joint=\"right_wheel_joint\"\n      wheel_separation=\"${2*mir_act_wheel_dy}\"\n      wheel_radius=\"${mir_act_wheel_radius}\"/>\n  -->\n</robot>\n"
  },
  {
    "path": "mir_driver/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Fix typo in license\n* pre-commit: Update hook versions\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Fix pydocstyle errors\n* Add license headers\n* Fix flake8 warnings\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n* Add arg mir_type to launch files and urdfs\n* Rename mir_100 -> mir\n  This is in preparation of mir_250 support.\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Subscribe to move_base_simple/goal in relative namespace\n* Use absolute topics for /tf, /tf_static, /map etc.\n* Rename tf frame and topic 'odom_comb' -> 'odom'\n  This is how they are called on the real MiR since MiR software 2.0.\n* Fix handling of tf_static topic\n  This does two things:\n  1. Make the tf_static topic latched.\n  2. Cache all transforms, publish as one message.\n* Increase queue_size for publishers + subscribers to 10\n  One case where this was a problem was the tf_static topic: Since\n  multiple messages are being published at once, the subscriber often\n  missed one. The tf_static topic will be fixed anyway in the next commit,\n  but let's increase the queue_size anyway to avoid such bugs in the\n  future.\n* Update topic list to 2.8.3.1\n* Reformat python code using black\n* Remove outdated topics\n  These topics don't exist on MiR software 2.8.3 any more (most of them\n  have been removed a long time ago).\n  Fixes `#37 <https://github.com/DFKI-NI/mir_robot/issues/37>`_.\n* Remove MirStatus\n  This message was removed in MiR software 2.0 (Renamed to RobotStatus).\n* Use same MirMoveBase params as real MiR (2.8.3)\n  This shouldn't make a difference (it used to work before). Just removing\n  one more potential source of error.\n* Fix: Converts move_base_simple/goal into a move_base action. (`#62 <https://github.com/DFKI-NI/mir_robot/issues/62>`_)\n  At least MIR software version 2.8 does not react properly to move_base_simple/goal messages. This implements a workaround.\n  Closes `#60 <https://github.com/DFKI-NI/mir_robot/issues/60>`_.\n* Fix: Adds subscription to \"tf_static\". (`#58 <https://github.com/DFKI-NI/mir_robot/issues/58>`_)\n  Some transformations are published on this topic and are needed to\n  obtain a full tf tree. E.g. \"base_footprint\" to \"base_link\"\n* Minor: Removes /particlecloud from the list of published topics. (`#57 <https://github.com/DFKI-NI/mir_robot/issues/57>`_)\n* Fix: Add missing dict_filter keyword argument for cmd_vel msgs (`#56 <https://github.com/DFKI-NI/mir_robot/issues/56>`_)\n* Remove relative_move_action (MiR => 2.4.0)\n  This action was merged into the generic MirMoveBaseAction in MiR\n  software 2.4.0.\n* Adjust to changed MirMoveBase action (MiR >= 2.4.0)\n  See `#45 <https://github.com/DFKI-NI/mir_robot/issues/45>`_.\n* Adjust cmd_vel topic to TwistStamped (MiR >= 2.7)\n  See `#45 <https://github.com/DFKI-NI/mir_robot/issues/45>`_.\n* Contributors: Martin Günther, matthias-mayr\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Fix subscribing twice to same topic (TF etc)\n  There was a flaw in the subscriber logic that caused the mir_bridge to\n  subscribe multiple times to the same topic from the MiR, especially for\n  latched topics. This can be seen by repeated lines in the output:\n  starting to stream messages on topic 'tf'\n  starting to stream messages on topic 'tf'\n  starting to stream messages on topic 'tf'\n  Probably related to `#64 <https://github.com/DFKI-NI/mir_robot/issues/64>`_.\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Adapt to changes in websocket-client >= 0.49\n  Ubuntu 16.04 has python-websocket  0.18\n  Ubuntu 20.04 has python3-websocket 0.53\n* Update scripts to Python3 (Noetic)\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n* Add optional prefix parameter to fake_mir_joint_publisher (`#47 <https://github.com/DFKI-NI/mir_robot/issues/47>`_)\n* tf_remove_child_frames: Don't publish empty TFs\n* Add sdc21x0 package, MC/currents topic\n* Contributors: Martin Günther, Nils Niemann\n\n1.0.4 (2019-05-06)\n------------------\n* Remove garbage file\n* Contributors: Martin Günther\n\n1.0.3 (2019-03-04)\n------------------\n* Make disable_map work with MiR software 2.0\n  See `#5 <https://github.com/DFKI-NI/mir_robot/issues/5>`_.\n* mir_driver: Optionally disable the map topic + TF frame (`#6 <https://github.com/DFKI-NI/mir_robot/issues/6>`_)\n  This is useful when running one's own SLAM / localization nodes.\n  Fixes `#5 <https://github.com/DFKI-NI/mir_robot/issues/5>`_.\n* Split scan_rep117 topic into two separate topics\n  This fixes the problem that the back laser scanner was ignored in the\n  navigation costmap in Gazebo (probably because in Gazebo, both laser\n  scanners have the exact same timestamp).\n* Contributors: Martin Günther\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n* mir_driver: Remove leading slashes in TF frames\n* mir_driver: Install launch directory\n* Contributors: Martin Günther\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_driver/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_driver)\n\nfind_package(catkin REQUIRED COMPONENTS\n  actionlib\n  actionlib_msgs\n  diagnostic_msgs\n  dynamic_reconfigure\n  geometry_msgs\n  mir_actions\n  mir_msgs\n  move_base_msgs\n  nav_msgs\n  rosgraph_msgs\n  roslaunch\n  rospy\n  rospy_message_converter\n  sdc21x0\n  sensor_msgs\n  std_msgs\n  tf\n  tf2_msgs\n  visualization_msgs\n)\n\ncatkin_python_setup()\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package(\n  CATKIN_DEPENDS\n    actionlib\n    actionlib_msgs\n    diagnostic_msgs\n    dynamic_reconfigure\n    geometry_msgs\n    mir_actions\n    mir_msgs\n    move_base_msgs\n    nav_msgs\n    rosgraph_msgs\n    rospy_message_converter\n    sdc21x0\n    sensor_msgs\n    std_msgs\n    tf\n    tf2_msgs\n    visualization_msgs\n)\n\n#############\n## Install ##\n#############\n\ncatkin_install_python(PROGRAMS\n  nodes/fake_mir_joint_publisher.py\n  nodes/mir_bridge.py\n  nodes/rep117_filter.py\n  nodes/tf_remove_child_frames.py\n  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n\n# Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(DIRECTORY\n  launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\nroslaunch_add_file_check(launch)\n"
  },
  {
    "path": "mir_driver/launch/mir.launch",
    "content": "<launch>\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n\n  <arg name=\"tf_prefix\" default=\"\" doc=\"TF prefix to use for all of MiR's TF frames\"/>\n\n  <arg name=\"mir_hostname\" default=\"192.168.12.20\" />\n\n  <arg name=\"disable_map\" default=\"false\" doc=\"Disable the map topic and map -> odom TF transform from the MiR\" />\n\n  <param name=\"tf_prefix\" type=\"string\" value=\"$(arg tf_prefix)\"/>\n\n  <!-- URDF -->\n  <include file=\"$(find mir_description)/launch/upload_mir_urdf.launch\">\n    <arg name=\"mir_type\" value=\"$(arg mir_type)\" />\n  </include>\n\n  <!-- Robot state publisher -->\n  <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\">\n    <remap from=\"/tf\"        to=\"tf_rss\" />\n    <remap from=\"/tf_static\" to=\"tf_static_rss\" />\n  </node>\n\n  <!-- remove those TFs that are also published by the MiR to avoid conflicts -->\n  <node name=\"tf_remove_state_publisher_frames\" pkg=\"mir_driver\" type=\"tf_remove_child_frames.py\" output=\"screen\">\n    <remap from=\"tf_in\"         to=\"tf_rss\" />\n    <remap from=\"tf_out\"        to=\"/tf\" />\n    <remap from=\"tf_static_in\"  to=\"tf_static_rss\" />\n    <remap from=\"tf_static_out\" to=\"/tf_static\" />\n    <rosparam param=\"remove_frames\">\n      - base_link\n      - front_laser_link\n      - back_laser_link\n      - camera_top_link\n      - camera_top_depth_optical_frame\n      - camera_floor_link\n      - camera_floor_depth_optical_frame\n      - imu_link\n    </rosparam>\n  </node>\n\n  <!-- MiR base -->\n  <group if=\"$(arg disable_map)\">\n    <node name=\"mir_bridge\" pkg=\"mir_driver\" type=\"mir_bridge.py\" output=\"screen\">\n      <param name=\"hostname\" value=\"$(arg mir_hostname)\" />\n      <param name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n      <remap from=\"map\" to=\"map_mir\" />\n      <remap from=\"map_metadata\" to=\"map_metadata_mir\" />\n      <remap from=\"rosout\" to=\"/rosout\" />\n      <remap from=\"rosout_agg\" to=\"/rosout_agg\" />\n      <remap from=\"tf\" to=\"tf_mir\" />\n    </node>\n\n    <!-- remove the map -> odom TF transform -->\n    <node name=\"tf_remove_mir_map_frame\" pkg=\"mir_driver\" type=\"tf_remove_child_frames.py\" output=\"screen\">\n      <remap from=\"tf_in\"         to=\"tf_mir\" />\n      <remap from=\"tf_out\"        to=\"/tf\" />\n      <rosparam param=\"remove_frames\">\n        - odom\n      </rosparam>\n    </node>\n  </group>\n  <group unless=\"$(arg disable_map)\">\n    <node name=\"mir_bridge\" pkg=\"mir_driver\" type=\"mir_bridge.py\" output=\"screen\">\n      <param name=\"hostname\" value=\"$(arg mir_hostname)\" />\n      <param name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n      <remap from=\"map\" to=\"/map\" />\n      <remap from=\"map_metadata\" to=\"/map_metadata\" />\n      <remap from=\"rosout\" to=\"/rosout\" />\n      <remap from=\"rosout_agg\" to=\"/rosout_agg\" />\n      <remap from=\"tf\" to=\"/tf\" />\n    </node>\n  </group>\n\n  <node name=\"b_rep117_laser_filter\" pkg=\"mir_driver\" type=\"rep117_filter.py\" output=\"screen\">\n    <remap from=\"scan\" to=\"b_scan\" />\n    <remap from=\"scan_filtered\" to=\"b_scan_rep117\" />\n  </node>\n\n  <node name=\"f_rep117_laser_filter\" pkg=\"mir_driver\" type=\"rep117_filter.py\" output=\"screen\">\n    <remap from=\"scan\" to=\"f_scan\" />\n    <remap from=\"scan_filtered\" to=\"f_scan_rep117\" />\n  </node>\n\n  <node name=\"fake_mir_joint_publisher\" pkg=\"mir_driver\" type=\"fake_mir_joint_publisher.py\" output=\"screen\" />\n</launch>\n"
  },
  {
    "path": "mir_driver/nodes/fake_mir_joint_publisher.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\nfrom sensor_msgs.msg import JointState\n\n\ndef fake_mir_joint_publisher():\n    rospy.init_node('fake_mir_joint_publisher')\n    prefix = rospy.get_param('~prefix', '')\n    pub = rospy.Publisher('joint_states', JointState, queue_size=10)\n    r = rospy.Rate(50.0)\n    while not rospy.is_shutdown():\n        js = JointState()\n        js.header.stamp = rospy.Time.now()\n        js.name = [\n            prefix + 'left_wheel_joint',\n            prefix + 'right_wheel_joint',\n            prefix + 'fl_caster_rotation_joint',\n            prefix + 'fl_caster_wheel_joint',\n            prefix + 'fr_caster_rotation_joint',\n            prefix + 'fr_caster_wheel_joint',\n            prefix + 'bl_caster_rotation_joint',\n            prefix + 'bl_caster_wheel_joint',\n            prefix + 'br_caster_rotation_joint',\n            prefix + 'br_caster_wheel_joint',\n        ]\n        js.position = [0.0 for _ in js.name]\n        js.velocity = [0.0 for _ in js.name]\n        js.effort = [0.0 for _ in js.name]\n        pub.publish(js)\n        r.sleep()\n\n\nif __name__ == '__main__':\n    try:\n        fake_mir_joint_publisher()\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "mir_driver/nodes/mir_bridge.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\n\nimport copy\nimport sys\nfrom collections.abc import Iterable\n\nfrom mir_driver import rosbridge\nfrom rospy_message_converter import message_converter\n\nfrom actionlib import SimpleActionClient\nimport actionlib_msgs.msg\nimport diagnostic_msgs.msg\nimport dynamic_reconfigure.msg\nimport geometry_msgs.msg\nimport mir_actions.msg\nimport mir_msgs.msg\nimport move_base_msgs.msg\nimport nav_msgs.msg\nimport rosgraph_msgs.msg\nimport sdc21x0.msg\nimport sensor_msgs.msg\nimport std_msgs.msg\nimport tf2_msgs.msg\nimport visualization_msgs.msg\n\nfrom collections import OrderedDict\n\ntf_prefix = ''\nstatic_transforms = OrderedDict()\n\n\nclass TopicConfig(object):\n    def __init__(self, topic, topic_type, latch=False, dict_filter=None):\n        self.topic = topic\n        self.topic_type = topic_type\n        self.latch = latch\n        self.dict_filter = dict_filter\n\n\n# remap mir_actions/MirMoveBaseAction => move_base_msgs/MoveBaseAction\ndef _move_base_goal_dict_filter(msg_dict):\n    filtered_msg_dict = copy.deepcopy(msg_dict)\n    filtered_msg_dict['goal']['move_task'] = mir_actions.msg.MirMoveBaseGoal.GLOBAL_MOVE\n    filtered_msg_dict['goal']['goal_dist_threshold'] = 0.25\n    filtered_msg_dict['goal']['clear_costmaps'] = True\n    return filtered_msg_dict\n\n\ndef _move_base_feedback_dict_filter(msg_dict):\n    # filter out slots from the dict that are not in our message definition\n    # e.g., MiRMoveBaseFeedback has the field \"state\", which MoveBaseFeedback doesn't\n    filtered_msg_dict = copy.deepcopy(msg_dict)\n    filtered_msg_dict['feedback'] = {\n        key: msg_dict['feedback'][key] for key in move_base_msgs.msg.MoveBaseFeedback.__slots__\n    }\n    return filtered_msg_dict\n\n\ndef _move_base_result_dict_filter(msg_dict):\n    filtered_msg_dict = copy.deepcopy(msg_dict)\n    filtered_msg_dict['result'] = {key: msg_dict['result'][key] for key in move_base_msgs.msg.MoveBaseResult.__slots__}\n    return filtered_msg_dict\n\n\ndef _cmd_vel_dict_filter(msg_dict):\n    \"\"\"\n    Convert Twist to TwistStamped.\n\n    Convert a geometry_msgs/Twist message dict (as sent from the ROS side) to\n    a geometry_msgs/TwistStamped message dict (as expected by the MiR on\n    software version >=2.7).\n    \"\"\"\n    header = std_msgs.msg.Header(frame_id='', stamp=rospy.Time.now())\n    filtered_msg_dict = {\n        'header': message_converter.convert_ros_message_to_dictionary(header),\n        'twist': copy.deepcopy(msg_dict),\n    }\n    return filtered_msg_dict\n\n\ndef _tf_dict_filter(msg_dict):\n    filtered_msg_dict = copy.deepcopy(msg_dict)\n    for transform in filtered_msg_dict['transforms']:\n        transform['child_frame_id'] = tf_prefix + '/' + transform['child_frame_id'].strip('/')\n    return filtered_msg_dict\n\n\ndef _tf_static_dict_filter(msg_dict):\n    \"\"\"\n    Cache tf_static messages (simulate latching).\n\n    The tf_static topic needs special handling. Publishers on tf_static are *latched*, which means that the ROS master\n    caches the last message that was sent by each publisher on that topic, and will forward it to new subscribers.\n    However, since the mir_driver node appears to the ROS master as a single node with a single publisher on tf_static,\n    and there are multiple actual publishers hiding behind it on the MiR side, only one of those messages will be\n    cached. Therefore, we need to implement the caching ourselves and make sure that we always publish the full set of\n    transforms as a single message.\n    \"\"\"\n    global static_transforms\n\n    # prepend tf_prefix\n    filtered_msg_dict = _tf_dict_filter(msg_dict)\n\n    # The following code was copied + modified from https://github.com/tradr-project/static_transform_mux .\n\n    # Process the incoming transforms, merge them with our cache.\n    for transform in filtered_msg_dict['transforms']:\n        key = transform['child_frame_id']\n        rospy.loginfo(\n            \"[%s] tf_static: updated transform %s->%s.\",\n            rospy.get_name(),\n            transform['header']['frame_id'],\n            transform['child_frame_id'],\n        )\n        static_transforms[key] = transform\n\n    # Return the cached messages.\n    filtered_msg_dict['transforms'] = static_transforms.values()\n    rospy.loginfo(\n        \"[%s] tf_static: sent %i transforms: %s\",\n        rospy.get_name(),\n        len(static_transforms),\n        str(static_transforms.keys()),\n    )\n    return filtered_msg_dict\n\n\ndef _prepend_tf_prefix_dict_filter(msg_dict):\n    # filtered_msg_dict = copy.deepcopy(msg_dict)\n    if not isinstance(msg_dict, dict):  # can happen during recursion\n        return\n    for key, value in msg_dict.items():\n        if key == 'header':\n            try:\n                # prepend frame_id\n                frame_id = value['frame_id'].strip('/')\n                if frame_id != 'map':\n                    # prepend tf_prefix, then remove leading '/' (e.g., when tf_prefix is empty)\n                    value['frame_id'] = (tf_prefix + '/' + frame_id).strip('/')\n                else:\n                    value['frame_id'] = frame_id\n\n            except TypeError:\n                pass  # value is not a dict\n            except KeyError:\n                pass  # value doesn't have key 'frame_id'\n        elif isinstance(value, dict):\n            _prepend_tf_prefix_dict_filter(value)\n        elif isinstance(value, Iterable):  # an Iterable other than dict (e.g., a list)\n            for item in value:\n                _prepend_tf_prefix_dict_filter(item)\n    return msg_dict\n\n\ndef _remove_tf_prefix_dict_filter(msg_dict):\n    # filtered_msg_dict = copy.deepcopy(msg_dict)\n    if not isinstance(msg_dict, dict):  # can happen during recursion\n        return\n    for key, value in msg_dict.items():\n        if key == 'header':\n            try:\n                # remove frame_id\n                s = value['frame_id'].strip('/')\n                if s.find(tf_prefix) == 0:\n                    value['frame_id'] = (s[len(tf_prefix) :]).strip('/')  # strip off tf_prefix, then strip leading '/'\n            except TypeError:\n                pass  # value is not a dict\n            except KeyError:\n                pass  # value doesn't have key 'frame_id'\n        elif isinstance(value, dict):\n            _remove_tf_prefix_dict_filter(value)\n        elif isinstance(value, Iterable):  # an Iterable other than dict (e.g., a list)\n            for item in value:\n                _remove_tf_prefix_dict_filter(item)\n    return msg_dict\n\n\n# topics we want to publish to ROS (and subscribe to from the MiR)\nPUB_TOPICS = [\n    # TopicConfig('LightCtrl/bms_data', mir_msgs.msg.BMSData),\n    # TopicConfig('LightCtrl/charging_state', mir_msgs.msg.ChargingState),\n    TopicConfig('LightCtrl/us_list', sensor_msgs.msg.Range),\n    # TopicConfig('MC/battery_currents', mir_msgs.msg.BatteryCurrents),\n    # TopicConfig('MC/battery_voltage', std_msgs.msg.Float64),\n    TopicConfig('MC/currents', sdc21x0.msg.MotorCurrents),\n    # TopicConfig('MC/encoders', sdc21x0.msg.StampedEncoders),\n    TopicConfig('MissionController/CheckArea/visualization_marker', visualization_msgs.msg.Marker),\n    # TopicConfig('MissionController/goal_position_guid', std_msgs.msg.String),\n    # TopicConfig('MissionController/prompt_user', mir_msgs.msg.UserPrompt),\n    TopicConfig('SickPLC/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('SickPLC/parameter_updates', dynamic_reconfigure.msg.Config),\n    # TopicConfig('active_mapping_guid', std_msgs.msg.String),\n    TopicConfig('amcl_pose', geometry_msgs.msg.PoseWithCovarianceStamped),\n    TopicConfig('b_raw_scan', sensor_msgs.msg.LaserScan),\n    TopicConfig('b_scan', sensor_msgs.msg.LaserScan),\n    TopicConfig('camera_floor/background', sensor_msgs.msg.PointCloud2),\n    TopicConfig('camera_floor/depth/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('camera_floor/depth/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('camera_floor/depth/points', sensor_msgs.msg.PointCloud2),\n    TopicConfig('camera_floor/filter/visualization_marker', visualization_msgs.msg.Marker),\n    TopicConfig('camera_floor/floor', sensor_msgs.msg.PointCloud2),\n    TopicConfig('camera_floor/obstacles', sensor_msgs.msg.PointCloud2),\n    TopicConfig('check_area/polygon', geometry_msgs.msg.PolygonStamped),\n    # TopicConfig('check_pose_area/polygon', geometry_msgs.msg.PolygonStamped),\n    # TopicConfig('data_events/area_events', mir_data_msgs.msg.AreaEventEvent),\n    # TopicConfig('data_events/maps', mir_data_msgs.msg.MapEvent),\n    # TopicConfig('data_events/positions', mir_data_msgs.msg.PositionEvent),\n    # TopicConfig('data_events/registers', mir_data_msgs.msg.PLCRegisterEvent),\n    # TopicConfig('data_events/sounds', mir_data_msgs.msg.SoundEvent),\n    TopicConfig('diagnostics', diagnostic_msgs.msg.DiagnosticArray),\n    TopicConfig('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray),\n    TopicConfig('diagnostics_toplevel_state', diagnostic_msgs.msg.DiagnosticStatus),\n    TopicConfig('f_raw_scan', sensor_msgs.msg.LaserScan),\n    TopicConfig('f_scan', sensor_msgs.msg.LaserScan),\n    TopicConfig('imu_data', sensor_msgs.msg.Imu),\n    TopicConfig('laser_back/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('laser_back/driver/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('laser_front/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('laser_front/driver/parameter_updates', dynamic_reconfigure.msg.Config),\n    # TopicConfig('localization_score', std_msgs.msg.Float64),\n    TopicConfig('/map', nav_msgs.msg.OccupancyGrid, latch=True),\n    TopicConfig('/map_metadata', nav_msgs.msg.MapMetaData),\n    # TopicConfig('marker_tracking_node/feedback', mir_marker_tracking.msg.MarkerTrackingActionFeedback),\n    # TopicConfig(\n    #     'marker_tracking_node/laser_line_extract/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription\n    # ),\n    # TopicConfig('marker_tracking_node/laser_line_extract/parameter_updates', dynamic_reconfigure.msg.Config),\n    # TopicConfig('marker_tracking_node/laser_line_extract/visualization_marker', visualization_msgs.msg.Marker),\n    # TopicConfig('marker_tracking_node/result', mir_marker_tracking.msg.MarkerTrackingActionResult),\n    # TopicConfig('marker_tracking_node/status', actionlib_msgs.msg.GoalStatusArray),\n    # TopicConfig('mirEventTrigger/events', mir_msgs.msg.Events),\n    TopicConfig('mir_amcl/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('mir_amcl/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('mir_amcl/selected_points', sensor_msgs.msg.PointCloud2),\n    TopicConfig('mir_log', rosgraph_msgs.msg.Log),\n    # TopicConfig('mir_sound/sound_event', mir_msgs.msg.SoundEvent),\n    TopicConfig('mir_status_msg', std_msgs.msg.String),\n    # TopicConfig('mirspawn/node_events', mirSpawn.msg.LaunchItem),\n    TopicConfig('mirwebapp/grid_map_metadata', mir_msgs.msg.LocalMapStat),\n    TopicConfig('mirwebapp/laser_map_metadata', mir_msgs.msg.LocalMapStat),\n    # TopicConfig('mirwebapp/web_path', mir_msgs.msg.WebPath),\n    # really mir_actions/MirMoveBaseActionFeedback:\n    TopicConfig(\n        'move_base/feedback', move_base_msgs.msg.MoveBaseActionFeedback, dict_filter=_move_base_feedback_dict_filter\n    ),\n    # really mir_actions/MirMoveBaseActionResult:\n    TopicConfig('move_base/result', move_base_msgs.msg.MoveBaseActionResult, dict_filter=_move_base_result_dict_filter),\n    TopicConfig('move_base/status', actionlib_msgs.msg.GoalStatusArray),\n    # TopicConfig('move_base_node/MIRPlannerROS/cost_cloud', sensor_msgs.msg.PointCloud2),\n    # TopicConfig('move_base_node/MIRPlannerROS/global_plan', nav_msgs.msg.Path),\n    # TopicConfig('move_base_node/MIRPlannerROS/len_to_goal', std_msgs.msg.Float64),\n    TopicConfig('move_base_node/MIRPlannerROS/local_plan', nav_msgs.msg.Path),\n    # TopicConfig('move_base_node/MIRPlannerROS/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    # TopicConfig('move_base_node/MIRPlannerROS/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('move_base_node/MIRPlannerROS/updated_global_plan', mir_msgs.msg.PlanSegments),\n    # TopicConfig('move_base_node/MIRPlannerROS/visualization_marker', visualization_msgs.msg.MarkerArray),\n    TopicConfig('move_base_node/SBPLLatticePlanner/plan', nav_msgs.msg.Path),\n    # TopicConfig(\n    #   'move_base_node/SBPLLatticePlanner/sbpl_lattice_planner_stats', sbpl_lattice_planner.msg.SBPLLatticePlannerStats\n    # ),\n    # TopicConfig('move_base_node/SBPLLatticePlanner/visualization_marker', visualization_msgs.msg.MarkerArray),\n    TopicConfig('move_base_node/current_goal', geometry_msgs.msg.PoseStamped),\n    # TopicConfig('move_base_node/global_costmap/inflated_obstacles', nav_msgs.msg.GridCells),\n    # TopicConfig('move_base_node/global_costmap/obstacles', nav_msgs.msg.GridCells),\n    # TopicConfig('move_base_node/global_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    # TopicConfig('move_base_node/global_costmap/parameter_updates', dynamic_reconfigure.msg.Config),\n    # TopicConfig('move_base_node/global_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped),\n    # TopicConfig('move_base_node/global_costmap/unknown_space', nav_msgs.msg.GridCells),\n    # TopicConfig('move_base_node/global_plan', nav_msgs.msg.Path),\n    TopicConfig('move_base_node/local_costmap/inflated_obstacles', nav_msgs.msg.GridCells),\n    TopicConfig('move_base_node/local_costmap/obstacles', nav_msgs.msg.GridCells),\n    # TopicConfig('move_base_node/local_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    # TopicConfig('move_base_node/local_costmap/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('move_base_node/local_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped),\n    # TopicConfig('move_base_node/local_costmap/safety_zone', geometry_msgs.msg.PolygonStamped),\n    # TopicConfig('move_base_node/local_costmap/unknown_space', nav_msgs.msg.GridCells),\n    # TopicConfig('move_base_node/mir_escape_recovery/visualization_marker', visualization_msgs.msg.Marker),\n    # TopicConfig('move_base_node/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    # TopicConfig('move_base_node/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('move_base_node/time_to_coll', std_msgs.msg.Float64),\n    TopicConfig('move_base_node/traffic_costmap/inflated_obstacles', nav_msgs.msg.GridCells),\n    TopicConfig('move_base_node/traffic_costmap/obstacles', nav_msgs.msg.GridCells),\n    TopicConfig('move_base_node/traffic_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    TopicConfig('move_base_node/traffic_costmap/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('move_base_node/traffic_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped),\n    TopicConfig('move_base_node/traffic_costmap/unknown_space', nav_msgs.msg.GridCells),\n    TopicConfig('move_base_node/visualization_marker', visualization_msgs.msg.Marker),\n    TopicConfig('move_base_simple/visualization_marker', visualization_msgs.msg.Marker),\n    TopicConfig('odom', nav_msgs.msg.Odometry),\n    TopicConfig('odom_enc', nav_msgs.msg.Odometry),\n    # TopicConfig('one_way_map', nav_msgs.msg.OccupancyGrid),\n    # TopicConfig('param_update', std_msgs.msg.String),\n    # TopicConfig('particlevizmarker', visualization_msgs.msg.MarkerArray),\n    # TopicConfig('resource_tracker/needed_resources', mir_msgs.msg.ResourcesState),\n    TopicConfig('robot_mode', mir_msgs.msg.RobotMode),\n    TopicConfig('robot_pose', geometry_msgs.msg.Pose),\n    TopicConfig('robot_state', mir_msgs.msg.RobotState),\n    # TopicConfig('robot_status', mir_msgs.msg.RobotStatus),\n    TopicConfig('/rosout', rosgraph_msgs.msg.Log),\n    TopicConfig('/rosout_agg', rosgraph_msgs.msg.Log),\n    TopicConfig('scan', sensor_msgs.msg.LaserScan),\n    # TopicConfig('scan_filter/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription),\n    # TopicConfig('scan_filter/parameter_updates', dynamic_reconfigure.msg.Config),\n    TopicConfig('scan_filter/visualization_marker', visualization_msgs.msg.Marker),\n    # TopicConfig('session_importer_node/info', mirSessionImporter.msg.SessionImportInfo),\n    # TopicConfig('set_mc_PID', std_msgs.msg.Float64MultiArray),\n    TopicConfig('/tf', tf2_msgs.msg.TFMessage, dict_filter=_tf_dict_filter),\n    TopicConfig('/tf_static', tf2_msgs.msg.TFMessage, dict_filter=_tf_static_dict_filter, latch=True),\n    # TopicConfig('traffic_map', nav_msgs.msg.OccupancyGrid),\n    # TopicConfig('wifi_diagnostics', diagnostic_msgs.msg.DiagnosticArray),\n    # TopicConfig('wifi_diagnostics/cur_ap', mir_wifi_msgs.msg.APInfo),\n    # TopicConfig('wifi_diagnostics/roam_events', mir_wifi_msgs.msg.WifiRoamEvent),\n    # TopicConfig('wifi_diagnostics/wifi_ap_interface_stats', mir_wifi_msgs.msg.WifiInterfaceStats),\n    # TopicConfig('wifi_diagnostics/wifi_ap_rssi', mir_wifi_msgs.msg.APRssiStats),\n    # TopicConfig('wifi_diagnostics/wifi_ap_time_stats', mir_wifi_msgs.msg.APTimeStats),\n    # TopicConfig('wifi_watchdog/ping', mir_wifi_msgs.msg.APPingStats),\n]\n\n# topics we want to subscribe to from ROS (and publish to the MiR)\nSUB_TOPICS = [\n    # really geometry_msgs.msg.TwistStamped:\n    TopicConfig('cmd_vel', geometry_msgs.msg.Twist, dict_filter=_cmd_vel_dict_filter),\n    TopicConfig('initialpose', geometry_msgs.msg.PoseWithCovarianceStamped),\n    TopicConfig('light_cmd', std_msgs.msg.String),\n    TopicConfig('mir_cmd', std_msgs.msg.String),\n    TopicConfig('move_base/cancel', actionlib_msgs.msg.GoalID),\n    # really mir_actions/MirMoveBaseActionGoal:\n    TopicConfig('move_base/goal', move_base_msgs.msg.MoveBaseActionGoal, dict_filter=_move_base_goal_dict_filter),\n]\n\n\nclass PublisherWrapper(rospy.SubscribeListener):\n    def __init__(self, topic_config, robot):\n        self.topic_config = topic_config\n        self.robot = robot\n        self.connected = False\n        # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace.\n        self.pub = rospy.Publisher(\n            name=topic_config.topic,\n            data_class=topic_config.topic_type,\n            subscriber_listener=self,\n            latch=topic_config.latch,\n            queue_size=10,\n        )\n        rospy.loginfo(\n            \"[%s] publishing topic '%s' [%s]\", rospy.get_name(), topic_config.topic, topic_config.topic_type._type\n        )\n        # latched topics must be subscribed immediately\n        if topic_config.latch:\n            self.peer_subscribe(\"\", None, None)\n\n    def peer_subscribe(self, topic_name, topic_publish, peer_publish):\n        if not self.connected:\n            self.connected = True\n            rospy.loginfo(\"[%s] starting to stream messages on topic '%s'\", rospy.get_name(), self.topic_config.topic)\n            absolute_topic = '/' + self.topic_config.topic.lstrip('/')  # ensure exactly 1 leading slash for MiR comm\n            self.robot.subscribe(topic=absolute_topic, callback=self.callback)\n\n    def peer_unsubscribe(self, topic_name, num_peers):\n        pass\n        # doesn't work: once ubsubscribed, robot doesn't let us subscribe again\n        # if self.connected and self.pub.get_num_connections() == 0 and not self.topic_config.latch:\n        #     self.connected = False\n        #     rospy.loginfo(\"[%s] stopping to stream messages on topic '%s'\", rospy.get_name(), self.topic_config.topic)\n        #     absolute_topic = '/' + self.topic_config.topic.lstrip('/')  # ensure exactly 1 leading slash for MiR comm\n        #     self.robot.unsubscribe(topic=absolute_topic)\n\n    def callback(self, msg_dict):\n        msg_dict = _prepend_tf_prefix_dict_filter(msg_dict)\n        if self.topic_config.dict_filter is not None:\n            msg_dict = self.topic_config.dict_filter(msg_dict)\n        msg = message_converter.convert_dictionary_to_ros_message(self.topic_config.topic_type._type, msg_dict)\n        self.pub.publish(msg)\n\n\nclass SubscriberWrapper(object):\n    def __init__(self, topic_config, robot):\n        self.topic_config = topic_config\n        self.robot = robot\n        # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace.\n        self.sub = rospy.Subscriber(\n            name=topic_config.topic, data_class=topic_config.topic_type, callback=self.callback, queue_size=10\n        )\n        rospy.loginfo(\n            \"[%s] subscribing to topic '%s' [%s]\", rospy.get_name(), topic_config.topic, topic_config.topic_type._type\n        )\n\n    def callback(self, msg):\n        msg_dict = message_converter.convert_ros_message_to_dictionary(msg)\n        msg_dict = _remove_tf_prefix_dict_filter(msg_dict)\n        if self.topic_config.dict_filter is not None:\n            msg_dict = self.topic_config.dict_filter(msg_dict)\n        absolute_topic = '/' + self.topic_config.topic.lstrip('/')  # ensure exactly 1 leading slash for MiR comm\n        self.robot.publish(absolute_topic, msg_dict)\n\n\nclass MiRBridge(object):\n    def __init__(self):\n        try:\n            hostname = rospy.get_param('~hostname')\n        except KeyError:\n            rospy.logfatal('[%s] parameter \"hostname\" is not set!', rospy.get_name())\n            sys.exit(-1)\n        port = rospy.get_param('~port', 9090)\n\n        global tf_prefix\n        tf_prefix = rospy.get_param('~tf_prefix', '').strip('/')\n\n        rospy.loginfo('[%s] trying to connect to %s:%i...', rospy.get_name(), hostname, port)\n        self.robot = rosbridge.RosbridgeSetup(hostname, port)\n\n        r = rospy.Rate(10)\n        i = 1\n        while not self.robot.is_connected():\n            if rospy.is_shutdown():\n                sys.exit(0)\n            if self.robot.is_errored():\n                rospy.logfatal('[%s] connection error to %s:%i, giving up!', rospy.get_name(), hostname, port)\n                sys.exit(-1)\n            if i % 10 == 0:\n                rospy.logwarn('[%s] still waiting for connection to %s:%i...', rospy.get_name(), hostname, port)\n            i += 1\n            r.sleep()\n\n        rospy.loginfo('[%s] ... connected.', rospy.get_name())\n\n        topics = self.get_topics()\n        published_topics = [topic_name for (topic_name, _, has_publishers, _) in topics if has_publishers]\n        subscribed_topics = [topic_name for (topic_name, _, _, has_subscribers) in topics if has_subscribers]\n\n        for pub_topic in PUB_TOPICS:\n            PublisherWrapper(pub_topic, self.robot)\n            absolute_topic = '/' + pub_topic.topic.lstrip('/')  # ensure exactly 1 leading slash for MiR comm\n            if absolute_topic not in published_topics:\n                rospy.logwarn(\"[%s] topic '%s' is not published by the MiR!\", rospy.get_name(), pub_topic.topic)\n\n        for sub_topic in SUB_TOPICS:\n            SubscriberWrapper(sub_topic, self.robot)\n            absolute_topic = '/' + sub_topic.topic.lstrip('/')  # ensure exactly 1 leading slash for MiR comm\n            if absolute_topic not in subscribed_topics:\n                rospy.logwarn(\"[%s] topic '%s' is not yet subscribed to by the MiR!\", rospy.get_name(), sub_topic.topic)\n\n        # At least with software version 2.8 there were issues when forwarding a simple goal to the robot\n        # This workaround converts it into an action. Check https://github.com/DFKI-NI/mir_robot/issues/60 for details.\n        self._move_base_client = SimpleActionClient('move_base', move_base_msgs.msg.MoveBaseAction)\n        rospy.Subscriber(\"move_base_simple/goal\", geometry_msgs.msg.PoseStamped, self._move_base_simple_goal_callback)\n\n    def get_topics(self):\n        srv_response = self.robot.callService('/rosapi/topics', msg={})\n        topic_names = sorted(srv_response['topics'])\n        topics = []\n\n        for topic_name in topic_names:\n            srv_response = self.robot.callService(\"/rosapi/topic_type\", msg={'topic': topic_name})\n            topic_type = srv_response['type']\n\n            srv_response = self.robot.callService(\"/rosapi/publishers\", msg={'topic': topic_name})\n            has_publishers = True if len(srv_response['publishers']) > 0 else False\n\n            srv_response = self.robot.callService(\"/rosapi/subscribers\", msg={'topic': topic_name})\n            has_subscribers = True if len(srv_response['subscribers']) > 0 else False\n\n            topics.append([topic_name, topic_type, has_publishers, has_subscribers])\n\n        print('Publishers:')\n        for topic_name, topic_type, has_publishers, has_subscribers in topics:\n            if has_publishers:\n                print((' * %s [%s]' % (topic_name, topic_type)))\n\n        print('\\nSubscribers:')\n        for topic_name, topic_type, has_publishers, has_subscribers in topics:\n            if has_subscribers:\n                print((' * %s [%s]' % (topic_name, topic_type)))\n\n        return topics\n\n    def _move_base_simple_goal_callback(self, msg):\n        if not self._move_base_client.wait_for_server(rospy.Duration(2)):\n            rospy.logwarn(\"Could not connect to 'move_base' server after two seconds. Dropping goal.\")\n            rospy.logwarn(\"Did you activate 'planner' in the MIR web interface?\")\n            return\n        goal = move_base_msgs.msg.MoveBaseGoal()\n        goal.target_pose.header = copy.deepcopy(msg.header)\n        goal.target_pose.pose = copy.deepcopy(msg.pose)\n        self._move_base_client.send_goal(goal)\n\n\ndef main():\n    rospy.init_node('mir_bridge')\n    MiRBridge()\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    try:\n        main()\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "mir_driver/nodes/rep117_filter.py",
    "content": "#!/usr/bin/env python3\n\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\nfrom sensor_msgs.msg import LaserScan\n\npub = None\n\n\ndef callback(msg):\n    \"\"\"\n    Convert laser scans to REP 117 standard.\n\n    See http://www.ros.org/reps/rep-0117.html\n    \"\"\"\n    ranges_out = []\n    for dist in msg.ranges:\n        if dist < msg.range_min:\n            # assume \"reading too close to measure\",\n            # although it could also be \"reading invalid\" (nan)\n            ranges_out.append(float(\"-inf\"))\n\n        elif dist > msg.range_max:\n            # assume \"reading of no return (outside sensor range)\",\n            # although it could also be \"reading invalid\" (nan)\n            ranges_out.append(float(\"inf\"))\n        else:\n            ranges_out.append(dist)\n\n    msg.ranges = ranges_out\n    pub.publish(msg)\n\n\ndef main():\n    global pub\n    rospy.init_node('rep117_filter')\n\n    pub = rospy.Publisher('scan_filtered', LaserScan, queue_size=10)\n    rospy.Subscriber('scan', LaserScan, callback)\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    try:\n        main()\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "mir_driver/nodes/tf_remove_child_frames.py",
    "content": "#!/usr/bin/env python3\n# -*- coding: utf-8 -*-\n\n# Copyright 2016 The Cartographer Authors\n# Copyright 2018 DFKI GmbH\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 rospy\nfrom tf.msg import tfMessage\n\n\ndef main():\n    rospy.init_node('tf_remove_child_frames')\n    remove_frames = rospy.get_param('~remove_frames', [])\n\n    # filter tf_in topic\n    tf_pub = rospy.Publisher('tf_out', tfMessage, queue_size=1)\n\n    def tf_cb(msg):\n        msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames]\n        if len(msg.transforms) > 0:\n            tf_pub.publish(msg)\n\n    rospy.Subscriber('tf_in', tfMessage, tf_cb)\n\n    # filter tf_static_in topic\n    tf_static_pub = rospy.Publisher('tf_static_out', tfMessage, queue_size=1, latch=True)\n\n    def tf_static_cb(msg):\n        msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames]\n        if len(msg.transforms) > 0:\n            tf_static_pub.publish(msg)\n\n    rospy.Subscriber('tf_static_in', tfMessage, tf_static_cb)\n\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "mir_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_driver</name>\n  <version>1.1.8</version>\n  <description>A reverse ROS bridge for the MiR robot</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n  <license>Apache-2.0</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roslaunch</build_depend>\n\n  <depend>actionlib</depend>\n  <depend>actionlib_msgs</depend>\n  <depend>diagnostic_msgs</depend>\n  <depend>dynamic_reconfigure</depend>\n  <depend>geometry_msgs</depend>\n  <depend>mir_actions</depend>\n  <depend>mir_msgs</depend>\n  <depend>move_base_msgs</depend>\n  <depend>nav_msgs</depend>\n  <depend>python3-websocket</depend>\n  <depend>rosgraph_msgs</depend>\n  <depend>rospy</depend>\n  <depend>rospy_message_converter</depend>\n  <depend>sdc21x0</depend>\n  <depend>sensor_msgs</depend>\n  <depend>std_msgs</depend>\n  <depend>tf2_msgs</depend>\n  <depend>tf</depend>\n  <depend>visualization_msgs</depend>\n\n  <exec_depend>mir_description</exec_depend>\n  <exec_depend>robot_state_publisher</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_driver/setup.py",
    "content": "# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD\n\nfrom distutils.core import setup\nfrom catkin_pkg.python_setup import generate_distutils_setup\n\n# fetch values from package.xml\nsetup_args = generate_distutils_setup(packages=['mir_driver'], package_dir={'': 'src'})\n\nsetup(**setup_args)\n"
  },
  {
    "path": "mir_driver/src/mir_driver/__init__.py",
    "content": ""
  },
  {
    "path": "mir_driver/src/mir_driver/rosbridge.py",
    "content": "# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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\nimport websocket\nimport threading\n\nimport json\nimport traceback\nimport time\n\nimport string\nimport random\n\n\nclass RosbridgeSetup:\n    def __init__(self, host, port):\n        self.callbacks = {}\n        self.service_callbacks = {}\n        self.resp = None\n        self.connection = RosbridgeWSConnection(host, port)\n        self.connection.registerCallback(self.onMessageReceived)\n\n    def publish(self, topic, obj):\n        pub = {\"op\": \"publish\", \"topic\": topic, \"msg\": obj}\n        self.send(pub)\n\n    def subscribe(self, topic, callback, throttle_rate=-1):\n        if self.addCallback(topic, callback):\n            sub = {\"op\": \"subscribe\", \"topic\": topic}\n            if throttle_rate > 0:\n                sub['throttle_rate'] = throttle_rate\n\n            self.send(sub)\n\n    def unhook(self, callback):\n        keys_for_deletion = []\n        for key, values in self.callbacks.items():\n            for value in values:\n                if callback == value:\n                    print(\"Found!\")\n                    values.remove(value)\n                    if len(values) == 0:\n                        keys_for_deletion.append(key)\n\n        for key in keys_for_deletion:\n            self.unsubscribe(key)\n            self.callbacks.pop(key)\n\n    def unsubscribe(self, topic):\n        unsub = {\"op\": \"unsubscribe\", \"topic\": topic}\n        self.send(unsub)\n\n    def callService(self, serviceName, callback=None, msg=None):\n        id = self.generate_id()\n        call = {\"op\": \"call_service\", \"id\": id, \"service\": serviceName}\n        if msg is not None:\n            call['args'] = msg\n\n        if callback is None:\n            self.resp = None\n\n            def internalCB(msg):\n                self.resp = msg\n                return None\n\n            self.addServiceCallback(id, internalCB)\n            self.send(call)\n\n            while self.resp is None:\n                time.sleep(0.01)\n\n            return self.resp\n\n        self.addServiceCallback(id, callback)\n        self.send(call)\n        return None\n\n    def send(self, obj):\n        try:\n            self.connection.sendString(json.dumps(obj))\n        except Exception:\n            traceback.print_exc()\n            raise\n\n    def generate_id(self, chars=16):\n        return ''.join(random.SystemRandom().choice(string.ascii_letters + string.digits) for _ in range(chars))\n\n    def addServiceCallback(self, id, callback):\n        self.service_callbacks[id] = callback\n\n    def addCallback(self, topic, callback):\n        if topic in self.callbacks:\n            self.callbacks[topic].append(callback)\n            return False\n\n        self.callbacks[topic] = [callback]\n        return True\n\n    def is_connected(self):\n        return self.connection.connected\n\n    def is_errored(self):\n        return self.connection.errored\n\n    def onMessageReceived(self, message):\n        try:\n            # Load the string into a JSON object\n            obj = json.loads(message)\n            # print \"Received: \", obj\n\n            if 'op' in obj:\n                option = obj['op']\n                if option == \"publish\":  # A message from a topic we have subscribed to..\n                    topic = obj[\"topic\"]\n                    msg = obj[\"msg\"]\n                    if topic in self.callbacks:\n                        for callback in self.callbacks[topic]:\n                            try:\n                                callback(msg)\n                            except Exception:\n                                print(\"exception on callback\", callback, \"from\", topic)\n                                traceback.print_exc()\n                                raise\n                elif option == \"service_response\":\n                    if \"id\" in obj:\n                        id = obj[\"id\"]\n                        values = obj[\"values\"]\n                        if id in self.service_callbacks:\n                            try:\n                                # print 'id:', id, 'func:', self.service_callbacks[id]\n                                self.service_callbacks[id](values)\n                            except Exception:\n                                print(\"exception on callback ID:\", id)\n                                traceback.print_exc()\n                                raise\n                    else:\n                        print(\"Missing ID!\")\n                else:\n                    print(\"Recieved unknown option - it was: \", option)\n            else:\n                print(\"No OP key!\")\n        except Exception:\n            print(\"exception in onMessageReceived\")\n            print(\"message\", message)\n            traceback.print_exc()\n            raise\n\n\nclass RosbridgeWSConnection:\n    def __init__(self, host, port):\n        self.ws = websocket.WebSocketApp(\n            (\"ws://%s:%d/\" % (host, port)), on_message=self.on_message, on_error=self.on_error, on_close=self.on_close\n        )\n        self.ws.on_open = self.on_open\n        self.run_thread = threading.Thread(target=self.run)\n        self.run_thread.start()\n        self.connected = False\n        self.errored = False\n        self.callbacks = []\n\n    def on_open(self):\n        print(\"### ROS bridge connected ###\")\n        self.connected = True\n\n    def sendString(self, message):\n        if not self.connected:\n            print(\"Error: not connected, could not send message\")\n            # TODO: throw exception\n        else:\n            self.ws.send(message)\n\n    def on_error(self, error):\n        self.errored = True\n        print(\"Error: %s\" % error)\n\n    def on_close(self):\n        self.connected = False\n        print(\"### ROS bridge closed ###\")\n\n    def run(self, *args):\n        self.ws.run_forever()\n\n    def on_message(self, message):\n        # Call the handlers\n        for callback in self.callbacks:\n            callback(message)\n\n    def registerCallback(self, callback):\n        self.callbacks.append(callback)\n"
  },
  {
    "path": "mir_dwb_critics/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_dwb_critics\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Fix typo in license\n* mir_dwb_critics: Fill in description\n* Re-format C++ files using clang-format\n* mir_dwb_critics: Fix URLs in package.xml\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Drop old C++ compiler flags\n* Add license headers\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Reformat python code using black\n* Contributors: Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Fix bug in path_dist_pruned\n  With some paths, the previous code crashed with \"terminate called after throwing an instance\n  of 'std::bad_alloc'\".\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Update scripts to Python3 (Noetic)\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Add missing matplotlib dependency\n* Fix some catkin_lint warnings\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n* mir_dwb_critics: Add plot_dwb_scores.py\n* mir_dwb_critics: Improve print_dwb_scores output\n* added PathDistPrunedCritic for dwb (`#42 <https://github.com/DFKI-NI/mir_robot/issues/42>`_)\n  which works exactly like the original PathDistCritic, except that it\n  searches for a local minimum in the distance from the global path to the robots\n  current position. It then prunes the global_path from the start up to\n  this point, therefore approximately cutting of a segment of the path\n  that the robot already followed.\n* Contributors: Martin Günther, Nils Niemann\n\n1.0.4 (2019-05-06)\n------------------\n\n1.0.3 (2019-03-04)\n------------------\n* PathProgressCritic: Add heading score\n* Add package: mir_dwb_critics\n* Contributors: Martin Günther\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n"
  },
  {
    "path": "mir_dwb_critics/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_dwb_critics)\n\nset_directory_properties(PROPERTIES COMPILE_OPTIONS \"-Wall;-Werror\")\n\nfind_package(catkin REQUIRED COMPONENTS\n  angles\n  costmap_queue\n  dwb_critics\n  dwb_local_planner\n  geometry_msgs\n  nav_2d_msgs\n  nav_2d_utils\n  nav_core2\n  nav_grid_iterators\n  pluginlib\n  roscpp\n  sensor_msgs\n)\n\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES ${PROJECT_NAME}\n  CATKIN_DEPENDS angles costmap_queue dwb_critics dwb_local_planner geometry_msgs nav_2d_msgs nav_2d_utils nav_core2 nav_grid_iterators pluginlib roscpp sensor_msgs\n)\n\ninclude_directories(\n  include\n  ${catkin_INCLUDE_DIRS}\n)\n\nadd_library(${PROJECT_NAME}\n  src/path_angle.cpp\n  src/path_progress.cpp\n  src/path_dist_pruned.cpp\n)\nadd_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS})\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\ninstall(PROGRAMS\n    nodes/print_dwb_scores.py\n    nodes/plot_dwb_scores.py\n  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\ninstall(TARGETS ${PROJECT_NAME}\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n)\ninstall(DIRECTORY include/${PROJECT_NAME}/\n  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n)\ninstall(FILES default_critics.xml\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n"
  },
  {
    "path": "mir_dwb_critics/default_critics.xml",
    "content": "<class_libraries>\n  <library path=\"lib/libmir_dwb_critics\">\n    <class type=\"mir_dwb_critics::PathProgressCritic\" base_class_type=\"dwb_local_planner::TrajectoryCritic\">\n      <description>Scores trajectories based on how far along the global path they end up.</description>\n    </class>\n    <class type=\"mir_dwb_critics::PathAngleCritic\" base_class_type=\"dwb_local_planner::TrajectoryCritic\">\n      <description>Scores trajectories based on the difference between the path's current angle and the trajectory's angle</description>\n    </class>\n    <class type=\"mir_dwb_critics::PathDistPrunedCritic\" base_class_type=\"dwb_local_planner::TrajectoryCritic\">\n      <description>Scores trajectories based on the distance to the global path, only taking the parts into account that are still ahead of the robot.</description>\n    </class>\n  </library>\n</class_libraries>\n"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_angle.h",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n#ifndef MIR_DWB_CRITICS_PATH_ANGLE_H_\n#define MIR_DWB_CRITICS_PATH_ANGLE_H_\n\n#include <dwb_local_planner/trajectory_critic.h>\n#include <vector>\n\nnamespace mir_dwb_critics\n{\n/**\n * @class PathAngleCritic\n * @brief Scores trajectories based on the difference between the path's current angle and the trajectory's angle\n *\n * This trajectory critic helps to ensure that the robot is roughly aligned with the path (i.e.,\n * if the path specifies a forward motion, the robot should point forward along the path and vice versa).\n * This critic is not a replacement for the PathAlignCritic: The PathAlignCritic tries to point the robot\n * towards a point on the path that is in front of the trajectory's end point, so it helps guiding the\n * robot back towards the path. The PathAngleCritic on the other hand uses the path point that is closest\n * to the robot's current position (not the trajectory end point, or even a point in front of that) as a\n * reference, so it always lags behind. Also, it tries to keep the robot parallel to the path, not towards\n * it. For these reasons, the error is squared, so that the PathAngleCritic really only affects the final\n * score if the error is large. The PathAlignCritic doesn't take the path orientation into account though,\n * so that's why the PathAngleCritic is a useful addition.\n */\nclass PathAngleCritic : public dwb_local_planner::TrajectoryCritic\n{\npublic:\n  virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,\n                       const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override;\n\n  virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override;\n\nprotected:\n  double desired_angle_;\n};\n\n}  // namespace mir_dwb_critics\n#endif  // MIR_DWB_CRITICS_PATH_ANGLE_H_\n"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n#ifndef MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_\n#define MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_\n\n#include <dwb_critics/path_dist.h>\n#include <vector>\n\nnamespace mir_dwb_critics\n{\n/**\n * @class PathDistPrunedCritic\n * @brief Scores trajectories based on how far from the global path they end up,\n *        where the global path is pruned to only include waypoints ahead of the\n *        robot.\n */\nclass PathDistPrunedCritic : public dwb_critics::PathDistCritic\n{\npublic:\n  virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,\n                       const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override;\n};\n\n}  // namespace mir_dwb_critics\n#endif  // MIR_DWB_CRITICS_DISTANCE_PRUNED_H_\n"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_progress.h",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n#ifndef MIR_DWB_CRITICS_PATH_PROGRESS_H_\n#define MIR_DWB_CRITICS_PATH_PROGRESS_H_\n\n#include <dwb_critics/map_grid.h>\n#include <vector>\n\nnamespace mir_dwb_critics\n{\n/**\n * @class PathProgressCritic\n * @brief Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal.\n *\n * This trajectory critic helps ensure progress along the global path. It\n * calculates an intermediate goal that is as far as possible along the global\n * path as long as the path continues to move in one direction (+/-\n * angle_threshold).\n */\nclass PathProgressCritic : public dwb_critics::MapGridCritic\n{\npublic:\n  bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal,\n               const nav_2d_msgs::Path2D& global_plan) override;\n\n  void onInit() override;\n  void reset() override;\n  double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override;\n\nprotected:\n  bool getGoalPose(const geometry_msgs::Pose2D& robot_pose, const nav_2d_msgs::Path2D& global_plan, unsigned int& x,\n                   unsigned int& y, double& desired_angle);\n\n  unsigned int getGoalIndex(const std::vector<geometry_msgs::Pose2D>& plan, unsigned int start_index,\n                            unsigned int last_valid_index) const;\n\n  double xy_local_goal_tolerance_;\n  double angle_threshold_;\n  double heading_scale_;\n\n  std::vector<geometry_msgs::Pose2D> reached_intermediate_goals_;\n  double desired_angle_;\n};\n\n}  // namespace mir_dwb_critics\n#endif  // MIR_DWB_CRITICS_PATH_PROGRESS_H_\n"
  },
  {
    "path": "mir_dwb_critics/nodes/plot_dwb_scores.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport os\nimport tkinter\nimport matplotlib.pyplot as plt\nimport numpy as np\n\nimport rospy\nfrom dwb_msgs.msg import LocalPlanEvaluation\n\nfig = None\nrects = None\nmax_score = 0.0\n\n\ndef eval_cb(msg):\n    global fig, rects, max_score\n    labels = [s.name for s in msg.twists[msg.best_index].scores]\n    scaled_scores = [s.scale * s.raw_score for s in msg.twists[msg.best_index].scores]\n\n    # reverse labels + scaled_scores to show the critics in the correct order top to bottom\n    labels.reverse()\n    scaled_scores.reverse()\n\n    if not fig:\n        # init\n        y = np.arange(len(labels))  # the label locations\n        height = 0.35  # the height of the bars\n\n        fig, ax = plt.subplots()\n        rects = ax.barh(y - height / 2, scaled_scores, height, label='scaled score')\n\n        ax.set_ylabel('DWB Critics')\n        ax.set_title('Scaled scores')\n        ax.set_yticks(y)\n        ax.set_yticklabels(labels)\n\n        fig.tight_layout()\n        fig.canvas.set_window_title('DWB Scores')\n\n    # update axis limit\n    if max_score < max(scaled_scores):\n        max_score = max(scaled_scores)\n        plt.xlim(0.0, max_score)\n\n    for rect, h in zip(rects, scaled_scores):\n        rect.set_width(h)\n    try:\n        fig.canvas.draw()\n        fig.canvas.flush_events()\n    except tkinter.TclError:\n        rospy.loginfo('Window was closed, exiting.')\n        os._exit(0)\n\n\ndef main():\n    rospy.init_node('plot_dwb_scores')\n    rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb)\n    rospy.loginfo('plot_dwb_scores ready.')\n    plt.ion()\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "mir_dwb_critics/nodes/print_dwb_scores.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\n\nfrom dwb_msgs.msg import LocalPlanEvaluation\n\n\ndef eval_cb(msg):\n    print('\\n\\n=========================================================\\n\\n')\n    for heading, i in zip(['best trajectory', 'worst trajectory'], [msg.best_index, msg.worst_index]):\n        print('### {}\\n'.format(heading))\n        print('Name                 |       Raw |   Scale | Scaled Score')\n        print('---------------------|-----------|---------|-------------')\n        for s in msg.twists[i].scores:\n            print('{:20} | {:9.4f} | {:7.4f} | {:12.4f}'.format(s.name, s.raw_score, s.scale, s.raw_score * s.scale))\n        print('---------------------------------------- total: {:9.4f}'.format(msg.twists[i].total))\n        print()\n\n\ndef main():\n    rospy.init_node('print_dwb_scores', anonymous=True)\n    rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb)\n    rospy.loginfo('print_dwb_scores ready.')\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "mir_dwb_critics/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_dwb_critics</name>\n  <version>1.1.8</version>\n  <description>\n    Trajectory critics for the dwb_local_planner that work well together with the SBPL global planner on the MiR robot\n  </description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>angles</depend>\n  <depend>costmap_queue</depend>\n  <depend>dwb_critics</depend>\n  <depend>dwb_local_planner</depend>\n  <depend>geometry_msgs</depend>\n  <depend>nav_2d_msgs</depend>\n  <depend>nav_2d_utils</depend>\n  <depend>nav_core2</depend>\n  <depend>nav_grid_iterators</depend>\n  <depend>pluginlib</depend>\n  <depend>roscpp</depend>\n  <depend>sensor_msgs</depend>\n\n  <exec_depend>python3-matplotlib</exec_depend>\n\n  <export>\n    <dwb_local_planner plugin=\"${prefix}/default_critics.xml\"/>\n  </export>\n</package>\n"
  },
  {
    "path": "mir_dwb_critics/src/path_angle.cpp",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <mir_dwb_critics/path_angle.h>\n#include <pluginlib/class_list_macros.h>\n#include <nav_2d_utils/path_ops.h>\n#include <nav_grid/coordinate_conversion.h>\n#include <vector>\n\nnamespace mir_dwb_critics\n{\nbool PathAngleCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,\n                              const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)\n{\n  const nav_core2::Costmap& costmap = *costmap_;\n  const nav_grid::NavGridInfo& info = costmap.getInfo();\n  nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution);\n\n  if (global_plan.poses.empty())\n  {\n    ROS_ERROR_NAMED(\"PathAngleCritic\", \"The global plan was empty.\");\n    return false;\n  }\n\n  // find the angle of the plan at the pose on the plan closest to the robot\n  double distance_min = std::numeric_limits<double>::infinity();\n  bool started_path = false;\n  for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); i++)\n  {\n    double g_x = adjusted_global_plan.poses[i].x;\n    double g_y = adjusted_global_plan.poses[i].y;\n    unsigned int map_x, map_y;\n    if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION)\n    {\n      double distance = nav_2d_utils::poseDistance(adjusted_global_plan.poses[i], pose);\n      if (distance_min > distance)\n      {\n        // still getting closer\n        desired_angle_ = adjusted_global_plan.poses[i].theta;\n        distance_min = distance;\n        started_path = true;\n      }\n      else\n      {\n        // plan is going away from the robot again\n        break;\n      }\n    }\n    else if (started_path)\n    {\n      // Off the costmap after being on the costmap.\n      break;\n    }\n    // else, we have not yet found a point on the costmap, so we just continue\n  }\n\n  if (!started_path)\n  {\n    ROS_ERROR_NAMED(\"PathAngleCritic\", \"None of the points of the global plan were in the local costmap.\");\n    return false;\n  }\n  return true;\n}\n\ndouble PathAngleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj)\n{\n  double diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI));\n  return diff * diff;\n}\n\n}  // namespace mir_dwb_critics\n\nPLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathAngleCritic, dwb_local_planner::TrajectoryCritic)\n"
  },
  {
    "path": "mir_dwb_critics/src/path_dist_pruned.cpp",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n#include <nav_2d_utils/path_ops.h>\n#include <pluginlib/class_list_macros.h>\n\n#include \"mir_dwb_critics/path_dist_pruned.h\"\n\nnamespace mir_dwb_critics\n{\nbool PathDistPrunedCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,\n                                   const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)\n{\n  const nav_core2::Costmap& costmap = *costmap_;\n  const nav_grid::NavGridInfo& info = costmap.getInfo();\n\n  auto plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses;\n\n  // --- stolen from PathProgressCritic::getGoalPose ---\n  // find the \"start pose\", i.e. the pose on the plan closest to the robot that is also on the local map\n  unsigned int start_index = 0;\n  double distance_to_start = std::numeric_limits<double>::infinity();\n  bool started_path = false;\n  for (unsigned int i = 0; i < plan.size(); i++)\n  {\n    double g_x = plan[i].x;\n    double g_y = plan[i].y;\n    unsigned int map_x, map_y;\n    if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION)\n    {\n      // Still on the costmap. Continue.\n      double distance = nav_2d_utils::poseDistance(plan[i], pose);\n      if (distance_to_start > distance)\n      {\n        start_index = i;\n        distance_to_start = distance;\n        started_path = true;\n      }\n      else\n      {\n        // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's\n        // even closer to the robot, but then we would skip over parts of the plan.\n        break;\n      }\n    }\n    else if (started_path)\n    {\n      // Off the costmap after being on the costmap.\n      break;\n    }\n    // else, we have not yet found a point on the costmap, so we just continue\n  }\n\n  if (!started_path)\n  {\n    ROS_ERROR_NAMED(\"PathDistPrunedCritic\", \"None of the points of the global plan were in the local costmap.\");\n    return false;\n  }\n  // ---------------------------------------------------\n\n  // remove the first part of the path, everything before start_index, to\n  // disregard that part in the PathDistCritic implementation.\n  nav_2d_msgs::Path2D global_plan_pruned;\n  global_plan_pruned.header = global_plan.header;\n  global_plan_pruned.poses = std::vector<geometry_msgs::Pose2D>(plan.begin() + start_index, plan.end());\n\n  return dwb_critics::PathDistCritic::prepare(pose, vel, goal, global_plan_pruned);\n}\n\n}  // namespace mir_dwb_critics\n\nPLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathDistPrunedCritic, dwb_local_planner::TrajectoryCritic)\n"
  },
  {
    "path": "mir_dwb_critics/src/path_progress.cpp",
    "content": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redistribution and use in source and binary forms, with or without\n *  modification, are permitted provided that the following conditions\n *  are met:\n *\n *   * Redistributions of source code must retain the above copyright\n *     notice, this list of conditions and the following disclaimer.\n *   * Redistributions in binary form must reproduce the above\n *     copyright notice, this list of conditions and the following\n *     disclaimer in the documentation and/or other materials provided\n *     with the distribution.\n *   * Neither the name of the copyright holder nor the names of its\n *     contributors may be used to endorse or promote products derived\n *     from this software without specific prior written permission.\n *\n *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n *  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n *  POSSIBILITY OF SUCH DAMAGE.\n */\n#include <mir_dwb_critics/path_progress.h>\n#include <nav_grid/coordinate_conversion.h>\n#include <pluginlib/class_list_macros.h>\n#include <nav_2d_utils/path_ops.h>\n#include <vector>\n\nnamespace mir_dwb_critics\n{\nbool PathProgressCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,\n                                 const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)\n{\n  dwb_critics::MapGridCritic::reset();\n\n  unsigned int local_goal_x, local_goal_y;\n  if (!getGoalPose(pose, global_plan, local_goal_x, local_goal_y, desired_angle_))\n  {\n    return false;\n  }\n\n  // Enqueue just the last pose\n  cell_values_.setValue(local_goal_x, local_goal_y, 0.0);\n  queue_->enqueueCell(local_goal_x, local_goal_y);\n\n  propogateManhattanDistances();\n\n  return true;\n}\n\nvoid PathProgressCritic::onInit()\n{\n  dwb_critics::MapGridCritic::onInit();\n  critic_nh_.param(\"xy_local_goal_tolerance\", xy_local_goal_tolerance_, 0.20);\n  critic_nh_.param(\"angle_threshold\", angle_threshold_, M_PI_4);\n  critic_nh_.param(\"heading_scale\", heading_scale_, 1.0);\n\n  // divide heading scale by position scale because the sum will be multiplied by scale again\n  heading_scale_ /= getScale();\n}\n\nvoid PathProgressCritic::reset()\n{\n  reached_intermediate_goals_.clear();\n}\n\ndouble PathProgressCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj)\n{\n  double position_score = MapGridCritic::scoreTrajectory(traj);\n  double heading_diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI));\n  double heading_score = heading_diff * heading_diff;\n\n  return position_score + heading_scale_ * heading_score;\n}\n\nbool PathProgressCritic::getGoalPose(const geometry_msgs::Pose2D& robot_pose, const nav_2d_msgs::Path2D& global_plan,\n                                     unsigned int& x, unsigned int& y, double& desired_angle)\n{\n  const nav_core2::Costmap& costmap = *costmap_;\n  const nav_grid::NavGridInfo& info = costmap.getInfo();\n\n  if (global_plan.poses.empty())\n  {\n    ROS_ERROR_NAMED(\"PathProgressCritic\", \"The global plan was empty.\");\n    return false;\n  }\n\n  std::vector<geometry_msgs::Pose2D> plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses;\n\n  // find the \"start pose\", i.e. the pose on the plan closest to the robot that is also on the local map\n  unsigned int start_index = 0;\n  double distance_to_start = std::numeric_limits<double>::infinity();\n  bool started_path = false;\n  for (unsigned int i = 0; i < plan.size(); i++)\n  {\n    double g_x = plan[i].x;\n    double g_y = plan[i].y;\n    unsigned int map_x, map_y;\n    if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION)\n    {\n      // Still on the costmap. Continue.\n      double distance = nav_2d_utils::poseDistance(plan[i], robot_pose);\n      if (distance_to_start > distance)\n      {\n        start_index = i;\n        distance_to_start = distance;\n        started_path = true;\n      }\n      else\n      {\n        // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's\n        // even closer to the robot, but then we would skip over parts of the plan.\n        break;\n      }\n    }\n    else if (started_path)\n    {\n      // Off the costmap after being on the costmap.\n      break;\n    }\n    // else, we have not yet found a point on the costmap, so we just continue\n  }\n\n  if (!started_path)\n  {\n    ROS_ERROR_NAMED(\"PathProgressCritic\", \"None of the points of the global plan were in the local costmap.\");\n    return false;\n  }\n\n  // find the \"last valid pose\", i.e. the last pose on the plan after the start pose that is still on the local map\n  unsigned int last_valid_index = start_index;\n  for (unsigned int i = start_index + 1; i < plan.size(); i++)\n  {\n    double g_x = plan[i].x;\n    double g_y = plan[i].y;\n    unsigned int map_x, map_y;\n    if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION)\n    {\n      // Still on the costmap. Continue.\n      last_valid_index = i;\n    }\n    else\n    {\n      // Off the costmap after being on the costmap.\n      break;\n    }\n  }\n\n  // find the \"goal pose\" by walking along the plan as long as each step leads far enough away from the starting point,\n  // i.e. is within angle_threshold_ of the starting direction.\n  unsigned int goal_index = start_index;\n\n  while (goal_index < last_valid_index)\n  {\n    goal_index = getGoalIndex(plan, start_index, last_valid_index);\n\n    // check if goal already reached\n    bool goal_already_reached = false;\n    for (auto& reached_intermediate_goal : reached_intermediate_goals_)\n    {\n      double distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[goal_index]);\n      if (distance < xy_local_goal_tolerance_)\n      {\n        goal_already_reached = true;\n        // choose a new start_index by walking along the plan until we're outside xy_local_goal_tolerance_ and try again\n        // (start_index is now > goal_index)\n        for (start_index = goal_index; start_index <= last_valid_index; ++start_index)\n        {\n          distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[start_index]);\n          if (distance >= xy_local_goal_tolerance_)\n          {\n            break;\n          }\n        }\n        break;\n      }\n    }\n    if (!goal_already_reached)\n    {\n      // new goal not in reached_intermediate_goals_\n      double distance = nav_2d_utils::poseDistance(plan[goal_index], robot_pose);\n      if (distance < xy_local_goal_tolerance_)\n      {\n        // the robot has currently reached the goal\n        reached_intermediate_goals_.push_back(plan[goal_index]);\n        ROS_DEBUG_NAMED(\"PathProgressCritic\", \"Number of reached_intermediate goals: %zu\",\n                        reached_intermediate_goals_.size());\n      }\n      else\n      {\n        // we've found a new goal!\n        break;\n      }\n    }\n  }\n  if (start_index > goal_index)\n    start_index = goal_index;\n  ROS_ASSERT(goal_index <= last_valid_index);\n\n  // save goal in x, y\n  worldToGridBounded(info, plan[goal_index].x, plan[goal_index].y, x, y);\n  desired_angle = plan[start_index].theta;\n  return true;\n}\n\nunsigned int PathProgressCritic::getGoalIndex(const std::vector<geometry_msgs::Pose2D>& plan, unsigned int start_index,\n                                              unsigned int last_valid_index) const\n{\n  if (start_index >= last_valid_index)\n    return last_valid_index;\n\n  unsigned int goal_index = start_index;\n  const double start_direction_x = plan[start_index + 1].x - plan[start_index].x;\n  const double start_direction_y = plan[start_index + 1].y - plan[start_index].y;\n  if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9)\n  {\n    // make sure that atan2 is defined\n    double start_angle = atan2(start_direction_y, start_direction_x);\n\n    for (unsigned int i = start_index + 1; i <= last_valid_index; ++i)\n    {\n      const double current_direction_x = plan[i].x - plan[i - 1].x;\n      const double current_direction_y = plan[i].y - plan[i - 1].y;\n      if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9)\n      {\n        double current_angle = atan2(current_direction_y, current_direction_x);\n\n        // goal pose is found if plan doesn't point far enough away from the starting point\n        if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) > angle_threshold_)\n          break;\n\n        goal_index = i;\n      }\n    }\n  }\n  return goal_index;\n}\n\n}  // namespace mir_dwb_critics\n\nPLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathProgressCritic, dwb_local_planner::TrajectoryCritic)\n"
  },
  {
    "path": "mir_gazebo/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_gazebo\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n* Add arg mir_type to launch files and urdfs\n* Rename mir_100 -> mir\n  This is in preparation of mir_250 support.\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n* Remove outdated comment\n* Contributors: Martin Günther\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Rename tf frame and topic 'odom_comb' -> 'odom'\n  This is how they are called on the real MiR since MiR software 2.0.\n* Contributors: Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n* Fix laser scan frame_id with gazebo_plugins 2.9.2\n* Contributors: Martin Günther\n\n1.1.1 (2021-02-11)\n------------------\n* mir_gazebo: Add model_name arg\n* Move joint_state_publisher to mir_gazebo_common.launch\n* Add optional namespace to launch files\n* Add prepend_prefix_to_laser_frame to URDF and launch files\n  Fixes `#65 <https://github.com/DFKI-NI/mir_robot/issues/65>`_.\n* Add tf_prefix to URDF and launch files\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n\n1.0.4 (2019-05-06)\n------------------\n* Fix gazebo launch file\n  Before this commit, the mobile base plugin couldn't initialize, because\n  subst_value didn't work.\n* Contributors: Martin Günther\n\n1.0.3 (2019-03-04)\n------------------\n* Add hector_mapping\n* fake_localization.launch: Add frame id args\n* Merge pull request `#16 <https://github.com/DFKI-NI/mir_robot/issues/16>`_ from niniemann/add-prefix-argument-to-configs\n  Add prefix argument to configs\n* adds $(arg prefix) to a lot of configs\n  This is an important step to be able to re-parameterize move base,\n  the diffdrive controller, ekf, amcl and the costmaps for adding a\n  tf prefix to the robots links\n* Fix translation error in odom_comb (`#12 <https://github.com/DFKI-NI/mir_robot/issues/12>`_)\n  Previously, the ekf localization only computed a correct orientation, but the translation still followed the pure odometry data. This led to strange errors where the robot would move sideways (despite only having a diff drive).\n  This PR changes the ekf configuration to not use any position information from the odometry, but to integrate the velocities, which fixes this problem.\n* Split scan_rep117 topic into two separate topics\n  This fixes the problem that the back laser scanner was ignored in the\n  navigation costmap in Gazebo (probably because in Gazebo, both laser\n  scanners have the exact same timestamp).\n* Contributors: Martin Günther, Nils Niemann\n\n1.0.2 (2018-07-30)\n------------------\n* mir_gazebo: Install config directory\n* Contributors: Martin Günther\n\n1.0.1 (2018-07-17)\n------------------\n* gazebo: Replace robot_pose_ekf with robot_localization\n  robot_pose_ekf is deprecated, and has been removed from the navigation\n  stack starting in melodic.\n* gazebo: Adjust ekf.yaml\n* gazebo: Copy robot_localization/ekf_template.yaml\n  ... for modification.\n* Contributors: Martin Günther\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_gazebo/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_gazebo)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package()\n\n#############\n## Install ##\n#############\n\n# Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(DIRECTORY\n  config\n  launch\n  maps\n  sdf\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\nroslaunch_add_file_check(launch)\n"
  },
  {
    "path": "mir_gazebo/config/ekf.yaml",
    "content": "# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin\n# computation until it receives at least one message from one of the inputs. It will then run continuously at the\n# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.\nfrequency: 40\n\n# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict\n# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the\n# filter will generate new output. Defaults to 1 / frequency if not specified.\nsensor_timeout: 0.1\n\n# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is\n# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar\n# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected\n# by, for example, an IMU. Defaults to false if unspecified.\ntwo_d_mode: true\n\n# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for\n# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if\n# unspecified.\ntransform_time_offset: 0.0\n\n# Use this parameter to specify how long the tf listener should wait for a transform to become available.\n# Defaults to 0.0 if unspecified.\ntransform_timeout: 0.0\n\n# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is\n# unhappy with any settings or data.\nprint_diagnostics: true\n\n# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by\n# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious\n# effects on the performance of the node. Defaults to false if unspecified.\ndebug: false\n\n# Defaults to \"robot_localization_debug.txt\" if unspecified. Please specify the full path.\ndebug_out_file: /path/to/debug/file.txt\n\n# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.\npublish_tf: true\n\n# Whether to publish the acceleration state. Defaults to false if unspecified.\npublish_acceleration: false\n\n# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and\n# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames.\n# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be\n# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom\n# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your\n# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based\n# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame.\n# ekf_localization_node and ukf_localization_node are not concerned with the earth frame.\n# Here is how to use the following settings:\n# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.\n#     1a. If your system does not have a map_frame, just remove it, and make sure \"world_frame\" is set to the value of\n#         odom_frame.\n# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set\n#   \"world_frame\" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.\n# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates\n# from landmark observations) then:\n#     3a. Set your \"world_frame\" to your map_frame value\n#     3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state\n#         estimation node from robot_localization! However, that instance should *not* fuse the global data.\nmap_frame: map                                   # Defaults to \"map\" if unspecified\nodom_frame: $(arg tf_prefix)odom                 # Defaults to \"odom\" if unspecified\nbase_link_frame: $(arg tf_prefix)base_footprint  # Defaults to \"base_link\" if unspecified\nworld_frame: $(arg tf_prefix)odom                # Defaults to the value of odom_frame if unspecified\n\n# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry,\n# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped,\n# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its \"base\" name, e.g., odom0,\n# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no\n# default values, and must be specified.\nodom0: odom\n\n# Each sensor reading updates some or all of the filter's state. These options give you greater control over which\n# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only\n# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the\n# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types\n# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message\n# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false\n# if unspecified, effectively making this parameter required for each sensor.\n# see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html\nodom0_config: [false, false, false,   # x y z\n               false, false, false,   # roll pitch yaw\n               true,  true,  false,   # vx vy vz\n               false, false, true,    # vroll vpitch vyaw\n               false, false, false]   # ax ay az\n\n# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase\n# the size of the subscription queue so that more measurements are fused.\nodom0_queue_size: 10\n\n# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result\n# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's\n# algorithm.\nodom0_nodelay: false\n\n# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under-\n# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they\n# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also\n# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't\n# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose\n# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then\n# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true\n# for twist measurements has no effect.\nodom0_differential: false\n\n# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a \"zero point\"\n# for all future measurements. While you can achieve the same effect with the differential paremeter, the key\n# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before\n# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.\nodom0_relative: false\n\n# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to\n# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to\n# numeric_limits<double>::max() if unspecified. It is strongly recommended that these parameters be removed if not\n# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation.\n# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying\n# the thresholds.\n#odom0_pose_rejection_threshold: 5\n#odom0_twist_rejection_threshold: 1\n\n# Further input parameter examples\n# see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html\nimu0: imu_data\nimu0_config: [false, false, false,   # x y z\n              false, false, true,    # roll pitch yaw\n              false, false, false,   # vx vy vz\n              false, false, true,    # vroll vpitch vyaw\n              true,  false, false]    # ax ay az\nimu0_nodelay: false\nimu0_differential: false\nimu0_relative: true\nimu0_queue_size: 10\n#imu0_pose_rejection_threshold: 0.8                 # Note the difference in parameter names\n#imu0_twist_rejection_threshold: 0.8                #\n#imu0_linear_acceleration_rejection_threshold: 0.8  #\n\n# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set\n# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.\nimu0_remove_gravitational_acceleration: false\n\n# [ADVANCED]  The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no\n# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During\n# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be\n# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When\n# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially\n# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance\n# for the velocity variable in question, or decrease the  variance of the variable in question in the measurement\n# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we\n# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during\n# predicition. Note that if an acceleration measurement for the variable in question is available from one of the\n# inputs, the control term will be ignored.\n# Whether or not we use the control input during predicition. Defaults to false.\nuse_control: false\n# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to\n# false.\nstamped_control: false\n# The last issued control command will be used in prediction for this period. Defaults to 0.2.\ncontrol_timeout: 0.2\n# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw.\ncontrol_config: [true, false, false, false, false, true]\n# Places limits on how large the acceleration term will be. Should match your robot's kinematics.\nacceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]\n# Acceleration and deceleration limits are not always the same for robots.\ndeceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]\n# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these\n# gains\nacceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]\n# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these\n# gains\ndeceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]\n\n# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is\n# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each\n# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.\n# However, if users find that a given variable is slow to converge, one approach is to increase the\n# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error\n# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are\n# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if\n# unspecified.\nprocess_noise_covariance: [0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]\n\n# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal\n# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in\n# question. Users should take care not to use large values for variables that will not be measured directly. The values\n# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below\n#if unspecified.\ninitial_estimate_covariance: [100.0,0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    100.0,0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    1.0,  0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1.0,   0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     10.0, 0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    10.0, 0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]\n"
  },
  {
    "path": "mir_gazebo/launch/fake_localization.launch",
    "content": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"delta_x\" default=\"0.0\" />\n  <arg name=\"delta_y\" default=\"0.0\" />\n  <arg name=\"delta_yaw\" default=\"0.0\" />\n  <arg name=\"odom_frame_id\" default=\"odom\"/>\n  <arg name=\"base_frame_id\" default=\"base_footprint\"/>\n\n  <node name=\"fake_localization\" pkg=\"fake_localization\" type=\"fake_localization\" output=\"screen\">\n    <param name=\"odom_frame_id\" value=\"$(arg odom_frame_id)\"/>\n    <param name=\"base_frame_id\" value=\"$(arg base_frame_id)\"/>\n    <param name=\"delta_x\"       value=\"$(arg delta_x)\" />\n    <param name=\"delta_y\"       value=\"$(arg delta_y)\" />\n    <param name=\"delta_yaw\"     value=\"$(arg delta_yaw)\" />\n  </node>\n</launch>\n"
  },
  {
    "path": "mir_gazebo/launch/includes/ekf.launch.xml",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"tf_prefix\" default=\"\" />\n  <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_localization_node\" clear_params=\"true\" output=\"screen\">\n    <rosparam command=\"load\" file=\"$(find mir_gazebo)/config/ekf.yaml\" subst_value=\"true\" />\n  </node>\n</launch>\n"
  },
  {
    "path": "mir_gazebo/launch/includes/spawn_maze.launch.xml",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n    <node name=\"spawn_maze\" pkg=\"gazebo_ros\" type=\"spawn_model\" args=\"-sdf\n      -file $(find mir_gazebo)/sdf/maze/model.sdf -model walls\" output=\"screen\" />\n</launch>\n"
  },
  {
    "path": "mir_gazebo/launch/mir_empty_world.launch",
    "content": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"gui\" default=\"true\" />\n  <arg name=\"world_name\" default=\"worlds/empty.world\"/> <!-- Note: the world_name is with respect to GAZEBO_RESOURCE_PATH environmental variable, but can also be an absolute path -->\n\n  <arg name=\"robot_x\"   default=\"0.0\" />\n  <arg name=\"robot_y\"   default=\"0.0\" />\n  <arg name=\"robot_yaw\" default=\"0.0\" />\n\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n\n  <arg name=\"tf_prefix\" default=\"\" doc=\"tf_prefix to be used by gazebo plugins and in the robot's urdf etc.\" />\n\n  <arg name=\"namespace\" default=\"$(arg tf_prefix)\" doc=\"Namespace to push all topics into.\"/>\n\n  <group if=\"$(eval namespace != '')\">\n    <group>\n      <remap from=\"$(arg namespace)/joint_states\"                   to=\"$(arg namespace)/mir/joint_states\" />\n      <remap from=\"$(arg namespace)/mobile_base_controller/cmd_vel\" to=\"$(arg namespace)/cmd_vel\" />\n      <remap from=\"$(arg namespace)/mobile_base_controller/odom\"    to=\"$(arg namespace)/odom\" />\n\n      <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\n        <arg name=\"world_name\" value=\"$(arg world_name)\"/>\n        <arg name=\"paused\" value=\"true\" />\n        <arg name=\"gui\" value=\"$(arg gui)\" />\n      </include>\n    </group>\n\n    <group ns=\"$(arg namespace)\">\n      <!-- spawn robot and bring up controllers etc. -->\n      <include file=\"$(find mir_gazebo)/launch/mir_gazebo_common.launch\">\n        <arg name=\"robot_x\"   value=\"$(arg robot_x)\" />\n        <arg name=\"robot_y\"   value=\"$(arg robot_y)\" />\n        <arg name=\"robot_yaw\" value=\"$(arg robot_yaw)\" />\n        <arg name=\"mir_type\"  value=\"$(arg mir_type)\" />\n        <arg name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n      </include>\n    </group>\n  </group>\n\n  <!-- Duplicate of the above in case namespace is empty. This is necessary to\n       avoid the \"<group> tag has an empty 'ns' attribute\" parsing error. -->\n  <group unless=\"$(eval namespace != '')\">\n    <group>\n      <remap from=\"joint_states\"                   to=\"mir/joint_states\" />\n      <remap from=\"mobile_base_controller/cmd_vel\" to=\"cmd_vel\" />\n      <remap from=\"mobile_base_controller/odom\"    to=\"odom\" />\n\n      <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\n        <arg name=\"world_name\" value=\"$(arg world_name)\"/>\n        <arg name=\"paused\" value=\"true\" />\n        <arg name=\"gui\" value=\"$(arg gui)\" />\n      </include>\n    </group>\n\n    <!-- spawn robot and bring up controllers etc. -->\n    <include file=\"$(find mir_gazebo)/launch/mir_gazebo_common.launch\">\n      <arg name=\"robot_x\"   value=\"$(arg robot_x)\" />\n      <arg name=\"robot_y\"   value=\"$(arg robot_y)\" />\n      <arg name=\"robot_yaw\" value=\"$(arg robot_yaw)\" />\n        <arg name=\"mir_type\"  value=\"$(arg mir_type)\" />\n      <arg name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n    </include>\n  </group>\n</launch>\n"
  },
  {
    "path": "mir_gazebo/launch/mir_gazebo_common.launch",
    "content": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"robot_x\"   default=\"0.0\" />\n  <arg name=\"robot_y\"   default=\"0.0\" />\n  <arg name=\"robot_yaw\" default=\"0.0\" />\n\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n\n  <arg name=\"tf_prefix\" default=\"\" doc=\"tf_prefix to be used by gazebo plugins and in the robot's urdf etc.\" />\n\n  <arg name=\"prefix\" value=\"$(arg tf_prefix)/\" if=\"$(eval tf_prefix != '')\" /> <!-- $(arg prefix) is used in all the config files! TODO: For multiple robots, create groups when loading the parameters to overwrite the arg? -->\n  <arg name=\"prefix\" value=\"\"                  unless=\"$(eval tf_prefix != '')\" />\n\n  <arg name=\"model_name\" default=\"mir\" doc=\"Name of the Gazebo robot model (needs to be different for each robot)\" />\n\n\n  <!-- Load URDF -->\n  <include file=\"$(find mir_description)/launch/upload_mir_urdf.launch\">\n    <arg name=\"mir_type\" value=\"$(arg mir_type)\" />\n    <arg name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n  </include>\n\n  <!-- Spawn the robot into Gazebo -->\n  <node name=\"spawn_urdf\" pkg=\"gazebo_ros\" type=\"spawn_model\" args=\"-param robot_description -urdf -model $(arg model_name)\n    -x $(arg robot_x) -y $(arg robot_y) -Y $(arg robot_yaw) \" />\n\n  <!-- Load ros_control controller configurations -->\n  <rosparam file=\"$(find mir_description)/config/joint_state_controller.yaml\" command=\"load\" />\n  <rosparam file=\"$(find mir_description)/config/diffdrive_controller.yaml\" command=\"load\" subst_value=\"true\" />\n\n  <!-- Start the controllers -->\n  <node name=\"controller_spawner\" pkg=\"controller_manager\" type=\"spawner\" output=\"screen\"\n    args=\"joint_state_controller mobile_base_controller\"/>\n\n  <!-- EKF -->\n  <include file=\"$(find mir_gazebo)/launch/includes/ekf.launch.xml\">\n      <arg name=\"tf_prefix\" value=\"$(arg prefix)\" />\n  </include>\n\n  <!-- Add passive + mimic joints to joint_states topic -->\n  <node name=\"joint_state_publisher\" pkg=\"joint_state_publisher\" type=\"joint_state_publisher\">\n    <rosparam param=\"source_list\">[mir/joint_states]</rosparam>\n    <param name=\"rate\" value=\"200.0\" />\n  </node>\n\n  <!-- Robot state publisher -->\n  <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\" output=\"screen\" />\n\n  <!-- Load teleop -->\n  <node name=\"rqt_robot_steering\" pkg=\"rqt_robot_steering\" type=\"rqt_robot_steering\">\n    <param name=\"default_topic\" value=\"cmd_vel\"/>\n    <param name=\"default_vx_max\" value=\"1.0\" />\n    <param name=\"default_vx_min\" value=\"-1.0\" />\n    <param name=\"default_vw_max\" value=\"1.5\" />\n    <param name=\"default_vw_min\" value=\"-1.5\" />\n  </node>\n\n  <!-- create combined scan topic (like on real MiR) -->\n  <node pkg=\"topic_tools\" type=\"relay\" name=\"b_scan_relay\" args=\"b_scan scan\"/>\n  <node pkg=\"topic_tools\" type=\"relay\" name=\"f_scan_relay\" args=\"f_scan scan\"/>\n\n  <node name=\"b_rep117_laser_filter\" pkg=\"mir_driver\" type=\"rep117_filter.py\" output=\"screen\">\n    <remap from=\"scan\" to=\"b_scan\" />\n    <remap from=\"scan_filtered\" to=\"b_scan_rep117\" />\n  </node>\n\n  <node name=\"f_rep117_laser_filter\" pkg=\"mir_driver\" type=\"rep117_filter.py\" output=\"screen\">\n    <remap from=\"scan\" to=\"f_scan\" />\n    <remap from=\"scan_filtered\" to=\"f_scan_rep117\" />\n  </node>\n</launch>\n"
  },
  {
    "path": "mir_gazebo/launch/mir_maze_world.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"gui\" default=\"true\" />\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n  <arg name=\"tf_prefix\" default=\"\" doc=\"tf_prefix to be used by gazebo plugins and in the robot's urdf etc.\" />\n\n  <include file=\"$(find mir_gazebo)/launch/mir_empty_world.launch\">\n    <arg name=\"gui\" value=\"$(arg gui)\" />\n    <arg name=\"mir_type\" value=\"$(arg mir_type)\" />\n    <arg name=\"tf_prefix\" value=\"$(arg tf_prefix)\" />\n  </include>\n\n  <include file=\"$(find mir_gazebo)/launch/includes/spawn_maze.launch.xml\" />\n</launch>\n"
  },
  {
    "path": "mir_gazebo/maps/maze.yaml",
    "content": "image: maze.png\nresolution: 0.05\norigin: [0.0, 0.0, 0.0]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n"
  },
  {
    "path": "mir_gazebo/maps/maze_virtual_walls.yaml",
    "content": "image: maze_virtual_walls.png\nresolution: 0.05\norigin: [0.0, 0.0, 0.0]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n"
  },
  {
    "path": "mir_gazebo/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_gazebo</name>\n  <version>1.1.8</version>\n  <description>Simulation specific launch and configuration files for the MiR robot.</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roslaunch</build_depend>\n\n  <exec_depend>controller_manager</exec_depend>\n  <exec_depend>fake_localization</exec_depend>\n  <exec_depend>gazebo_ros</exec_depend>\n  <exec_depend>joint_state_publisher</exec_depend>\n  <exec_depend>mir_description</exec_depend>\n  <exec_depend>mir_driver</exec_depend>\n  <exec_depend>robot_localization</exec_depend>\n  <exec_depend>robot_state_publisher</exec_depend>\n  <exec_depend>rostopic</exec_depend>\n  <exec_depend>rqt_robot_steering</exec_depend>\n  <exec_depend>topic_tools</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_gazebo/sdf/maze/model.config",
    "content": "<?xml version=\"1.0\" ?>\n<model>\n    <name>maze</name>\n    <version>1.0</version>\n    <sdf version=\"1.6\">model.sdf</sdf>\n    <author>\n        <name>Martin Günther</name>\n        <email>martin.guenther@dfki.de</email>\n    </author>\n    <description></description>\n</model>\n"
  },
  {
    "path": "mir_gazebo/sdf/maze/model.sdf",
    "content": "<?xml version='1.0'?>\n<sdf version='1.6'>\n  <model name='maze'>\n    <pose frame=''>-0.078283 0.098984 0 0 -0 0</pose>\n    <link name='Wall_0'>\n      <collision name='Wall_0_Collision'>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_0_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>0.030536 9.925 0 0 -0 0</pose>\n    </link>\n    <link name='Wall_1'>\n      <collision name='Wall_1_Collision'>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_1_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>9.95554 0 0 0 0 -1.5708</pose>\n    </link>\n    <link name='Wall_2'>\n      <collision name='Wall_2_Collision'>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_2_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>0.030536 -9.925 0 0 -0 3.14159</pose>\n    </link>\n    <link name='Wall_24'>\n      <collision name='Wall_24_Collision'>\n        <geometry>\n          <box>\n            <size>1.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_24_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>1.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>5.35089 3.21906 0 0 -0 3.14159</pose>\n    </link>\n    <link name='Wall_25'>\n      <collision name='Wall_25_Collision'>\n        <geometry>\n          <box>\n            <size>5.25 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_25_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>5.25 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>4.67589 5.76906 0 0 -0 1.5708</pose>\n    </link>\n    <link name='Wall_27'>\n      <collision name='Wall_27_Collision'>\n        <geometry>\n          <box>\n            <size>5.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_27_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>5.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>7.10914 4.73454 0 0 0 -1.5708</pose>\n    </link>\n    <link name='Wall_28'>\n      <collision name='Wall_28_Collision'>\n        <geometry>\n          <box>\n            <size>3 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_28_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>3 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>8.53414 2.05954 0 0 -0 0</pose>\n    </link>\n    <link name='Wall_3'>\n      <collision name='Wall_3_Collision'>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_3_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>20 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>-9.89446 0 0 0 -0 1.5708</pose>\n    </link>\n    <link name='Wall_30'>\n      <collision name='Wall_30_Collision'>\n        <geometry>\n          <box>\n            <size>5.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_30_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>5.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>-4.35914 -2.82889 0 0 0 -1.5708</pose>\n    </link>\n    <link name='Wall_31'>\n      <collision name='Wall_31_Collision'>\n        <geometry>\n          <box>\n            <size>5.75 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_31_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>5.75 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>-7.15914 -5.50389 0 0 -0 3.14159</pose>\n    </link>\n    <link name='Wall_5'>\n      <collision name='Wall_5_Collision'>\n        <geometry>\n          <box>\n            <size>16 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_5_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>16 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>-1.89911 1.86906 0 0 -0 0</pose>\n    </link>\n    <link name='Wall_6'>\n      <collision name='Wall_6_Collision'>\n        <geometry>\n          <box>\n            <size>1.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_6_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>1.5 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>6.02589 2.54406 0 0 -0 1.5708</pose>\n    </link>\n    <link name='Wall_8'>\n      <collision name='Wall_8_Collision'>\n        <geometry>\n          <box>\n            <size>0.15 0.15 2.5</size>\n          </box>\n        </geometry>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n      </collision>\n      <visual name='Wall_8_Visual'>\n        <pose frame=''>0 0 1.25 0 -0 0</pose>\n        <geometry>\n          <box>\n            <size>0.15 0.15 2.5</size>\n          </box>\n        </geometry>\n        <material>\n          <script>\n            <uri>file://media/materials/scripts/gazebo.material</uri>\n            <name>Gazebo/Grey</name>\n          </script>\n          <ambient>1 1 1 1</ambient>\n        </material>\n      </visual>\n      <pose frame=''>6.02589 3.21906 0 0 -0 0</pose>\n    </link>\n    <static>1</static>\n  </model>\n</sdf>\n"
  },
  {
    "path": "mir_msgs/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_msgs\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Build new msgs (`#117 <https://github.com/DFKI-NI/mir_robot/issues/117>`_)\n  Need to build new msg files. The files were added in a previous commit, but not added here for build and installation.\n* Update MirMoveBase action to 2.10.3.1\n* Update BMSData.msg to MiR software 2.13.2\n  This is an \"unsafe\" change (it breaks compatibility with MiR versions <=\n  2.13.2), but since BMSData is not published by the mir_driver currently,\n  it should be ok.\n* Add new messages added in MiR software 2.13.4.1\n  This does not break compatibility with earlier versions (like 2.8.3.1),\n  because these messages did not exist before.\n  Actually, these messages were added in 2.10.3.1 (all other messages) and\n  2.13.0.4 (ServiceResponseHeader.msg).\n* Update Brake, Gripper + Height State msg to 2.13.4.1\n  These are \"unsafe\" message changes (fields have been removed), but it\n  should be ok because these are only used in HookExtendedStatus, and that\n  message isn't forwarded by the mir_driver.\n* Partially update messages to MiR software 2.13.4.1\n  This only contains the \"safe\" changes, where fields were added. Also, it\n  doesn't include the move of some messages to mir_hook_shared_interface,\n  but keeps them here.\n* Don't set cmake_policy CMP0048\n* Contributors: Martin Günther, moooeeeep\n\n1.1.6 (2022-06-02)\n------------------\n* Rename mir_100 -> mir\n  This is in preparation of mir_250 support.\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n* mir_msgs: Build all messages (`#98 <https://github.com/DFKI-NI/mir_robot/issues/98>`_)\n* Contributors: Martin Günther\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Update BMSData msg to MiR software 2.8.3.1\n* Remove MirStatus\n  This message was removed in MiR software 2.0 (Renamed to RobotStatus).\n* Update mir_msgs to 2.8.2.2\n* Contributors: Felix, Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Fix some catkin_lint warnings\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n\n1.0.4 (2019-05-06)\n------------------\n* Update mir_msgs and mir_actions to MiR 2.3.1\n  The following changes were made to the actual mir_msgs:\n  * rename mirMsgs -> mir_msgs\n  * rename proximity -> Proximity\n  * rename serial -> Serial\n  * keep MirStatus msg (was replaced by RobotStatus in MiR software 2.0)\n* Contributors: Martin Günther\n\n1.0.3 (2019-03-04)\n------------------\n* mir_msgs: Compile new msgs + rename mirMsgs -> mir_msgs\n* mir_msgs: Add geometry_msgs dependency\n  Now that we have an actual msg package dependency, we don't need the std_msgs placeholder any more.\n* mir_msgs: Add new messages on kinetic\n* Contributors: Martin Günther\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_msgs/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_msgs)\n\nfind_package(catkin REQUIRED COMPONENTS\n  geometry_msgs\n  message_generation\n)\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n# Generate messages in the 'msg' folder\nadd_message_files(\n  FILES\n    AngleMeasurment.msg\n    BMSData.msg\n    BatteryCurrents.msg\n    BrakeState.msg\n    ChargingState.msg\n    Device.msg\n    Devices.msg\n    EncoderTestEntry.msg\n    Encoders.msg\n    Error.msg\n    Event.msg\n    Events.msg\n    ExternalRobot.msg\n    ExternalRobots.msg\n    Gpio.msg\n    GripperState.msg\n    HeightState.msg\n    HookData.msg\n    HookExtendedStatus.msg\n    HookStatus.msg\n    IOs.msg\n    JoystickVel.msg\n    LocalMapStat.msg\n    MirExtra.msg\n    MirLocalPlannerPathTypes.msg\n    MissionCtrlCommand.msg\n    MissionCtrlState.msg\n    MovingState.msg\n    PalletLifterStatus.msg\n    Path.msg\n    Pendant.msg\n    PlanSegment.msg\n    PlanSegments.msg\n    Pose2D.msg\n    PowerBoardMotorStatus.msg\n    PrecisionDockingStatus.msg\n    Proximity.msg\n    ResourceState.msg\n    ResourcesAcquisition.msg\n    ResourcesState.msg\n    RobotMode.msg\n    RobotState.msg\n    RobotStatus.msg\n    SafetyStatus.msg\n    Serial.msg\n    ServiceResponseHeader.msg\n    SkidDetectionDiff.msg\n    SkidDetectionStampedFloat.msg\n    SoundEvent.msg\n    StampedEncoders.msg\n    TimeDebug.msg\n    Trolley.msg\n    Twist2D.msg\n    UserPrompt.msg\n    WebPath.msg\n    WorldMap.msg\n    WorldModel.msg\n)\n\n# Generate added messages and services with any dependencies listed here\ngenerate_messages(\n  DEPENDENCIES\n    geometry_msgs\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package(\n  CATKIN_DEPENDS\n    geometry_msgs\n    message_runtime\n)\n"
  },
  {
    "path": "mir_msgs/msg/AngleMeasurment.msg",
    "content": "float64 angle #radians\ntime timestamp\n"
  },
  {
    "path": "mir_msgs/msg/BMSData.msg",
    "content": "float64 pack_voltage\nfloat64 charge_current\nfloat64 discharge_current\nfloat64 state_of_charge\nfloat64 remaining_time_to_full_charge\nint32 remaining_capacity\nint32 state_of_health\nint32 DISCHARGING=1 #bit 0\nint32 CHARGING=2    #bit 1\nint32 OV=4         #bit 2 Over voltage\nint32 UV=8          #bit 3 Under voltage\nint32 COC=16         #bit 4 Charge over current\nint32 DOC=32         #bit 5 Discharge over current\nint32 DOT=64         #bit 6 Discharge over temperature\nint32 DUT=128         #bit 7 Discharge under temperature\nint32  SC=512         #bit 9\nint32 COT=1024         #bit 10 Charge over temperature\nint32 CUT=2048         #bit 11 Charge under temperature\nint32 FW_STATUS_MSK=2031616 # to get Battery_Firmware_Status  do the following:\nint32 FW_STATUS_SHIFT=16    # batt_fw_stat=(status_flags & FW_STATUS_MSK)>>FW_STATUS_SHIFT\nint32 FW_UPD_OK=0                  #Battery firmware update finished OK.\nint32 FW_UPD_RUNNING=1             #Battery firmware update running.\nint32 FW_UPD_FAILED_BOOT=2         #Battery firmware update failed in Bootloader (Robot must not drive)\nint32 FW_UPD_FAILED_APP=3          #Battery firmware update failed updating the application (Robot can drive with old FW)\nint32 FW_UPD_FAILED_PARAM=4        #Battery firmware update failed uploading parameters (Robot can drive with old fw and parameters.)\nint32 FW_STATUS_LOW_BATT=5         #Battery firmware update skipped battery too low or high (Robot can drive with old parameters.)\nint32 FW_STATUS_FILE_CORRUPTED=6   #Battery firmware file corrupted (Robot can drive with old parameters.)\nint32 FW_STATUS_CURRENT_TO_HIGH=7  #Battery firmware file corrupted (Robot can drive with old parameters.)\nint32 FW_STATUS_NO_CAN=8           #Battery firmware update skipped no CAN communication (Robot can drive with old fw and parameters.)\nint32 FW_BATTERY_IMBALANCE_HIGH=9  #Battery firmware update is enforced and the battery will be shut off by the new firmware\nint32 status_flags\nint32 temperature\nuint32[] cell_voltage # In Mk2 robots and above the BMS provides data for 8 battery cells. 2Gen robots have BMS for 13 battery cells\nuint32 cell_voltage_diff\n\nstring WST_serial\n\n# Exteded diagnosticts for BMZ battery\nuint32 bmz_flag # Flag for enabling extended diagnosticts\nuint32 battery_type\nuint32 BATT_TYPE_UNKNOWN=0      #type is unknown / no communucation\nuint32 BATT_TYPE_BMZ=1          #BMZ battery\nuint32 BATT_TYPE_WST=2          #WST battery\nuint32 BATT_TYPE_SBS=3          #SBS battery\nuint32 BATT_TYPE_SBS_SLIDE=4    #SBS SLIDE battery\nuint32 BATT_TYPE_NO_BMS=255       #WST No BMS battery\nfloat64 full_voltage\nint32 full_capacity\nint32 temperature2\nint32 temperature_pcb\nint32 cycle_count\nint32 dsg_overcurrent_counter\nint32 chg_overcurrent_counter\nint32 hw_major\nint32 hw_minor\nint32 fw_major\nint32 fw_minor\nint32 fw_patch\nint32 fw_parameters_ok\nint32 rec_fw_major\nint32 rec_fw_minor\nint32 rec_fw_patch\nint32 bl_major\nint32 bl_minor\nuint32 status_enabled\nuint32 status_current_limitation\nuint32 status_switch_off_warn1\nuint32 status_switch_off_warn2\nuint32 status_fully_discharged\nuint32 status_nearly_discharged\nuint32 status_chargefet_on\nuint32 status_dischargefet_on\nuint32 status_discharging\nuint32 status_fully_charged\nuint32 status_charging\nuint32 status_temp_charging_err\nuint32 status_cell_over_voltage\nuint32 status_cell_under_voltage\nuint32 status_charge_over_current\nuint32 status_shortcircuit\nuint32 status_discharge_over_current\nfloat64 status_chargefet_voltage\nfloat64 status_dischargefet_voltage\nuint32 status_temp_discharging_err\nuint32 status_charger_detected\nuint32 mnfct_bms_revision\nuint32 mnfct_asn_revision\nuint32 mnfct_year\nuint32 mnfct_week\nuint32 mnfct_model\nuint32 mnfct_serial\nuint32 afe_i2c_error_count\nuint32 app_error_count\nuint32 fet_disable_state\n\nfloat64 last_battery_msg_time\n\n# SBS battery states\nuint32 SBS_battery_status\nuint32 SBS_battery_status_raw\nuint32 SBS_InitState1=1\nuint32 SBS_InitState2=2\nuint32 SBS_InitState3=3\nuint32 SBS_InitState4=4\nuint32 SBS_Idle=5\nuint32 SBS_Discharge=6\nuint32 SBS_Charge=7\nuint32 SBS_Fault=10\nuint32 SBS_CriticalError=11\nuint32 SBS_PrepareDeepsleep=99\nuint32 SBS_Deepsleep=100\n\nstring SBS_serial_1\nstring SBS_serial_2\n\nuint32 SBS_arti_nr_1\nuint32 SBS_arti_nr_2\nuint32 SBS_arti_nr_3\n\nuint32 SBS_curr_flow_passive_state\n\n# Overcurrent counters\nuint8 CHG_OC1_Count\nuint8 CHG_OC2_Count\nuint8 DSG_OC1_Count\nuint8 DSG_OC2_Count\nuint8 DSG_OC3_Count\nuint8 AFE_OC1_Count\nuint8 AFE_OC2_Count\nuint8 CHG_LatchClear_Count\nuint8 DSG_LatchClear_Count\n\nuint8 chg_oc_warning\nuint8 dsg_oc_warning\n"
  },
  {
    "path": "mir_msgs/msg/BatteryCurrents.msg",
    "content": "float64 battery1_current\nfloat64 battery2_current\n"
  },
  {
    "path": "mir_msgs/msg/BrakeState.msg",
    "content": "uint8 UNKNOWN = 0\nuint8 INITIALIZING = 1\nuint8 HOMING = 2\nuint8 ACTIVE = 3\nuint8 INACTIVE = 4\nuint8 ACTIVATING = 5\nuint8 DEACTIVATING = 6\nuint8 ERROR = 7\n\nuint8 state\n"
  },
  {
    "path": "mir_msgs/msg/ChargingState.msg",
    "content": "bool charging_relay\nfloat64 charging_current\nuint32 charging_current_raw\nfloat64 last_time_current\n\nfloat64 charging_voltage\nuint32 charging_voltage_raw\nbool is_voltage_low\nfloat64 last_time_voltage\n"
  },
  {
    "path": "mir_msgs/msg/Device.msg",
    "content": "string name\nstring serial\n"
  },
  {
    "path": "mir_msgs/msg/Devices.msg",
    "content": "mir_msgs/Device[] devices\n"
  },
  {
    "path": "mir_msgs/msg/EncoderTestEntry.msg",
    "content": "float64 command_velocity\nfloat64 command_distance\nfloat64 left_dist\nfloat64 right_dist\nstring suggested_direction\nstring user_direction\n"
  },
  {
    "path": "mir_msgs/msg/Encoders.msg",
    "content": "float32 time_delta # Time since last encoder update.\nint32 left_wheel  # Encoder counts (absolute or relative)\nint32 right_wheel # Encoder counts (absolute or relative)\n"
  },
  {
    "path": "mir_msgs/msg/Error.msg",
    "content": "# Definition of offsets indicating what type an error is\nint32 HARDWARE_ERROR = 0\nint32 CPU_LOAD_ERROR = 100\nint32 MEMORY_ERROR = 200\nint32 ETHERNET_ERROR = 300\nint32 HDD_ERROR = 400\nint32 BATTERY_ERROR = 500\nint32 IMU_ERROR = 600\nint32 MOTOR_ERROR = 700\nint32 LASER_ERROR = 800\nint32 CAMERA_ERROR = 900\nint32 SAFETY_SYSTEM_ERROR = 1000\nint32 POWERBOARD_ERROR = 2000\nint32 POWERSUPPLY_ERROR = 2100\nint32 CANBUS_ERROR = 2200\nint32 HOOK_ERROR = 5000\nint32 HOOK_CAMERA_ERROR = 5100\nint32 HOOK_ACTUATOR_ERROR = 5200\nint32 HOOK_BRAKE_ERROR = 5300\nint32 HOOK_ENCODER_ERROR = 5400\nint32 MISSING_ERROR = 9000\nint32 SOFTWARE_ERROR = 10000\nint32 MISSION_ERROR = 10100\nint32 LOCALIZATION_ERROR = 10200\nint32 MAPPING_ERROR = 10300\nint32 ODOM_FUSION_ERROR = 10400\nint32 EVACUATION_ERROR = 12000\n\n\ntime timestamp\t\t# Timestamp for when the error occurred\nint32 code \t\t\t# Error code\nstring description \t# Error description\nstring module\t\t# Module in which the error occurred\nbool nolog          # Do not trigger an error log if set to true\n"
  },
  {
    "path": "mir_msgs/msg/Event.msg",
    "content": "uint32 EV_SPEED=1\nuint32 EV_BLINK=2\nuint32 EV_SOUND=3\nuint32 EV_DOOR=4\nuint32 EV_AMCLOFF=5\nuint32 EV_FWDDIST=6\nuint32 EV_IO=7\nuint32 EV_FLEETLCK=8\t# Fleet\nuint32 EV_EMERGENCY=9\t# Fleet\nuint32 eventType\t# The area event type\nstring area_guid\t# The area unique identifier\nstring area_name\t# The name of the area\ngeometry_msgs/Point[] polygon # An array of corner points that define the edges of the area\n"
  },
  {
    "path": "mir_msgs/msg/Events.msg",
    "content": "Header header\nEvent[] events\n"
  },
  {
    "path": "mir_msgs/msg/ExternalRobot.msg",
    "content": "Header header\nuint32 id\nuint32 MIR100=1\nuint32 MIR500=3\nuint32 type_id\nstring name\nfloat64 robot_length\nfloat64 robot_width\nstring footprint\nstring ip\nuint32 map_id\nint32 priority\ngeometry_msgs/Pose pose\ngeometry_msgs/Pose extrapolated_pose\ngeometry_msgs/Twist twist\n"
  },
  {
    "path": "mir_msgs/msg/ExternalRobots.msg",
    "content": "Header header\nmir_msgs/ExternalRobot[] robots\n"
  },
  {
    "path": "mir_msgs/msg/Gpio.msg",
    "content": "uint8 POWERBOARD_GPIO = 0\nuint8 POWERBOARD_RESET_SWITCH_LED = 1\nuint8 PENDANT_INPUT = 5\nuint8 AUTO_MODE_SWITCH = 10\nuint8 MANUAL_MODE_SWITCH = 11\nuint8 STOP_BUTTON = 12\n\nuint8 ioport\nuint8 dat\n"
  },
  {
    "path": "mir_msgs/msg/GripperState.msg",
    "content": "uint8 LOCK_UNKNOWN = 0\nuint8 LOCK_HOMING = 1\nuint8 LOCK_OPEN = 2\nuint8 LOCK_OPENING = 3\nuint8 LOCK_CLOSED = 4\nuint8 LOCK_CLOSING = 6\nuint8 LOCK_ERROR = 9\n\nuint8 state\n"
  },
  {
    "path": "mir_msgs/msg/HeightState.msg",
    "content": "uint8 HEIGHT_UNKNOWN = 0\nuint8 HEIGHT_HOMING = 1\nuint8 HEIGHT_IDLE = 2\nuint8 HEIGHT_CHANGING = 3\nuint8 HEIGHT_ERROR = 4\n\nuint8 state\n"
  },
  {
    "path": "mir_msgs/msg/HookData.msg",
    "content": "AngleMeasurment angle\nfloat64 height\nfloat64 length\nuint8 brake_state\nuint8 gripper_state\nuint8 height_state\n"
  },
  {
    "path": "mir_msgs/msg/HookExtendedStatus.msg",
    "content": "bool available\n\nBrakeState brake\n\nGripperState gripper\n\nHeightState height\n\nfloat32 angle\n\nstring qr_marker_name\n"
  },
  {
    "path": "mir_msgs/msg/HookStatus.msg",
    "content": "bool available\nfloat32 length\nfloat32 height\nfloat32 angle\nbool braked\n\nbool trolley_attached\nTrolley trolley\n"
  },
  {
    "path": "mir_msgs/msg/IOs.msg",
    "content": "string module_guid\nbool connected\nuint8 DONE=0\nuint8 STARTED=1\nuint8 ERROR=3\nuint8 status\nint8 num_inputs\nbool[] input_state\nint8 num_outputs\nbool[] output_state\nstring ip\nstring error\n"
  },
  {
    "path": "mir_msgs/msg/JoystickVel.msg",
    "content": "string joystick_token\ngeometry_msgs/Twist speed_command\n"
  },
  {
    "path": "mir_msgs/msg/LocalMapStat.msg",
    "content": "int32  idx\nint32  x\nint32  y\n"
  },
  {
    "path": "mir_msgs/msg/MirExtra.msg",
    "content": "# MirExtra - to publish data on a topic\nHeader header\nfloat32 time_delta # Time since last encoder update.\nfloat32 r_rpm  # rmp speed from right encoder\nfloat32 l_rpm  # rmp speed from left encoder\nfloat32 vel # calc velocity\nfloat32 ang # calculated angle speed\n"
  },
  {
    "path": "mir_msgs/msg/MirLocalPlannerPathTypes.msg",
    "content": "uint8 REVERSE_TROLLEY_STANDARD=1\nuint8 REVERSE_TROLLEY_FAST=2\nuint8 REVERSE_TROLLEY_COMPACT=3\n\n\nuint8 path_type\n"
  },
  {
    "path": "mir_msgs/msg/MissionCtrlCommand.msg",
    "content": "uint8 CMD_GET_STATUS = 0\nuint8 CMD_WAIT_POS_LOCK = 1\nuint8 CMD_WAIT_AREA_LOCK = 2\nuint8 CMD_CONTINUE = 3\nuint8 CMD_LOAD_MISSION = 4\n\nstring description\nint32 cmd\nint32 mission_id\n"
  },
  {
    "path": "mir_msgs/msg/MissionCtrlState.msg",
    "content": "uint8 STATE_IDLE = 0\nuint8 STATE_WAIT_POS_LOCK = 1\nuint8 STATE_WAIT_AREA_LOCK = 2\nuint8 STATE_WAIT_MAP_TRANSITION = 10\nuint8 STATE_WAIT_LIFT_START_FLOOR = 11\nuint8 STATE_WAIT_LIFT_END_FLOOR = 12\nuint8 STATE_WAIT_LIFT_END_FLOOR_CONTINUE = 13\n\n\nint32 state\nint32 pos_id\n"
  },
  {
    "path": "mir_msgs/msg/MovingState.msg",
    "content": "uint8 UNKNOWN=0\nuint8 MOVING=1\nuint8 STOPPED=2\nuint8 STANDING_STILL=3\n\nuint8 moving_state\t# Current robot moving state\n"
  },
  {
    "path": "mir_msgs/msg/PalletLifterStatus.msg",
    "content": "uint8 PALLET_LIFT_STATE_DISABLED = 0\nuint8 PALLET_LIFT_STATE_MOVING = 1\nuint8 PALLET_LIFT_STATE_DOWN = 2\nuint8 PALLET_LIFT_STATE_UP = 3\n\nbool is_enabled\nuint8 state\n"
  },
  {
    "path": "mir_msgs/msg/Path.msg",
    "content": "Header header\nmir_msgs/Pose2D[] poses\n"
  },
  {
    "path": "mir_msgs/msg/Pendant.msg",
    "content": "float32   x\nfloat32   y\nuint8     gpio_bits\n"
  },
  {
    "path": "mir_msgs/msg/PlanSegment.msg",
    "content": "bool forward_motion\nint32 start_idx\nfloat64 length\nfloat64 remaining_length\ngeometry_msgs/PoseStamped[] path\n"
  },
  {
    "path": "mir_msgs/msg/PlanSegments.msg",
    "content": "mir_msgs/PlanSegment[] p_segments\n"
  },
  {
    "path": "mir_msgs/msg/Pose2D.msg",
    "content": "float32 x\nfloat32 y\nfloat32 orientation\n"
  },
  {
    "path": "mir_msgs/msg/PowerBoardMotorStatus.msg",
    "content": "uint16 LeftMotor_CtrlWord\nint32 LeftMotor_Speed\nint32 LeftMotor_Encoder\nuint16 LeftMotor_Status\nuint8 LeftMotor_Error\nuint32 LeftMotor_ErrorHist1\nuint32 LeftMotor_ErrorHist2\nint32 LeftMotor_Current\nuint16 LeftMotor_I2t_Motor\nuint16 LeftMotor_I2t_Controller\nint16 LeftMotor_Temperature\nuint16 RightMotor_CtrlWord\nint32 RightMotor_Speed\nint32 RightMotor_Encoder\nuint16 RightMotor_Status\nuint8 RightMotor_Error\nuint32 RightMotor_ErrorHist1\nuint32 RightMotor_ErrorHist2\nint32 RightMotor_Current\nuint16 RightMotor_I2t_Motor\nuint16 RightMotor_I2t_Controller\nint16 RightMotor_Temperature\n#Status bits for brake feedback.\nuint8 BRAKE_STATUS_BRAKED_BIT=1\t\t# is \"1\" if brake is supposed to be braked\nuint8 BRAKE_STATUS_FB_BIT=4\t\t\t# is \"1\" if brake feedback sensor is activated (brake is released)\nuint8 BRAKE_STATUS_TRANSITION_BIT=128\n# So error combinations are - (Any combination with the TRANSITION bit set are valid)\n#  BRAKED\tFB\tTRANSITION\tSTATUSWORD\n#\t0\t\t0\t0\t\t\t0x00\t\t\tBrake is suppused to be released, but FB indicate braked. We are not in transition.\n#\t1\t\t1\t0\t\t\t0x05\t\t\tBrake is suppused to be braked, but FB indicate released. We are not in transition.\nuint8 Brake_LeftStatus\nuint8 Brake_RightStatus\n"
  },
  {
    "path": "mir_msgs/msg/PrecisionDockingStatus.msg",
    "content": "bool connected\nbool motor_forward\nbool motor_back\nbool left_docking\nbool right_docking\n"
  },
  {
    "path": "mir_msgs/msg/Proximity.msg",
    "content": "Header header\nuint16[] ranges\n"
  },
  {
    "path": "mir_msgs/msg/ResourceState.msg",
    "content": "string[] assigned # A list of IPs of all assigned robots (Areas can have more than one robot assigned at a time)\nuint32 ROBOT_POSITION=0\nuint32 STAGING_POSITION=1\nuint32 CHARGING_STATION=2\nuint32 AREA=3\nuint32 ELEVATOR_ENTRY_POSITION=26\nuint32 ELEVATOR_POSITION=25\nuint32 type # The resource type\nuint32 path_idx # The index from the global path in which the robot gets into the position\nfloat32 distance # The distance from the robot to the resource\ngeometry_msgs/Point collision_point # The collision point with the resource\ngeometry_msgs/Point[] resource_geometry # The resource_geometry\nstring[] queue # The queue for a resource. It's a list of robots ips.\nstring name # The name of the resource\nstring guid # The guid of the resource\n"
  },
  {
    "path": "mir_msgs/msg/ResourcesAcquisition.msg",
    "content": "Header header\ngeometry_msgs/PoseStamped[] path\nstring position_guid\nstring token\n"
  },
  {
    "path": "mir_msgs/msg/ResourcesState.msg",
    "content": "Header header\nResourceState[] resources\nstring token\n"
  },
  {
    "path": "mir_msgs/msg/RobotMode.msg",
    "content": "# The robot operates in different mode\nuint8 ROBOT_MODE_NONE = 0\t\t# start mode\nuint8 ROBOT_MODE_MAPPING = 3\t\t# in mapping a new map is made\nuint8 ROBOT_MODE_MAPPING_FINALIZING = 4\t\t# in mapping the recorded map is being finalised\nuint8 ROBOT_MODE_MISSION = 7\t\t# primary mode when executing a mission (action list)\nuint8 ROBOT_MODE_CHANGING = 255\t\t# a transition mode - to say that a transition is in progress\n\nuint8 robotMode\nstring robotModeString\n"
  },
  {
    "path": "mir_msgs/msg/RobotState.msg",
    "content": "# The robot has to be in a predefined state\nuint8 ROBOT_STATE_NONE = 0\nuint8 ROBOT_STATE_STARTING = 1\nuint8 ROBOT_STATE_SHUTTINGDOWN = 2\nuint8 ROBOT_STATE_READY = 3\t\t# ready to execute\nuint8 ROBOT_STATE_PAUSE = 4\t\t# pause from executing\nuint8 ROBOT_STATE_EXECUTING = 5\t\t# when running in mission/taxa/bus\nuint8 ROBOT_STATE_ABORTED = 6\nuint8 ROBOT_STATE_COMPLETED = 7\t\t# done executing\nuint8 ROBOT_STATE_DOCKED = 8\t\t# in the dock and charging the batteries\nuint8 ROBOT_STATE_DOCKING = 9\nuint8 ROBOT_STATE_EMERGENCYSTOP = 10\t# the robot has emg-stop activated\nuint8 ROBOT_STATE_MANUALCONTROL = 11\t# a pause state, where the robot can move\nuint8 ROBOT_STATE_ERROR = 12\t\t# a general error state, requires a error handle\n\nuint8 robotState\nstring robotStateString\n"
  },
  {
    "path": "mir_msgs/msg/RobotStatus.msg",
    "content": "Header header\nfloat32 battery_percentage\nint32 battery_time_remaining\nfloat32 battery_voltage\nfloat32 distance_to_next_target\nError[] errors\nstring footprint\nHookStatus hook_status\nHookData hook_data\nstring map_id\nbool unloaded_map_changes\nint32 mission_queue_id\nstring mission_text\nint32 mode_id\nstring mode_text\nfloat64 moved\nPose2D position\nstring robot_name\nstring session_id\nstring software_version\nuint8 state_id\nstring state_text\nint32 uptime\nTwist2D velocity\nmir_msgs/UserPrompt user_prompt\nbool safety_system_muted\nbool joystick_low_speed_mode_enabled\nstring joystick_web_session_id\nstring mode_key_state\n"
  },
  {
    "path": "mir_msgs/msg/SafetyStatus.msg",
    "content": "bool is_connected\n\nbool is_firmware_ok\nint32 firmware_version\n\nbool in_protective_stop\nbool in_emergency_stop\nbool sto_feedback\nbool is_restart_required\n\nbool is_safety_muted\nfloat64 max_lin_speed\nfloat64 max_rot_speed\n\n# Defines for filling out the mute_mask\nuint8 MUTE_FRONT_RIGHT  = 1\nuint8 MUTE_FRONT_CENTER = 2\nuint8 MUTE_FRONT_LEFT   = 4\nuint8 MUTE_LEFT_CENTER  = 8\nuint8 MUTE_REAR_LEFT    = 16\nuint8 MUTE_REAR_CENTER  = 32\nuint8 MUTE_REAR_RIGHT   = 64\nuint8 MUTE_RIGHT_CENTER = 128\n\nuint8 MUTE_FRONT        = 7\nuint8 MUTE_LEFT         = 28\nuint8 MUTE_REAR         = 112\nuint8 MUTE_RIGHT        = 193\nuint8 MUTE_SIDES        = 221\nuint8 MUTE_ALL          = 255\n\nuint8 mute_mask\nuint8 partial_mute_mask\n\nbool is_limited_speed_active\nbool is_lifter_down\nbool in_sleep_mode\n\nbool in_manual_mode\nbool is_manual_mode_restart_required\n"
  },
  {
    "path": "mir_msgs/msg/Serial.msg",
    "content": "Header header\nstring data\n"
  },
  {
    "path": "mir_msgs/msg/ServiceResponseHeader.msg",
    "content": "bool success\nstring error\n"
  },
  {
    "path": "mir_msgs/msg/SkidDetectionDiff.msg",
    "content": "time time_stamp\nfloat64 enc_acc_x\nfloat64 enc_acc_y\nfloat64 enc_rot_th\n\n\nfloat64 imu_acc_x\nfloat64 imu_acc_y\nfloat64 imu_rot_th\n\n\nfloat64 diff_acc_x\nfloat64 diff_acc_y\nfloat64 diff_rot_th\n"
  },
  {
    "path": "mir_msgs/msg/SkidDetectionStampedFloat.msg",
    "content": "time time_stamp\nfloat64 value\n"
  },
  {
    "path": "mir_msgs/msg/SoundEvent.msg",
    "content": "time time_stamp\nstring sound_guid\nstring message\n\nuint8 START=0\nuint8 STOP =1\nuint8 MUTE=2\nuint8 UNMUTE=3\nuint8 PAUSE=4\nuint8 UNPAUSE=5\nuint8 FINISH=6\nuint8 MUTEABLE=7\nuint8 REQ_PLAY=10\n\n\nuint8 event\n"
  },
  {
    "path": "mir_msgs/msg/StampedEncoders.msg",
    "content": "Header header\nEncoders encoders\n"
  },
  {
    "path": "mir_msgs/msg/TimeDebug.msg",
    "content": "string[] description\nfloat64[] time_elapsed\n"
  },
  {
    "path": "mir_msgs/msg/Trolley.msg",
    "content": "int32 id\nfloat32 length\nfloat32 width\nfloat32 height\nfloat32 offset_locked_wheels\n"
  },
  {
    "path": "mir_msgs/msg/Twist2D.msg",
    "content": "float32 linear\nfloat32 angular\n"
  },
  {
    "path": "mir_msgs/msg/UserPrompt.msg",
    "content": "bool has_request\nstring guid\nstring user_group\nstring question\nstring[] options\nduration timeout\n"
  },
  {
    "path": "mir_msgs/msg/WebPath.msg",
    "content": "int32 seq\nfloat32[] x\nfloat32[] y\n"
  },
  {
    "path": "mir_msgs/msg/WorldMap.msg",
    "content": "mir_msgs/ResourcesState positions\nmir_msgs/ResourcesState areas\nmir_msgs/ExternalRobots robots\nint32 map_id\n"
  },
  {
    "path": "mir_msgs/msg/WorldModel.msg",
    "content": "Header header\nmir_msgs/WorldMap[] world_map # world model for a particular map\nbool enable_resource_tracking\n"
  },
  {
    "path": "mir_msgs/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_msgs</name>\n  <version>1.1.8</version>\n  <description>Message definitions for the MiR robot</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>geometry_msgs</depend>\n\n  <build_depend>message_generation</build_depend>\n  <exec_depend>message_runtime</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_navigation/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_navigation\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Fix typo in license\n* Add Regulated Pure Pursuit local planner (experimental)\n  requires https://github.com/JohnTGZ/regulated_pure_pursuit_controller\n  known bugs:\n  - ignores local costmap (will collide with dynamic obstacles)\n  - oscillates near goal (https://github.com/JohnTGZ/regulated_pure_pursuit_controller/issues/8)\n* Move repo to DFKI-NI\n* Fix start_planner documentation\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Add license headers\n* Fix flake8 warnings\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n* navigation: Reduce footprint to actual size\n  This reduces the footprint:\n  * 18 mm in front\n  * 42 mm in the back\n  * 27 mm at the sides\n  Now the footprint exactly matches the bounding box of the mesh, with no\n  padding. This should make navigation in tight spaces easier; let's hope\n  it doesn't lead to collisions.\n* navigation: Move footprint_padding to proper namespace\n  The footprint_padding parameter in the upper namespace was ignored,\n  needed to be moved into local_costmap/global_costmap to take effect.\n* genmprim: Remove obsolete plt.hold()\n  This fixes the following error:\n  AttributeError: module 'matplotlib.pyplot' has no attribute 'hold'\n* mir_navigation: Remove static_map parameter\n  This fixes the following warning:\n  [ WARN] local_costmap: Pre-Hydro parameter \"static_map\" unused since \"plugins\" is provided\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n* Merge branch 'melodic-2.8' into noetic\n* Rename tf frame and topic 'odom_comb' -> 'odom'\n  This is how they are called on the real MiR since MiR software 2.0.\n* Reformat python code using black\n* Contributors: Martin Günther\n\n1.1.2 (2021-05-12)\n------------------\n* Uncomment available dependencies in noetic (`#79 <https://github.com/DFKI-NI/mir_robot/issues/79>`_)\n* Contributors: Oscar Lima\n\n1.1.1 (2021-02-11)\n------------------\n* Add optional namespace to launch files\n* Add prefix to start_planner.launch (`#67 <https://github.com/DFKI-NI/mir_robot/issues/67>`_)\n* Update scripts to Python3 (Noetic)\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Remove hector_mapping dependency (not released in noetic)\n* Update scripts to Python3 (Noetic)\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Add missing matplotlib dependency\n* plot_mprim: Fix color display\n* Fix bug in genmprim_unicycle_highcost_5cm\n  In Python3, np.arange doesn't accept floats.\n* Fix some catkin_lint warnings\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n* Rename hector_mapping.launch, add dependency\n* genmprim.py: Improve plotting\n* genmprim.py: Make executable\n* SBPL: Reduce allocated_time + initial_epsilon params\n  This leads to shorter planning times, but will perhaps fail on larger\n  maps.\n* Update mprim file to mir-software 2.0.17\n  This was updated in 2.0.17 and hasn't changed through 2.6 at least.\n* Add genmprim_unicycle matlab + python script, fix mprim file\n* Adjust dwb params: split_path, finer trajectories (`#43 <https://github.com/DFKI-NI/mir_robot/issues/43>`_)\n  - use split_path option to enforce following complex paths\n  - more trajectory samples over a smaller simulated time. This fixes a\n  problem where the robot would stop too far away from the goal, as all\n  possible trajectories either overshot the goal, or were too short to\n  reach into the next gridcell of the critics.\n  - remove Oscillation critic (never helped)\n* added PathDistPrunedCritic for dwb (`#42 <https://github.com/DFKI-NI/mir_robot/issues/42>`_)\n  which works exactly like the original PathDistCritic, except that it\n  searches for a local minimum in the distance from the global path to the robots\n  current position. It then prunes the global_path from the start up to\n  this point, therefore approximately cutting of a segment of the path\n  that the robot already followed.\n* Add default local_planner to move_base launch file\n  This makes the hector_mapping Gazebo demo work with the instructions\n  from the README (see `#32 <https://github.com/DFKI-NI/mir_robot/issues/32>`_).\n* Contributors: Martin Günther, Nils Niemann\n\n1.0.4 (2019-05-06)\n------------------\n* Rviz config: Add planned paths + costmap from real MiR\n* Contributors: Martin Günther\n\n1.0.3 (2019-03-04)\n------------------\n* fix frame_id for melodic (`#18 <https://github.com/DFKI-NI/mir_robot/issues/18>`_)\n* Tune dwb parameters\n* PathProgressCritic: Add heading score\n* Use dwb_local_planner in move_base config\n* Move footprint param to move_base root namespace\n  This allows other move_base plugins, such as dwb_local_planner, to\n  access this parameter.\n* Add hector_mapping\n* amcl.launch: Change default, remap service\n  This is required if amcl.launch is started within a namespace.\n* teb_local_planner: Fix odom topic name\n* Merge pull request `#16 <https://github.com/DFKI-NI/mir_robot/issues/16>`_ from niniemann/add-prefix-argument-to-configs\n  Add prefix argument to configs\n* adds $(arg prefix) to a lot of configs\n  This is an important step to be able to re-parameterize move base,\n  the diffdrive controller, ekf, amcl and the costmaps for adding a\n  tf prefix to the robots links\n* mir_navigation: Adjust helper node topics\n* Add amcl launchfile (`#11 <https://github.com/DFKI-NI/mir_robot/issues/11>`_)\n  * added amcl.launch\n  * changed amcl params to default mir amcl parameters\n* Merge pull request `#13 <https://github.com/DFKI-NI/mir_robot/issues/13>`_ from niniemann/fix-virtual-walls\n  The previous configuration of the local costmap didn't work for me -- obstacles seen in the laser scans were not added, or were overridden by the virtual\\_walls\\_map layer. Reordering the layers and loading the virtual walls before the obstacles fixes this for me.\n  Also, I added a `with_virtual_walls` parameter to `start_maps.launch` and `start_planner.launch`.\n* added with_virtual_walls parameter to start_maps and start_planner\n* reorder local costmap plugins\n* Revert \"mir_navigation: Disable virtual walls if no map file set\"\n  This reverts commit 0cfda301b2bb1e8b3458e698efd24a7901e5d132.\n  The reason is that the `eval` keyword was introduced in kinetic, so it\n  doesn't work in indigo.\n* mir_navigation: Update rviz config\n* mir_navigation: Disable virtual walls if no map file set\n* mir_navigation: Rename virtual_walls args + files\n* mir_navigation: Remove parameter first_map_only\n  This parameter must be set to false (the default) when running SLAM\n  (otherwise the map updates won't be received), and when running a static\n  map_server it doesn't matter; even then, it should be false to allow\n  restarting the map_server with a different map. Therefore this commit\n  removes it altogether and leaves it at the default of \"false\".\n* split parameter files between mapping/planning (`#10 <https://github.com/DFKI-NI/mir_robot/issues/10>`_)\n  The differences are simple: When mapping, first_map_only must be\n  set to false, and the virtual walls plugin must not be loaded\n  (else move_base will wait for a topic that is not going to be\n  published).\n* Document move_base params, add max_planning_retries\n  Setting max_planning_retries to 10 makes the planner fail faster if the\n  planning problem is infeasible. By default, there's an infinite number\n  of retries, so we had to wait until the planner_patience ran out (5 s).\n* Update rviz config\n  Make topics relative, so that ROS_NAMESPACE=... works.\n* Switch to binary sbpl_lattice_planner dependency\n  ... instead of compiling from source.\n* Split scan_rep117 topic into two separate topics\n  This fixes the problem that the back laser scanner was ignored in the\n  navigation costmap in Gazebo (probably because in Gazebo, both laser\n  scanners have the exact same timestamp).\n* mir_navigation: Add clear_params to move_base launch\n* mir_navigation: marking + clearing were switched\n  Other than misleading names, this had no effect.\n* Contributors: Martin Günther, Nils Niemann, Noël Martignoni\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n* Initial release\n* Contributors: Martin Günther\n"
  },
  {
    "path": "mir_navigation/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_navigation)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package()\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n# Mark executable scripts (Python etc.) for installation\n# in contrast to setup.py, you can choose the destination\ninstall(PROGRAMS\n  mprim/genmprim_unicycle_highcost_5cm.py\n  nodes/acc_finder.py\n  nodes/min_max_finder.py\n  scripts/plot_mprim.py\n  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark executables and/or libraries for installation\n# install(TARGETS mir_navigation mir_navigation_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n# Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(DIRECTORY\n  config\n  launch\n  mprim\n  rviz\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_mir_navigation.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n\nroslaunch_add_file_check(launch)\n"
  },
  {
    "path": "mir_navigation/config/base_local_planner_params.yaml",
    "content": "base_local_planner: base_local_planner/TrajectoryPlannerROS\nTrajectoryPlannerROS:\n  # Robot configuration\n  acc_lim_x: 1.5\n  acc_lim_y: 0\n  acc_lim_theta: 2.0\n  max_vel_x: 0.8\n  min_vel_x: 0.1\n  max_vel_theta: 1.0\n  min_vel_theta: -1.0\n  min_in_place_vel_theta: 0.2\n  escape_vel: -0.1\n  holonomic_robot: false\n\n  # Goal tolerance\n  yaw_goal_tolerance: 0.03\n  xy_goal_tolerance: 0.08\n  latch_xy_goal_tolerance: true\n\n  # Forward simulaton parameters\n  sim_time: 1.2\n  sim_granularity: 0.025\n  angular_sim_granularity: 0.04\n  vx_samples: 15\n  vtheta_samples: 20\n  controller_frequency: 5\n\n  # Trajectory scoring parameters\n  meter_scoring: true\n  pdist_scale: 2.2 #0.6\n  gdist_scale: 0.8 #0.8\n  occdist_scale: 0.1\n  heading_lookahead: 0.325\n  heading_scoring: true\n  heading_scoring_timestep: 0.8\n  dwa: true\n  publish_cost_grid: false\n  global_frame_id: map\n\n  # Oscillation prevention parameter\n  oscillation_reset_dist: 0.05\n\n  # Global plan parameters\n  prune_plan: true\n"
  },
  {
    "path": "mir_navigation/config/costmap_common_params.yaml",
    "content": "robot_base_frame: $(arg prefix)base_footprint\ntransform_tolerance: 0.4\nupdate_frequency: 5.0\npublish_frequency: 1.0\nobstacle_range: 3.0\n#mark_threshold: 1\npublish_voxel_map: true\nfootprint_padding: 0.0\nnavigation_map:\n  map_topic: /map\nobstacles:\n  observation_sources: b_scan_marking b_scan_clearing f_scan_marking f_scan_clearing\n  b_scan_marking:\n    topic: b_scan_rep117\n    data_type: LaserScan\n    clearing: false\n    marking: true\n    inf_is_valid: false\n    min_obstacle_height: 0.13\n    max_obstacle_height: 0.25\n  b_scan_clearing:\n    topic: b_scan_rep117\n    data_type: LaserScan\n    clearing: true\n    marking: false\n    inf_is_valid: false\n    min_obstacle_height: 0.13\n    max_obstacle_height: 0.25\n  f_scan_marking:\n    topic: f_scan_rep117\n    data_type: LaserScan\n    clearing: false\n    marking: true\n    inf_is_valid: false\n    min_obstacle_height: 0.13\n    max_obstacle_height: 0.25\n  f_scan_clearing:\n    topic: f_scan_rep117\n    data_type: LaserScan\n    clearing: true\n    marking: false\n    inf_is_valid: false\n    min_obstacle_height: 0.13\n    max_obstacle_height: 0.25\nvirtual_walls_map:\n  map_topic: /virtual_walls/map\n  use_maximum: true\n"
  },
  {
    "path": "mir_navigation/config/costmap_global_params.yaml",
    "content": "global_costmap:\n    global_frame: map\n    update_frequency: 1.0\n    publish_frequency: 1.0\n    raytrace_range: 2.0\n    resolution: 0.05\n    z_resolution: 0.2\n    z_voxels: 10\n    inflation:\n      cost_scaling_factor:  3.0  # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius.\n      inflation_radius:     0.6  # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.\n\n    # plugins are loaded via costmap_global_params_plugins_[mapping|planning].yaml\n"
  },
  {
    "path": "mir_navigation/config/costmap_global_params_plugins_no_virtual_walls.yaml",
    "content": "global_costmap:\n    plugins:\n        - {name: navigation_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obstacles,  type: \"costmap_2d::VoxelLayer\" }\n        - {name: inflation,  type: \"costmap_2d::InflationLayer\" }\n"
  },
  {
    "path": "mir_navigation/config/costmap_global_params_plugins_virtual_walls.yaml",
    "content": "global_costmap:\n    plugins:\n        - {name: navigation_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obstacles,  type: \"costmap_2d::VoxelLayer\" }\n        - {name: virtual_walls_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: inflation,  type: \"costmap_2d::InflationLayer\" }\n"
  },
  {
    "path": "mir_navigation/config/costmap_local_params.yaml",
    "content": "local_costmap:\n    global_frame: $(arg prefix)odom\n    rolling_window: true\n    raytrace_range: 6.0\n    resolution: 0.05\n    z_resolution: 0.15\n    z_voxels: 8\n    inflation:\n      cost_scaling_factor: 10.0  # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius.\n      inflation_radius:     0.6  # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius.\n    width: 4.0\n    height: 4.0\n    origin_x: 0.0\n    origin_y: 0.0\n\n    # plugins are loaded via costmap_local_params_plugins_[mapping|planning].yaml\n"
  },
  {
    "path": "mir_navigation/config/costmap_local_params_plugins_no_virtual_walls.yaml",
    "content": "local_costmap:\n    plugins:\n        - {name: obstacles,  type: \"costmap_2d::VoxelLayer\" }\n        - {name: inflation,  type: \"costmap_2d::InflationLayer\" }\n"
  },
  {
    "path": "mir_navigation/config/costmap_local_params_plugins_virtual_walls.yaml",
    "content": "local_costmap:\n    plugins:\n        - {name: virtual_walls_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obstacles,  type: \"costmap_2d::VoxelLayer\" }\n        - {name: inflation,  type: \"costmap_2d::InflationLayer\" }\n"
  },
  {
    "path": "mir_navigation/config/dwa_local_planner_params.yaml",
    "content": "base_local_planner: dwa_local_planner/DWAPlannerROS\nDWAPlannerROS:\n  # Robot configuration\n  max_vel_x:  0.8\n  min_vel_x: -0.2\n\n  max_vel_y: 0.0  # diff drive robot\n  min_vel_y: 0.0  # diff drive robot\n\n  max_trans_vel: 0.8  # choose slightly less than the base's capability\n  min_trans_vel: 0.1  # this is the min trans velocity when there is negligible rotational velocity\n  trans_stopped_vel: 0.03\n\n  # Warning!\n  #   do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities\n  #   are non-negligible and small in place rotational velocities will be created.\n\n  max_rot_vel: 1.0  # choose slightly less than the base's capability\n  min_rot_vel: 0.1  # this is the min angular velocity when there is negligible translational velocity\n  rot_stopped_vel: 0.1\n\n  acc_lim_x: 1.5\n  acc_lim_y: 0.0      # diff drive robot\n  acc_limit_trans: 1.5\n  acc_lim_theta: 2.0\n\n  # Goal tolerance\n  yaw_goal_tolerance: 0.03  # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)\n  xy_goal_tolerance: 0.08   # xy_goal_tolerance  > (sim_time * min_vel_x)   / 2\n  latch_xy_goal_tolerance: true\n\n  # Forward simulation\n  sim_time: 1.2\n  vx_samples: 15\n  vy_samples: 1       # diff drive robot, there is only one sample\n  vtheta_samples: 20\n\n  # Trajectory scoring\n  path_distance_bias: 64.0      # default: 32.0  mir: 32.0  - weighting for how much it should stick to the global path plan\n  goal_distance_bias: 12.0      # default: 24.0  mir: 48.0  - weighting for how much it should attempt to reach its goal\n  occdist_scale: 0.5            # default: 0.01  mir: 0.01  - weighting for how much the controller should avoid obstacles\n  forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point\n  stop_time_buffer: 0.2         # default: 0.2   mir: 0.2   - amount of time a robot must stop before colliding for a valid traj.\n  scaling_speed: 0.25           # default: 0.25  mir: 0.25  - absolute velocity at which to start scaling the robot's footprint\n  max_scaling_factor: 0.2       # default: 0.2   mir: 0.2   - how much to scale the robot's footprint when at speed.\n  prune_plan: true\n\n  # Oscillation prevention\n  oscillation_reset_dist: 0.05  # 0.05   - how far to travel before resetting oscillation flags, in m\n  oscillation_reset_angle: 0.2  # 0.2    - the angle the robot must turn before resetting Oscillation flags, in rad\n\n  # Debugging\n  publish_traj_pc : true\n  publish_cost_grid_pc: true\n  global_frame_id: /odom  # or <robot namespace>/odom\n"
  },
  {
    "path": "mir_navigation/config/dwb_local_planner_params.yaml",
    "content": "base_local_planner: nav_core_adapter::LocalPlannerAdapter\nLocalPlannerAdapter:\n  planner_name: dwb_local_planner::DWBLocalPlanner\nDWBLocalPlanner:\n  # Robot configuration\n  max_vel_x:  0.8\n  min_vel_x: -0.2\n\n  max_vel_y: 0.0  # diff drive robot\n  min_vel_y: 0.0  # diff drive robot\n\n  max_speed_xy: 0.8    # max_trans_vel: 0.8  # choose slightly less than the base's capability\n  min_speed_xy: 0.1    # min_trans_vel: 0.1  # this is the min trans velocity when there is negligible rotational velocity\n\n  max_vel_theta: 1.0    # max_rot_vel: 1.0  # choose slightly less than the base's capability\n  min_speed_theta: 0.1  # min_rot_vel: 0.1 default: 0.4  # this is the min angular velocity when there is negligible translational velocity\n\n  acc_lim_x: 1.5\n  acc_lim_y: 0.0      # diff drive robot\n  acc_lim_theta: 2.0\n  decel_lim_x: -1.5\n  decel_lim_y: -0.0\n  decel_lim_theta: -2.0\n\n  # Goal tolerance\n  yaw_goal_tolerance: 0.03  # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)\n  xy_goal_tolerance: 0.08   # xy_goal_tolerance  > (sim_time * min_vel_x)   / 2\n  #latch_xy_goal_tolerance: true\n\n  # Whether to split the path into segments or not\n  # Requires https://github.com/locusrobotics/robot_navigation/pull/50\n  split_path: true\n\n  # Forward simulation (trajectory generation)\n  trajectory_generator_name: dwb_plugins::StandardTrajectoryGenerator # or dwb_plugins::LimitedAccelGenerator\n  sim_time: 0.8\n  vx_samples: 15\n  vy_samples: 1       # diff drive robot, there is only one sample\n  vtheta_samples: 15\n  discretize_by_time: false\n  angular_granularity: 0.15\n  linear_granularity: 0.05\n  # sim_period\n  # include_last_point\n\n  # Goal checking\n  goal_checker_name: dwb_plugins::SimpleGoalChecker\n  # stateful: true\n\n  # Critics (trajectory scoring)\n  #default_critic_namespaces: [dwb_critics, mir_dwb_critics]\n  critics: [RotateToGoal, ObstacleFootprint, PathAlign, PathDistPruned, PathProgress]\n  RotateToGoal:\n    scale: 100.0\n    # lookahead_time: -1.0\n    # slowing_factor: 5.0\n  ObstacleFootprint:\n    scale: 0.01             # default: 0.01  mir: 0.01  - weighting for how much the controller should avoid obstacles\n    max_scaling_factor: 0.2 # default: 0.2   mir: 0.2   - how much to scale the robot's footprint when at speed.\n    scaling_speed: 0.25     # default: 0.25  mir: 0.25  - absolute velocity at which to start scaling the robot's footprint\n    sum_scores: false       # if true, return sum of scores of all trajectory points instead of only last one\n  PathAlign:\n    scale: 16.0\n    forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point\n  PathDistPruned:\n    scale: 32.0            # default: 32.0  mir: 32.0   - weighting for how much it should stick to the global path plan\n    class: 'mir_dwb_critics::PathDistPruned'\n  PathProgress:\n    scale: 24.0            # default: 24.0  mir: 48.0   - weighting for how much it should attempt to reach its goal\n    heading_scale: 0.1\n    class: 'mir_dwb_critics::PathProgress'\n    xy_local_goal_tolerance: 0.20\n    angle_threshold: 0.78539816  # 45 degrees\n\n\n  # Prune already passed poses from plan\n  prune_plan: true\n  prune_distance: 1.0   # Old poses farther away than prune_distance (in m) will be pruned.\n                        # If the robot ever gets away further than this distance from the plan,\n                        # the error \"Resulting plan has 0 poses in it\" will be thrown and\n                        # replanning will be triggered.\n\n  # Debugging\n  publish_cost_grid_pc: true\n  debug_trajectory_details: false\n  publish_evaluation: true\n  publish_global_plan: true\n  publish_input_params: true\n  publish_local_plan: true\n  publish_trajectories: true\n  publish_transformed_plan: true\n  marker_lifetime: 0.5\n"
  },
  {
    "path": "mir_navigation/config/eband_local_planner_params.yaml",
    "content": "base_local_planner: eband_local_planner/EBandPlannerROS\nEBandPlannerROS:\n  # Robot configuration\n  max_vel_lin: 0.8                                  # choose slightly less than the base's capability\n  min_vel_lin: 0.1                                  # this is the min trans velocity when there is negligible rotational velocity\n  trans_stopped_vel: 0.03\n\n  max_vel_th: 1.0                                   # choose slightly less than the base's capability\n  min_vel_th: 0.1                                   # this is the min angular velocity when there is negligible translational velocity\n  rot_stopped_vel: 0.1\n\n  min_in_place_vel_th: 0.1                          # Minimum in-place angular velocity\n  in_place_trans_vel: 0.0                           # Minimum in place linear velocity\n\n  max_acceleration: 1.5                             # Maximum allowable acceleration\n  max_translational_acceleration: 1.5               # Maximum linear acceleration\n  max_rotational_acceleration: 2.0                  # Maximum angular acceleration\n\n  # Goal tolerance\n  yaw_goal_tolerance: 0.03                          # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)\n  xy_goal_tolerance: 0.08                           # xy_goal_tolerance  > (sim_time * min_vel_x)   / 2\n\n  # Elastic Band Parameters\n  eband_min_relative_overlap: 0.7                   # Min distance that denotes connectivity between consecutive bubbles\n  eband_tiny_bubble_distance: 0.01                  # Bubble geometric bound regarding tiny bubble distance\n  eband_tiny_bubble_expansion: 0.01                 # Bubble geometric bound regarding tiny bubble expansion\n  eband_internal_force_gain: 1.0                    # Force gain of forces between consecutive bubbles that tend to stretch the elastic band\n  eband_external_force_gain: 2.0                    # Force gain of forces that tend to move the bubbles away from obstacles\n  num_iterations_eband_optimization: 3              # Number of iterations for eband optimization\n  eband_equilibrium_approx_max_recursion_depth: 4   # Number of iterations for reaching the equilibrium between internal and external forces\n  eband_equilibrium_relative_overshoot: 0.75        # Maximum relative equlibrium overshoot\n  eband_significant_force_lower_bound: 0.15         # Minimum magnitude of force that is considered significant and used in the calculations\n  costmap_weight: 10.0                              # Costmap weight factor used in the calculation of distance to obstacles\n\n  # Trajectory Controller Parameters\n  k_prop: 4.0                                       # Proportional gain of the PID controller\n  k_damp: 3.5                                       # Damping gain of the PID controller\n  Ctrl_Rate: 10.0                                   # Control rate\n  virtual_mass: 0.75                                # Virtual mass\n  rotation_correction_threshold: 0.5                # Rotation correction threshold\n  differential_drive: True                          # Denotes whether to use the differential drive mode\n  bubble_velocity_multiplier: 2.0                   # Multiplier of bubble radius\n  rotation_threshold_multiplier: 1.0                # Multiplier of rotation threshold\n  disallow_hysteresis: False                        # Determines whether to try getting closer to the goal, in case of going past the tolerance\n"
  },
  {
    "path": "mir_navigation/config/mir_local_planner_params.yaml",
    "content": "base_local_planner: mirLocalPlanner/MIRPlannerROS\nMIRPlannerROS:\n  # Robot configuration\n  max_vel_x: 0.8\n  min_vel_x: -0.2\n\n  min_trans_vel: 0.1  # this is the min trans velocity when there is negligible rotational velocity\n\n  # Warning!\n  #   do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities\n  #   are non-negligible and small in place rotational velocities will be created.\n\n  max_rot_vel: 1.0  # choose slightly less than the base's capability\n  min_rot_vel: 0.1  # this is the min angular velocity when there is negligible translational velocity\n\n  acc_lim_x: 1.5\n  acc_lim_y: 0.0      # diff drive robot\n  acc_lim_th: 2.0\n  min_inplace_rot: 0.15\n  max_inplace_rot: 0.6\n  min_in_place_rotational_vel: 0.2\n  escape_vel: -0.1\n  holonomic_robot: false\n\n  # Goal tolerance\n  yaw_goal_tolerance: 0.03  # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide)\n  xy_goal_tolerance: 0.08   # xy_goal_tolerance  > (sim_time * min_vel_x)   / 2\n\n  # Forward simulaton\n  sim_time: 1.2\n  sim_granularity: 0.025\n  vx_samples: 15\n  vth_samples: 20\n  vtheta_samples: 20\n\n  # Trajectory scoring\n  path_distance_bias: 0.4        # weighting for how much it should stick to the global path plan\n  goal_distance_bias: 0.6        # weighting for how much it should attempt to reach its goal\n  occdist_scale: 0.01            # weighting for how much the controller should avoid obstacles\n  forward_point_distance: 0.325  # how far along to place an additional scoring point\n  stop_time_buffer: 0.2          # amount of time a robot must stop before colliding for a valid traj.\n  scaling_speed: 0.25            # absolute velocity at which to start scaling the robot's footprint\n  max_scaling_factor: 0.2        # how much to scale the robot's footprint when at speed.\n  heading_lookahead: 0.325\n  dwa: true\n\n  # Oscillation prevention\n  oscillation_reset_dist: 0.05  # how far to travel before resetting oscillation flags, in m\n\n\n  # Debugging\n  publish_visualization: false\n  publish_cost_grid_pc: false\n  global_frame_id: odom\n\n  # MiR specific parameters\n  tau_p: 5.0  # The proportional value in the CTE PID tracking\n  tau_i: 0.1  # The integral value in the CTE PID tracking\n  tau_d: 0.5  # The differential value in the CTE PID tracking\n  tau_w: 9.0  # The proportional angle value in the CTE tracking\n\n  k_rho: 1.0    # The proportional value to goal in Goal tracking\n  k_alfa: 8.0   # The diff angle between the robot and the goal in the Goal tracking\n  k_beta: -2.5  # The angle to the goal from the robot in the Goal tracking\n\n  blocked_path_dist: 3.0         # At what distance should the planner react when the path is blocked\n  blocked_path_dev: 60.0         # How far can we move from the planned path when it is blocked\n  blocked_path_action: new_plan  # Which action to take, when path is blocked\n  occ_path_dist: 3.0             # At what distance should the planner react when the path is near obstacle\n  occ_path_dev: 15.0             # How far can we move from the planned path when the path is near a obstacle\n  occ_path_level: 120.0          # Threshold level for a obstacle\n\n  cte_look_ahead: 0.2            # The max/min distance to add for the CTE tracking\n\n  penalize_negative_x: true      # Whether to penalize trajectories that have negative x velocities.\n\n  # non-dynamic parameters\n  dist_towards_obstacles: 1.5\n  dist_towards_obstacles_trolley: 1.75\n  goal_seek_tolerance: 2.0\n  goal_seek_tolerance_trolley: 0.25\n"
  },
  {
    "path": "mir_navigation/config/move_base_common_params.yaml",
    "content": "### footprint\nfootprint: [[0.488,-0.293],[0.488,0.293],[-0.412,0.293],[-0.412,-0.293]]\n\n### replanning\ncontroller_frequency: 5.0   # run controller at 5.0 Hz\ncontroller_patience: 15.0    # if the controller failed, clear obstacles and retry; after 15.0 s, abort and replan\nplanner_frequency: 0.0       # don't continually replan (only when controller failed)\nplanner_patience: 5.0        # if the first planning attempt failed, abort planning retries after 5.0 s...\nmax_planning_retries: 10     # ... or after 10 attempts (whichever happens first)\noscillation_timeout: 30.0    # abort controller and trigger recovery behaviors after 30.0 s\n\n### recovery behaviors\nrecovery_behavior_enabled: true\nrecovery_behaviors: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]\nconservative_reset:\n  reset_distance: 3.0        # clear obstacles farther away than 3.0 m\n"
  },
  {
    "path": "mir_navigation/config/pose_local_planner_params.yaml",
    "content": "base_local_planner: pose_follower/PoseFollower\nPoseFollower:\n    k_trans: 2.0\n    k_rot: 1.0\n\n    # within this distance to the goal, finally rotate to the goal heading (also, we've reached our goal only if we're within this dist)\n    tolerance_trans: 0.3\n\n    # we've reached our goal only if we're within this angular distance\n    tolerance_rot: 0.3\n\n    # we've reached our goal only if we're within range for this long and stopped\n    tolerance_timeout: 0.5\n\n    # set this to true if you're using a holonomic robot\n    holonomic: false\n\n    # number of samples (scaling factors of our current desired twist) to check the validity of\n    samples: 10\n\n    # go no faster than this\n    max_vel_lin: 0.3\n    max_vel_th: 0.5\n\n    # minimum velocities to keep from getting stuck\n    min_vel_lin: 0.03\n    min_vel_th: 0.1\n\n    # if we're rotating in place, go at least this fast to avoid getting stuck\n    min_in_place_vel_th: 0.1\n\n    # when we're near the end and would be trying to go no faster than this translationally, just rotate in place instead\n    in_place_trans_vel: 0.1\n\n    # we're \"stopped\" if we're going slower than these velocities\n    trans_stopped_velocity: 0.03\n    rot_stopped_velocity: 0.1\n\n    # if this is true, we don't care whether we go backwards or forwards\n    allow_backwards: true\n\n    # if this is true, turn in place to face the new goal instead of arcing toward it\n    turn_in_place_first: true\n\n    # if turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location\n    max_heading_diff_before_moving: 0.2\n"
  },
  {
    "path": "mir_navigation/config/rpp_local_planner_params.yaml",
    "content": "# requires https://github.com/JohnTGZ/regulated_pure_pursuit_controller\n#\n# known bugs:\n# - ignores local costmap (will collide with dynamic obstacles)\n# - oscillates near goal (https://github.com/JohnTGZ/regulated_pure_pursuit_controller/issues/8)\n\nbase_local_planner: regulated_pure_pursuit_controller/RegulatedPurePursuitController\nRegulatedPurePursuitController:\n  # general params\n  #max_robot_pose_search_dist: -1.0   # Unused. Upper bound on integrated distance along the global plan to search for the closest pose to the robot pose. This should be left as the default unless there are paths with loops and intersections that do not leave the local costmap, in which case making this value smaller is necessary to prevent shortcutting. If set to -1, it will use the maximum distance possible to search every point on the path for the nearest path point.\n  min_global_plan_complete_size: 20     # (default: 20)\n  global_plan_prune_distance: 1.0       # Unused. (default: 1.0)\n\n  # Lookahead\n  use_velocity_scaled_lookahead_dist: false   # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false)\n  # only when false:\n  lookahead_dist: 0.25                        # The lookahead distance (m) to use to find the lookahead point. (default: 0.6)\n  # only when true:\n  min_lookahead_dist: 0.3                     # The minimum lookahead distance (m) threshold. (default: 0.3)\n  max_lookahead_dist: 0.9                     # The maximum lookahead distance (m) threshold. (default: 0.9)\n  lookahead_time: 1.5                         # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)\n\n  # Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true\n  use_rotate_to_heading: false         # Whether to enable rotating to rough heading and goal orientation when using holonomic planners. Recommended on for all robot types that can rotate in place. (default: true)\n  # only when true:\n  rotate_to_heading_angular_vel: 1.0   # The angular velocity to use. (default: 1.8)\n  rotate_to_heading_min_angle: 0.785   # The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785)\n  max_angular_accel: 1.5               # Maximum allowable angular acceleration (rad/s/s) while rotating to heading. (default: 3.2)\n\n  # Reversing - onle one of use_rotate_to_heading and allow_reversing can be set to true\n  allow_reversing: true                # Enables the robot to drive in the reverse direction, when the path planned involves reversing (which is represented by orientation cusps). (default: false)\n\n  # Speed\n  desired_linear_vel: 0.6              # The desired maximum linear velocity (m/s) to use. (default: 0.5)\n  max_angular_vel: 0.8                 # (default: 1.5)\n  min_approach_linear_velocity: 0.05   # The minimum velocity (m/s) threshold to apply when approaching the goal to ensure progress. Must be > 0.01. (default: 0.05)\n\n  # Regulated linear velocity scaling\n  use_regulated_linear_velocity_scaling: true   # Whether to use the regulated features for path curvature (e.g. slow on high curvature paths). (default: true)\n  # only when true:\n  regulated_linear_scaling_min_radius: 0.9      # The turning radius (m) for which the regulation features are triggered. Remember, sharper turns have smaller radii. (default: 0.9)\n  regulated_linear_scaling_min_speed: 0.25      # The minimum speed (m/s) for which any of the regulated heuristics can send, to ensure process is still achievable even in high cost spaces with high curvature. Must be > 0.1. (default: 0.25)\n\n  # Inflation cost scaling (Limit velocity by proximity to obstacles)\n  use_cost_regulated_linear_velocity_scaling: true   # Whether to use the regulated features for proximity to obstacles (e.g. slow in close proximity to obstacles). (default: true)\n  inflation_cost_scaling_factor: 3.0                 # (default: 3.0)   # must be > 0\n  cost_scaling_dist: 0.6                             # (default: 0.6)\n  cost_scaling_gain: 1.0                             # (default: 1.0)\n\n  # Collision avoidance\n  max_allowed_time_to_collision_up_to_carrot: 1.0    # The time (s) to project a velocity command forward to check for collisions. (default: 1.0)\n\n  goal_dist_tol: 0.25        # (default: 0.25)\n\n  control_frequency: 20      # (default: 20)\n\n  transform_tolerance: 0.1   # The TF transform tolerance (seconds). (default: 0.1)\n"
  },
  {
    "path": "mir_navigation/config/sbpl_global_params.yaml",
    "content": "base_global_planner: SBPLLatticePlanner\nSBPLLatticePlanner:\n  environment_type: XYThetaLattice\n  planner_type: ARAPlanner\n  allocated_time: 10.0\n  initial_epsilon: 15.0\n  forward_search: false\n  nominalvel_mpersecs: 0.8\n  timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s\n"
  },
  {
    "path": "mir_navigation/config/teb_local_planner_params.yaml",
    "content": "# NOTE: When using the teb_local_planner, make sure to set the local costmap\n# resolution high (for example 0.1 m), otherwise the optimization will take\n# forever (around 10 minutes for each iteration).\nbase_local_planner: teb_local_planner/TebLocalPlannerROS\nTebLocalPlannerROS:\n  # Trajectory\n  teb_autosize: true                       # Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended)\n  dt_ref: 0.3                              # Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate)\n  dt_hysteresis: 0.1                       # Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref\n  global_plan_overwrite_orientation: false # Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automatically\n  allow_init_with_backwards_motion: false  # If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors)\n  max_global_plan_lookahead_dist: 3.0      # Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size]\n  force_reinit_new_goal_dist: 1.0          # Force the planner to reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting)\n  feasibility_check_no_poses: 5            # Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval\n  global_plan_viapoint_sep: -0.1           # Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled]\n  via_points_ordered: false                # If true, the planner adheres to the order of via-points in the storage container\n  exact_arc_length: false                  # If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used.\n  publish_feedback: false                  # Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes)\n\n  # Robot\n  max_vel_x: 0.8                           # Maximum translational velocity of the robot\n  max_vel_x_backwards: 0.2                 # Maximum translational velocity of the robot for driving backwards\n  max_vel_y: 0.0                           # Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)\n  max_vel_theta: 1.0                       # Maximum angular velocity of the robot\n  acc_lim_x: 1.5                           # Maximum translational acceleration of the robot\n  acc_lim_y: 0.0                           # Maximum strafing acceleration of the robot\n  acc_lim_theta: 2.0                       # Maximum angular acceleration of the robot\n  min_turning_radius: 0.0                  # Minimum turning radius of a carlike robot (diff-drive robot: zero)\n  wheelbase: 1.0                           # The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots!\n  cmd_angle_instead_rotvel: false          # Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance')\n  is_footprint_dynamic: false              # If true, update the footprint before checking trajectory feasibility\n  footprint_model:\n    type: \"polygon\"\n    vertices: [[0.506,-0.32],[0.506,0.32],[-0.454,0.32],[-0.454,-0.32]]\n\n  # Goal tolerance\n  xy_goal_tolerance: 0.03                  # Allowed final euclidean distance to the goal position\n  yaw_goal_tolerance: 0.08                 # Allowed final orientation error to the goal orientation\n  free_goal_vel: false                     # Allow the robot's velocity to be nonzero for planning purposes (the robot can arrive at the goal with max speed)\n\n  # Obstacles\n  min_obstacle_dist: 0.4                   # Minimum desired separation from obstacles\n  inflation_dist: 0.1                      # Buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)\n  dynamic_obstacle_inflation_dist: 0.6     # Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)\n  include_dynamic_obstacles: false         # Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also changes the homotopy class search). If false, all obstacles are considered to be static.\n  include_costmap_obstacles: true          # Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented)\n  legacy_obstacle_association: false       # If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only 'relevant' obstacles).\n  obstacle_association_force_inclusion_factor: 1.5  # The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist.\n  obstacle_association_cutoff_factor: 5.0           # See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first.\n  costmap_obstacles_behind_robot_dist: 1.5 # Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)\n  obstacle_poses_affected: 10              # The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well\n  #costmap_converter_plugin: \"\"            #\n  #costmap_converter_spin_thread: true     #\n  #costmap_converter_rate: 5               #\n\n  # Optimization\n  no_inner_iterations: 5                   # Number of solver iterations called in each outerloop iteration\n  no_outer_iterations: 4                   # Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations\n  optimization_activate: true              # Activate the optimization\n  optimization_verbose: false              # Print verbose information\n  penalty_epsilon: 0.1                     # Add a small safty margin to penalty functions for hard-constraint approximations\n  weight_max_vel_x: 2.0                    # Optimization weight for satisfying the maximum allowed translational velocity\n  weight_max_vel_y: 2.0                    # Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)\n  weight_max_vel_theta: 1.0                # Optimization weight for satisfying the maximum allowed angular velocity\n  weight_acc_lim_x: 1.0                    # Optimization weight for satisfying the maximum allowed translational acceleration\n  weight_acc_lim_y: 1.0                    # Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)\n  weight_acc_lim_theta: 1.0                # Optimization weight for satisfying the maximum allowed angular acceleration\n  weight_kinematics_nh: 1000.0             # Optimization weight for satisfying the non-holonomic kinematics\n  weight_kinematics_forward_drive: 1.0     # Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)\n  weight_kinematics_turning_radius: 1.0    # Optimization weight for enforcing a minimum turning radius (carlike robots)\n  weight_optimaltime: 1.0                  # Optimization weight for contracting the trajectory w.r.t transition time\n  weight_obstacle: 50.0                    # Optimization weight for satisfying a minimum seperation from obstacles\n  weight_inflation: 0.1                    # Optimization weight for the inflation penalty (should be small)\n  weight_dynamic_obstacle: 50.0            # Optimization weight for satisfying a minimum seperation from dynamic obstacles\n  weight_dynamic_obstacle_inflation: 0.1   # Optimization weight for the inflation penalty of dynamic obstacles (should be small)\n  weight_viapoint: 1.0                     # Optimization weight for minimizing the distance to via-points\n  weight_adapt_factor: 2.0                 # Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new: weight_old * factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.\n\n  # Homotopy Class Planner\n#  enable_homotopy_class_planning: true    #\n  enable_multithreading: true              # Activate multiple threading for planning multiple trajectories in parallel\n#  simple_exploration: false               #\n  max_number_classes: 2                    # Specify the maximum number of allowed alternative homotopy classes (limits computational effort)\n  selection_cost_hysteresis: 1.0           # Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor)\n  selection_prefer_initial_plan: 0.95      # Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan.)\n  selection_obst_cost_scale: 100.0         # Extra scaling of obstacle cost terms just for selecting the 'best' candidate (new_obst_cost: obst_cost*factor)\n  selection_viapoint_cost_scale: 1.0       # Extra scaling of via-point cost terms just for selecting the 'best' candidate. (new_viapt_cost: viapt_cost*factor)\n  selection_alternative_time_cost: false   # If true, time cost is replaced by the total transition time.\n  roadmap_graph_no_samples: 15             # Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off\n  roadmap_graph_area_width: 5.0            # Specify the width of the area in which sampled will be generated between start and goal [m] (the height equals the start-goal distance)\n  roadmap_graph_area_length_scale: 1.0     # The length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal!)\n  h_signature_prescaler: 1.0               # Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2<H<=1)\n  h_signature_threshold: 0.1               # Two h-signuteres are assumed to be equal, if both the difference of real parts and complex parts are below the specified threshold\n#  obstacle_keypoint_offset: 0.1           #\n  obstacle_heading_threshold: 0.45         # Specify the value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account for exploration)\n  viapoints_all_candidates: true           # If true, all trajectories of different topologies are attached to the set of via-points, otherwise only the trajectory sharing the same one as the initial/global plan is attached (no effect in test_optim_node).\n  visualize_hc_graph: false                # Visualize the graph that is created for exploring new homotopy classes\n  visualize_with_time_as_z_axis_scale: 0.0 # If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as the z-axis scaled by this value. Most useful for dynamic obstacles.\n\n  # Recovery\n  shrink_horizon_backup: true              # Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.\n  oscillation_recovery: true               # Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards).\n\n  odom_topic: odom\n  map_frame: odom\n"
  },
  {
    "path": "mir_navigation/launch/amcl.launch",
    "content": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"tf_prefix\" default=\"\" />\n  <arg name=\"namespace\" default=\"$(arg tf_prefix)\" doc=\"Namespace to push all topics into.\"/>\n\n  <arg name=\"use_map_topic\"   default=\"true\"/>\n  <arg name=\"scan_topic\"      default=\"scan\"/>\n  <arg name=\"map_topic\"       default=\"/map\"/>         <!-- if use_map_topic = true  -->\n  <arg name=\"map_service\"     default=\"/static_map\"/>  <!-- if use_map_topic = false -->\n  <arg name=\"initial_pose_x\"  default=\"0.0\"/>\n  <arg name=\"initial_pose_y\"  default=\"0.0\"/>\n  <arg name=\"initial_pose_a\"  default=\"0.0\"/>\n  <arg name=\"odom_frame_id\"   default=\"$(arg tf_prefix)/odom\"/>\n  <arg name=\"base_frame_id\"   default=\"$(arg tf_prefix)/base_footprint\"/>\n  <arg name=\"global_frame_id\" default=\"/map\"/>\n\n  <group if=\"$(eval namespace != '')\" ns=\"$(arg namespace)\">\n    <node pkg=\"amcl\" type=\"amcl\" name=\"amcl\" output=\"screen\" >\n      <param name=\"use_map_topic\"             value=\"$(arg use_map_topic)\"/>\n      <param name=\"odom_model_type\"           value=\"diff-corrected\"/>\n      <param name=\"gui_publish_rate\"          value=\"10.0\"/>\n      <param name=\"save_pose_rate\"            value=\"0.5\"/>\n      <param name=\"laser_max_beams\"           value=\"50\"/>\n      <param name=\"laser_min_range\"           value=\"-1.0\"/>\n      <param name=\"laser_max_range\"           value=\"-1.0\"/>\n      <param name=\"min_particles\"             value=\"500\"/>\n      <param name=\"max_particles\"             value=\"5000\"/>\n      <param name=\"kld_err\"                   value=\"0.05\"/>\n      <param name=\"kld_z\"                     value=\"0.99\"/>\n      <param name=\"odom_alpha1\"               value=\"0.02\"/>\n      <param name=\"odom_alpha2\"               value=\"0.01\"/>\n      <param name=\"odom_alpha3\"               value=\"0.01\"/>\n      <param name=\"odom_alpha4\"               value=\"0.02\"/>\n      <param name=\"laser_z_hit\"               value=\"0.5\"/>\n      <param name=\"laser_z_short\"             value=\"0.05\"/>\n      <param name=\"laser_z_max\"               value=\"0.05\"/>\n      <param name=\"laser_z_rand\"              value=\"0.5\"/>\n      <param name=\"laser_sigma_hit\"           value=\"0.2\"/>\n      <param name=\"laser_lambda_short\"        value=\"0.1\"/>\n      <param name=\"laser_model_type\"          value=\"likelihood_field\"/>\n      <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n      <param name=\"update_min_d\"              value=\"0.2\"/>\n      <param name=\"update_min_a\"              value=\"0.2\"/>\n      <param name=\"odom_frame_id\"             value=\"$(arg odom_frame_id)\"/>\n      <param name=\"base_frame_id\"             value=\"$(arg base_frame_id)\"/>\n      <param name=\"global_frame_id\"           value=\"$(arg global_frame_id)\"/>\n      <param name=\"resample_interval\"         value=\"1\"/>\n      <param name=\"transform_tolerance\"       value=\"0.2\"/>\n      <param name=\"recovery_alpha_slow\"       value=\"0.0\"/>\n      <param name=\"recovery_alpha_fast\"       value=\"0.0\"/>\n      <param name=\"initial_pose_x\"            value=\"$(arg initial_pose_x)\"/>\n      <param name=\"initial_pose_y\"            value=\"$(arg initial_pose_y)\"/>\n      <param name=\"initial_pose_a\"            value=\"$(arg initial_pose_a)\"/>\n      <remap from=\"scan\"                      to=\"$(arg scan_topic)\"/>\n      <remap from=\"map\"                       to=\"$(arg map_topic)\"/>\n      <remap from=\"static_map\"                to=\"$(arg map_service)\"/>\n    </node>\n  </group>\n\n  <!-- Duplicate of the above in case namespace is empty. This is necessary to\n       avoid the \"<group> tag has an empty 'ns' attribute\" parsing error. -->\n  <group unless=\"$(eval namespace != '')\">\n    <node pkg=\"amcl\" type=\"amcl\" name=\"amcl\" output=\"screen\" >\n      <param name=\"use_map_topic\"             value=\"$(arg use_map_topic)\"/>\n      <param name=\"odom_model_type\"           value=\"diff-corrected\"/>\n      <param name=\"gui_publish_rate\"          value=\"10.0\"/>\n      <param name=\"save_pose_rate\"            value=\"0.5\"/>\n      <param name=\"laser_max_beams\"           value=\"50\"/>\n      <param name=\"laser_min_range\"           value=\"-1.0\"/>\n      <param name=\"laser_max_range\"           value=\"-1.0\"/>\n      <param name=\"min_particles\"             value=\"500\"/>\n      <param name=\"max_particles\"             value=\"5000\"/>\n      <param name=\"kld_err\"                   value=\"0.05\"/>\n      <param name=\"kld_z\"                     value=\"0.99\"/>\n      <param name=\"odom_alpha1\"               value=\"0.02\"/>\n      <param name=\"odom_alpha2\"               value=\"0.01\"/>\n      <param name=\"odom_alpha3\"               value=\"0.01\"/>\n      <param name=\"odom_alpha4\"               value=\"0.02\"/>\n      <param name=\"laser_z_hit\"               value=\"0.5\"/>\n      <param name=\"laser_z_short\"             value=\"0.05\"/>\n      <param name=\"laser_z_max\"               value=\"0.05\"/>\n      <param name=\"laser_z_rand\"              value=\"0.5\"/>\n      <param name=\"laser_sigma_hit\"           value=\"0.2\"/>\n      <param name=\"laser_lambda_short\"        value=\"0.1\"/>\n      <param name=\"laser_model_type\"          value=\"likelihood_field\"/>\n      <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n      <param name=\"update_min_d\"              value=\"0.2\"/>\n      <param name=\"update_min_a\"              value=\"0.2\"/>\n      <param name=\"odom_frame_id\"             value=\"$(arg odom_frame_id)\"/>\n      <param name=\"base_frame_id\"             value=\"$(arg base_frame_id)\"/>\n      <param name=\"global_frame_id\"           value=\"$(arg global_frame_id)\"/>\n      <param name=\"resample_interval\"         value=\"1\"/>\n      <param name=\"transform_tolerance\"       value=\"0.2\"/>\n      <param name=\"recovery_alpha_slow\"       value=\"0.0\"/>\n      <param name=\"recovery_alpha_fast\"       value=\"0.0\"/>\n      <param name=\"initial_pose_x\"            value=\"$(arg initial_pose_x)\"/>\n      <param name=\"initial_pose_y\"            value=\"$(arg initial_pose_y)\"/>\n      <param name=\"initial_pose_a\"            value=\"$(arg initial_pose_a)\"/>\n      <remap from=\"scan\"                      to=\"$(arg scan_topic)\"/>\n      <remap from=\"map\"                       to=\"$(arg map_topic)\"/>\n      <remap from=\"static_map\"                to=\"$(arg map_service)\"/>\n    </node>\n  </group>\n</launch>\n"
  },
  {
    "path": "mir_navigation/launch/hector_mapping.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"tf_map_scanmatch_transform_frame_name\" default=\"scanmatcher_frame\"/>\n  <arg name=\"base_frame\" default=\"base_footprint\"/>\n  <arg name=\"odom_frame\" default=\"odom\"/>\n  <arg name=\"pub_map_odom_transform\" default=\"true\"/>\n  <arg name=\"scan_subscriber_queue_size\" default=\"5\"/>\n  <arg name=\"scan_topic\" default=\"scan\"/>\n  <arg name=\"map_size\" default=\"2048\"/>\n    <!-- set use_tf_pose_start_estimate and map_with_known_poses to `true` when\n         the map-base_footprint transform is provided by a different node, such\n         as fake_localization -->\n  <arg name=\"disable_localization\" default=\"false\"/>\n\n  <node pkg=\"hector_mapping\" type=\"hector_mapping\" name=\"hector_mapping\" output=\"screen\">\n\n    <!-- Frame names -->\n    <param name=\"map_frame\" value=\"map\" />\n    <param name=\"base_frame\" value=\"$(arg base_frame)\" />\n    <param name=\"odom_frame\" value=\"$(arg odom_frame)\" />\n\n    <!-- Tf use -->\n    <param name=\"use_tf_scan_transformation\" value=\"true\"/>\n    <param name=\"use_tf_pose_start_estimate\" value=\"$(arg disable_localization)\"/>\n    <param name=\"map_with_known_poses\" value=\"$(arg disable_localization)\" />\n    <param name=\"pub_map_odom_transform\" value=\"$(arg pub_map_odom_transform)\"/>\n    <param name=\"pub_map_scanmatch_transform\" value=\"true\" />\n\n    <!-- Map size / start point -->\n    <param name=\"map_resolution\" value=\"0.050\"/>\n    <param name=\"map_size\" value=\"$(arg map_size)\"/>\n    <param name=\"map_start_x\" value=\"0.5\"/>\n    <param name=\"map_start_y\" value=\"0.5\" />\n    <param name=\"map_multi_res_levels\" value=\"3\" />\n    <param name=\"map_pub_period\" value =\"2.0\" />\n\n    <!-- Map update parameters -->\n    <param name=\"update_factor_free\" value=\"0.4\"/>\n    <param name=\"update_factor_occupied\" value=\"0.9\" />\n    <param name=\"map_update_distance_thresh\" value=\"0.4\"/>\n    <param name=\"map_update_angle_thresh\" value=\"0.06\" />\n    <param name=\"laser_min_dist\" value=\"0.4\" />\n    <param name=\"laser_max_dist\" value=\"30.0\" />\n    <param name=\"laser_z_min_value\" value=\"-1.0\" />\n    <param name=\"laser_z_max_value\" value=\"1.0\" />\n\n    <!-- Advertising config -->\n    <param name=\"advertise_map_service\" value=\"true\"/>\n\n    <param name=\"scan_subscriber_queue_size\" value=\"$(arg scan_subscriber_queue_size)\"/>\n    <param name=\"scan_topic\" value=\"$(arg scan_topic)\"/>\n    <param name=\"pose_update_topic\" value=\"poseupdate\" />\n    <param name=\"sys_msg_topic\" value=\"syscommand\" />\n    <param name=\"pub_odometry\" value=\"false\" />\n\n    <!-- Debug parameters -->\n    <!--\n      <param name=\"output_timing\" value=\"false\"/>\n      <param name=\"pub_drawings\" value=\"true\"/>\n      <param name=\"pub_debug_output\" value=\"true\"/>\n    -->\n    <param name=\"tf_map_scanmatch_transform_frame_name\" value=\"$(arg tf_map_scanmatch_transform_frame_name)\" />\n\n    <remap from=\"map\" to=\"/map\" />\n  </node>\n\n  <!--<node pkg=\"tf\" type=\"static_transform_publisher\" name=\"map_nav_broadcaster\" args=\"0 0 0 0 0 0 map nav 100\"/>-->\n</launch>\n"
  },
  {
    "path": "mir_navigation/launch/move_base.xml",
    "content": "<launch>\n    <!--node ns=\"local_costmap\" name=\"voxel_grid_throttle\" pkg=\"topic_tools\" type=\"throttle\" args=\"messages voxel_grid 3.0 voxel_grid_throttled\" /-->\n    <arg name=\"local_planner\" default=\"dwb\" doc=\"Local planner can be either dwa, base, teb or pose\"/>\n    <arg name=\"with_virtual_walls\" default=\"true\" doc=\"Enables usage of virtual walls when set. Set to false when running SLAM.\" />\n    <arg name=\"prefix\" default=\"\" doc=\"Prefix used for robot tf frames\" /> <!-- used in the config files -->\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base_node\" output=\"screen\" clear_params=\"true\">\n        <param name=\"SBPLLatticePlanner/primitive_filename\" value=\"$(find mir_navigation)/mprim/unicycle_highcost_5cm.mprim\" />\n        <rosparam file=\"$(find mir_navigation)/config/move_base_common_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find mir_navigation)/config/sbpl_global_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find mir_navigation)/config/$(arg local_planner)_local_planner_params.yaml\" command=\"load\" />\n        <!-- global costmap params -->\n        <rosparam file=\"$(find mir_navigation)/config/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" subst_value=\"true\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_global_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_global_params_plugins_virtual_walls.yaml\" command=\"load\" if=\"$(arg with_virtual_walls)\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_global_params_plugins_no_virtual_walls.yaml\" command=\"load\" unless=\"$(arg with_virtual_walls)\" />\n        <!-- local costmap params -->\n        <rosparam file=\"$(find mir_navigation)/config/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" subst_value=\"true\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_local_params.yaml\" command=\"load\" subst_value=\"true\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_local_params_plugins_virtual_walls.yaml\" command=\"load\" if=\"$(arg with_virtual_walls)\" />\n        <rosparam file=\"$(find mir_navigation)/config/costmap_local_params_plugins_no_virtual_walls.yaml\" command=\"load\" unless=\"$(arg with_virtual_walls)\" />\n        <remap from=\"map\" to=\"/map\" />\n        <remap from=\"marker\" to=\"move_base_node/DWBLocalPlanner/markers\" />\n    </node>\n</launch>\n"
  },
  {
    "path": "mir_navigation/launch/start_maps.launch",
    "content": "<launch>\n  <arg name=\"map_file\" default=\"$(find mir_gazebo)/maps/maze.yaml\" doc=\"Path to a map .yaml file (required).\" />\n  <arg name=\"virtual_walls_map_file\" default=\"$(arg map_file)\" doc=\"Path to a virtual walls map .yaml file (optional).\" />\n  <arg name=\"with_virtual_walls\" default=\"true\" />\n\n  <node name=\"static_map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(arg map_file)\" ns=\"/\" output=\"screen\">\n    <param name=\"frame_id\" type=\"string\" value=\"map\"/>\n  </node>\n\n  <node if=\"$(arg with_virtual_walls)\" name=\"virtual_walls_map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(arg virtual_walls_map_file)\" ns=\"/virtual_walls\" output=\"screen\">\n    <param name=\"frame_id\" type=\"string\" value=\"map\"/>\n  </node>\n</launch>\n"
  },
  {
    "path": "mir_navigation/launch/start_planner.launch",
    "content": "<launch>\n  <arg name=\"local_planner\"          default=\"dwb\"             doc=\"Local planner can be either dwa, dwb, eband, base, teb or pose\" />\n  <arg name=\"map_file\" default=\"$(find mir_gazebo)/maps/maze.yaml\" doc=\"Path to a map .yaml file (required).\" />\n  <arg name=\"virtual_walls_map_file\" default=\"$(arg map_file)\" doc=\"Path to a virtual walls map .yaml file (optional).\" />\n  <arg name=\"with_virtual_walls\" default=\"true\" />\n  <arg name=\"prefix\" default=\"\" />\n  <arg name=\"namespace\" default=\"$(arg prefix)\" doc=\"Namespace to push all topics into.\"/>\n\n  <group if=\"$(eval namespace != '')\" ns=\"$(arg namespace)\">\n    <include file=\"$(find mir_navigation)/launch/start_maps.launch\">\n      <arg name=\"map_file\" value=\"$(arg map_file)\" />\n      <arg name=\"virtual_walls_map_file\" value=\"$(arg virtual_walls_map_file)\" />\n      <arg name=\"with_virtual_walls\" value=\"$(arg with_virtual_walls)\" />\n    </include>\n\n    <include file=\"$(find mir_navigation)/launch/move_base.xml\">\n      <arg name=\"local_planner\" value=\"$(arg local_planner)\"/>\n      <arg name=\"with_virtual_walls\" value=\"$(arg with_virtual_walls)\" />\n      <arg name=\"prefix\" value=\"$(arg prefix)\" />\n    </include>\n  </group>\n\n  <!-- Duplicate of the above in case namespace is empty. This is necessary to\n       avoid the \"<group> tag has an empty 'ns' attribute\" parsing error. -->\n  <group unless=\"$(eval namespace != '')\">\n    <include file=\"$(find mir_navigation)/launch/start_maps.launch\">\n      <arg name=\"map_file\" value=\"$(arg map_file)\" />\n      <arg name=\"virtual_walls_map_file\" value=\"$(arg virtual_walls_map_file)\" />\n      <arg name=\"with_virtual_walls\" value=\"$(arg with_virtual_walls)\" />\n    </include>\n\n    <include file=\"$(find mir_navigation)/launch/move_base.xml\">\n      <arg name=\"local_planner\" value=\"$(arg local_planner)\"/>\n      <arg name=\"with_virtual_walls\" value=\"$(arg with_virtual_walls)\" />\n      <arg name=\"prefix\" value=\"$(arg prefix)\" />\n    </include>\n  </group>\n</launch>\n"
  },
  {
    "path": "mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m",
    "content": "% /*\n%  * Copyright (c) 2008, Maxim Likhachev\n%  * All rights reserved.\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%  *     * 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%  *     * Neither the name of the Carnegie Mellon University 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 OWNER 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\nfunction[] = genmprim_unicycle_highcost_5cm(outfilename)\n\n%\n%generates motion primitives and saves them into file\n%\n%written by Maxim Likhachev\n%---------------------------------------------------\n%\n\n%defines\n\nUNICYCLE_MPRIM_16DEGS = 1;\n\n\nif UNICYCLE_MPRIM_16DEGS == 1\n    resolution = 0.05;\n    numberofangles = 16; %preferably a power of 2, definitely multiple of 8\n    numberofprimsperangle = 7;\n\n    %multipliers (multiplier is used as costmult*cost)\n    forwardcostmult = 1;\n    backwardcostmult = 40;\n    forwardandturncostmult = 2;\n    sidestepcostmult = 10;\n    turninplacecostmult = 20;\n\n    %note, what is shown x,y,theta changes (not absolute numbers)\n\n    %0 degreees\n    basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult\n    %x aligned with the heading of the robot, angles are positive\n    %counterclockwise\n    %0 theta change\n    basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult];\n    basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult];\n    basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult];\n    %1/16 theta change\n    basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult];\n    basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult];\n    %turn in place\n    basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult];\n    basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult];\n\n    %45 degrees\n    basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost)\n    %x aligned with the heading of the robot, angles are positive\n    %counterclockwise\n    %0 theta change\n    basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult];\n    basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult];\n    basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult];\n    %1/16 theta change\n    basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult];\n    basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult];\n    %turn in place\n    basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult];\n    basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult];\n\n    %22.5 degrees\n    basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost)\n    %x aligned with the heading of the robot, angles are positive\n    %counterclockwise\n    %0 theta change\n    basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult];\n    basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult];\n    basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult];\n    %1/16 theta change\n    basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult];\n    basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult];\n    %turn in place\n    basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult];\n    basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult];\n\nelse\n    fprintf(1, 'ERROR: undefined mprims type\\n');\n    return;\nend;\n\n\nfout = fopen(outfilename, 'w');\n\n\n%write the header\nfprintf(fout, 'resolution_m: %f\\n', resolution);\nfprintf(fout, 'numberofangles: %d\\n', numberofangles);\nfprintf(fout, 'totalnumberofprimitives: %d\\n', numberofprimsperangle*numberofangles);\n\n%iterate over angles\nfor angleind = 1:numberofangles\n\n    figure(1);\n    hold off;\n\n    text(0, 0, int2str(angleind));\n\n    %iterate over primitives\n    for primind = 1:numberofprimsperangle\n        fprintf(fout, 'primID: %d\\n', primind-1);\n        fprintf(fout, 'startangle_c: %d\\n', angleind-1);\n\n        %current angle\n        currentangle = (angleind-1)*2*pi/numberofangles;\n        currentangle_36000int = round((angleind-1)*36000/numberofangles);\n\n        %compute which template to use\n        if (rem(currentangle_36000int, 9000) == 0)\n            basemprimendpts_c = basemprimendpts0_c(primind,:);\n            angle = currentangle;\n        elseif (rem(currentangle_36000int, 4500) == 0)\n            basemprimendpts_c = basemprimendpts45_c(primind,:);\n            angle = currentangle - 45*pi/180;\n        elseif (rem(currentangle_36000int-7875, 9000) == 0)\n            basemprimendpts_c = basemprimendpts33p75_c(primind,:);\n            basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y\n            basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1);\n            basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well\n            angle = currentangle - 78.75*pi/180;\n            fprintf(1, '78p75\\n');\n        elseif (rem(currentangle_36000int-6750, 9000) == 0)\n            basemprimendpts_c = basemprimendpts22p5_c(primind,:);\n            basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y\n            basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1);\n            basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well\n            %fprintf(1, '%d %d %d onto %d %d %d\\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ...\n            %    basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3));\n            angle = currentangle - 67.5*pi/180;\n            fprintf(1, '67p5\\n');\n        elseif (rem(currentangle_36000int-5625, 9000) == 0)\n            basemprimendpts_c = basemprimendpts11p25_c(primind,:);\n            basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y\n            basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1);\n            basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well\n            angle = currentangle - 56.25*pi/180;\n            fprintf(1, '56p25\\n');\n        elseif (rem(currentangle_36000int-3375, 9000) == 0)\n            basemprimendpts_c = basemprimendpts33p75_c(primind,:);\n            angle = currentangle - 33.75*pi/180;\n            fprintf(1, '33p75\\n');\n        elseif (rem(currentangle_36000int-2250, 9000) == 0)\n            basemprimendpts_c = basemprimendpts22p5_c(primind,:);\n            angle = currentangle - 22.5*pi/180;\n            fprintf(1, '22p5\\n');\n        elseif (rem(currentangle_36000int-1125, 9000) == 0)\n            basemprimendpts_c = basemprimendpts11p25_c(primind,:);\n            angle = currentangle - 11.25*pi/180;\n            fprintf(1, '11p25\\n');\n        else\n            fprintf(1, 'ERROR: invalid angular resolution. angle = %d\\n', currentangle_36000int);\n            return;\n        end;\n\n        %now figure out what action will be\n        baseendpose_c = basemprimendpts_c(1:3);\n        additionalactioncostmult = basemprimendpts_c(4);\n        endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle));\n        endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle));\n        endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles);\n        endpose_c = [endx_c endy_c endtheta_c];\n\n        fprintf(1, 'rotation angle=%f\\n', angle*180/pi);\n\n        if baseendpose_c(2) == 0 & baseendpose_c(3) == 0\n            %fprintf(1, 'endpose=%d %d %d\\n', endpose_c(1), endpose_c(2), endpose_c(3));\n        end;\n\n        %generate intermediate poses (remember they are w.r.t 0,0 (and not\n        %centers of the cells)\n        numofsamples = 10;\n        intermcells_m = zeros(numofsamples,3);\n        if UNICYCLE_MPRIM_16DEGS == 1\n            startpt = [0 0 currentangle];\n            endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ...\n                rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles];\n            intermcells_m = zeros(numofsamples,3);\n            if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward\n                for iind = 1:numofsamples\n                    intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ...\n                                            startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ...\n                                            0];\n                    rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles);\n                    intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi);\n\n                end;\n            else %unicycle-based move forward or backward\n                R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3));\n                    sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))];\n                S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)];\n                l = S(1);\n                tvoverrv = S(2);\n                rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv);\n                tv = tvoverrv*rv;\n\n                if l < 0\n                    fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\\n', l);\n                    l = 0;\n                end;\n                %compute rv\n                %rv = baseendpose_c(3)*2*pi/numberofangles;\n                %compute tv\n                %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3)))\n                %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3)))\n                %tv = (tvx + tvy)/2.0;\n                %generate samples\n                for iind = 1:numofsamples\n                    dt = (iind-1)/(numofsamples-1);\n\n                    %dtheta = rv*dt + startpt(3);\n                    %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ...\n                    %                        startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ...\n                    %                        dtheta];\n\n                    if(dt*tv < l)\n                        intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ...\n                                                 startpt(2) + dt*tv*sin(startpt(3)) ...\n                                                 startpt(3)];\n                    else\n                        dtheta = rv*(dt - l/tv) + startpt(3);\n                        intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ...\n                                                 startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ...\n                                                 dtheta];\n                    end;\n                end;\n                %correct\n                errorxy = [endpt(1) - intermcells_m(numofsamples,1) ...\n                           endpt(2) - intermcells_m(numofsamples,2)];\n                fprintf(1, 'l=%f errx=%f erry=%f\\n', l, errorxy(1), errorxy(2));\n                interpfactor = [0:1/(numofsamples-1):1];\n                intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor';\n                intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor';\n            end;\n        end;\n\n        %write out\n        fprintf(fout, 'endpose_c: %d %d %d\\n', endpose_c(1), endpose_c(2), endpose_c(3));\n        fprintf(fout, 'additionalactioncostmult: %d\\n', additionalactioncostmult);\n        fprintf(fout, 'intermediateposes: %d\\n', size(intermcells_m,1));\n        for interind = 1:size(intermcells_m, 1)\n            fprintf(fout, '%.4f %.4f %.4f\\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3));\n        end;\n\n        plot(intermcells_m(:,1), intermcells_m(:,2));\n        axis([-0.3 0.3 -0.3 0.3]);\n        text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3)));\n        hold on;\n\n    end;\n    grid;\n    pause;\nend;\n\nfclose('all');\n"
  },
  {
    "path": "mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py",
    "content": "#!/usr/bin/env python3\n#\n# Copyright (c) 2016, David Conner (Christopher Newport University)\n# Based on genmprim_unicycle.m\n# Copyright (c) 2008, Maxim Likhachev\n# All rights reserved.\n# converted by libermate utility (https://github.com/awesomebytes/libermate)\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#     * 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#     * Neither the name of the Carnegie Mellon University 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 OWNER 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\nimport numpy as np\nimport rospkg\n\n# if available import pylab (from matlibplot)\nmatplotlib_found = False\ntry:\n    import matplotlib.pylab as plt\n\n    matplotlib_found = True\nexcept ImportError:\n    pass\n\n\ndef matrix_size(mat, elem=None):\n    if not elem:\n        return mat.shape\n    else:\n        return mat.shape[int(elem) - 1]\n\n\ndef genmprim_unicycle(outfilename, visualize=False, separate_plots=False):\n    visualize = matplotlib_found and visualize  # Plot the primitives\n\n    # Local Variables: basemprimendpts22p5_c, endtheta_c, endx_c,\n    #   baseendpose_c, additionalactioncostmult, fout, numofsamples,\n    #   basemprimendpts45_c, primind, basemprimendpts0_c, rv, angle, outfilename,\n    #   numberofangles, startpt, UNICYCLE_MPRIM_16DEGS, sidestepcostmult,\n    #   rotation_angle, basemprimendpts_c, forwardandturncostmult,\n    #   forwardcostmult, turninplacecostmult, endpose_c, backwardcostmult,\n    #   interpfactor, S, R, tvoverrv, dtheta, intermcells_m, tv, dt,\n    #   currentangle, numberofprimsperangle, resolution, currentangle_36000int,\n    #   l, iind, errorxy, interind, endy_c, angleind, endpt\n    # Function calls: plot, cos, pi, grid, figure, genmprim_unicycle, text,\n    #   int2str, pause, axis, sin, pinv, fprintf, fclose, rem, zeros, fopen,\n    #   round, size\n    # %\n    # %generates motion primitives and saves them into file\n    # %\n    # %written by Maxim Likhachev\n    # %---------------------------------------------------\n    # %\n    # %defines\n    UNICYCLE_MPRIM_16DEGS = 1.0\n    if UNICYCLE_MPRIM_16DEGS == 1.0:\n        resolution = 0.05\n        numberofangles = 16\n        # %preferably a power of 2, definitely multiple of 8\n        numberofprimsperangle = 7\n        # %multipliers (multiplier is used as costmult*cost)\n        forwardcostmult = 1.0\n        backwardcostmult = 40.0\n        forwardandturncostmult = 2.0\n        # sidestepcostmult = 10.0\n        turninplacecostmult = 20.0\n        # %note, what is shown x,y,theta changes (not absolute numbers)\n        # %0 degreees\n        basemprimendpts0_c = np.zeros((numberofprimsperangle, 4))\n        # %x,y,theta,costmult\n        # %x aligned with the heading of the robot, angles are positive\n        # %counterclockwise\n        # %0 theta change\n        basemprimendpts0_c[0, :] = np.array(np.hstack((1.0, 0.0, 0.0, forwardcostmult)))\n        basemprimendpts0_c[1, :] = np.array(np.hstack((8.0, 0.0, 0.0, forwardcostmult)))\n        basemprimendpts0_c[2, :] = np.array(np.hstack((-1.0, 0.0, 0.0, backwardcostmult)))\n        # %1/16 theta change\n        basemprimendpts0_c[3, :] = np.array(np.hstack((8.0, 1.0, 1.0, forwardandturncostmult)))\n        basemprimendpts0_c[4, :] = np.array(np.hstack((8.0, -1.0, -1.0, forwardandturncostmult)))\n        # %turn in place\n        basemprimendpts0_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult)))\n        basemprimendpts0_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult)))\n        # %45 degrees\n        basemprimendpts45_c = np.zeros((numberofprimsperangle, 4))\n        # %x,y,theta,costmult (multiplier is used as costmult*cost)\n        # %x aligned with the heading of the robot, angles are positive\n        # %counterclockwise\n        # %0 theta change\n        basemprimendpts45_c[0, :] = np.array(np.hstack((1.0, 1.0, 0.0, forwardcostmult)))\n        basemprimendpts45_c[1, :] = np.array(np.hstack((6.0, 6.0, 0.0, forwardcostmult)))\n        basemprimendpts45_c[2, :] = np.array(np.hstack((-1.0, -1.0, 0.0, backwardcostmult)))\n        # %1/16 theta change\n        basemprimendpts45_c[3, :] = np.array(np.hstack((5.0, 7.0, 1.0, forwardandturncostmult)))\n        basemprimendpts45_c[4, :] = np.array(np.hstack((7.0, 5.0, -1.0, forwardandturncostmult)))\n        # %turn in place\n        basemprimendpts45_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult)))\n        basemprimendpts45_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult)))\n        # %22.5 degrees\n        basemprimendpts22p5_c = np.zeros((numberofprimsperangle, 4))\n        # %x,y,theta,costmult (multiplier is used as costmult*cost)\n        # %x aligned with the heading of the robot, angles are positive\n        # %counterclockwise\n        # %0 theta change\n        basemprimendpts22p5_c[0, :] = np.array(np.hstack((2.0, 1.0, 0.0, forwardcostmult)))\n        basemprimendpts22p5_c[1, :] = np.array(np.hstack((6.0, 3.0, 0.0, forwardcostmult)))\n        basemprimendpts22p5_c[2, :] = np.array(np.hstack((-2.0, -1.0, 0.0, backwardcostmult)))\n        # %1/16 theta change\n        basemprimendpts22p5_c[3, :] = np.array(np.hstack((5.0, 4.0, 1.0, forwardandturncostmult)))\n        basemprimendpts22p5_c[4, :] = np.array(np.hstack((7.0, 2.0, -1.0, forwardandturncostmult)))\n        # %turn in place\n        basemprimendpts22p5_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult)))\n        basemprimendpts22p5_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult)))\n    else:\n        print('ERROR: undefined mprims type\\n')\n        return []\n\n    fout = open(outfilename, 'w')\n    # %write the header\n    fout.write('resolution_m: %f\\n' % (resolution))\n    fout.write('numberofangles: %d\\n' % (numberofangles))\n    fout.write('totalnumberofprimitives: %d\\n' % (numberofprimsperangle * numberofangles))\n    # %iterate over angles\n    for angleind in np.arange(1.0, (numberofangles) + 1):\n        currentangle = ((angleind - 1) * 2.0 * np.pi) / numberofangles\n        currentangle_36000int = np.round((angleind - 1) * 36000.0 / numberofangles)\n        if visualize:\n            if separate_plots:\n                fig = plt.figure(angleind)\n                plt.title('angle {:2.0f} (= {:3.1f} degrees)'.format(angleind - 1, currentangle_36000int / 100.0))\n            else:\n                fig = plt.figure(1)\n\n            plt.axis('equal')\n            plt.axis([-10 * resolution, 10 * resolution, -10 * resolution, 10 * resolution])\n            ax = fig.add_subplot(1, 1, 1)\n            major_ticks = np.arange(-8 * resolution, 9 * resolution, 4 * resolution)\n            minor_ticks = np.arange(-8 * resolution, 9 * resolution, resolution)\n            ax.set_xticks(major_ticks)\n            ax.set_xticks(minor_ticks, minor=True)\n            ax.set_yticks(major_ticks)\n            ax.set_yticks(minor_ticks, minor=True)\n            ax.grid(which='minor', alpha=0.5)\n            ax.grid(which='major', alpha=0.9)\n\n        # %iterate over primitives\n        for primind in np.arange(1.0, (numberofprimsperangle) + 1):\n            fout.write('primID: %d\\n' % (primind - 1))\n            fout.write('startangle_c: %d\\n' % (angleind - 1))\n            # %current angle\n            # %compute which template to use\n            if (currentangle_36000int % 9000) == 0:\n                basemprimendpts_c = basemprimendpts0_c[int(primind) - 1, :]\n                angle = currentangle\n            elif (currentangle_36000int % 4500) == 0:\n                basemprimendpts_c = basemprimendpts45_c[int(primind) - 1, :]\n                angle = currentangle - 45.0 * np.pi / 180.0\n\n            # commented out because basemprimendpts33p75_c is undefined\n            # elif ((currentangle_36000int - 7875) % 9000) == 0:\n            #     basemprimendpts_c = (\n            #         1 * basemprimendpts33p75_c[primind, :]\n            #     )  # 1* to force deep copy to avoid reference update below\n            #     basemprimendpts_c[0] = basemprimendpts33p75_c[primind, 1]\n            #     # %reverse x and y\n            #     basemprimendpts_c[1] = basemprimendpts33p75_c[primind, 0]\n            #     basemprimendpts_c[2] = -basemprimendpts33p75_c[primind, 2]\n            #     # %reverse the angle as well\n            #     angle = currentangle - (78.75 * np.pi) / 180.0\n            #     print('78p75\\n')\n\n            elif ((currentangle_36000int - 6750) % 9000) == 0:\n                basemprimendpts_c = (\n                    1 * basemprimendpts22p5_c[int(primind) - 1, :]\n                )  # 1* to force deep copy to avoid reference update below\n                basemprimendpts_c[0] = basemprimendpts22p5_c[int(primind) - 1, 1]\n                # %reverse x and y\n                basemprimendpts_c[1] = basemprimendpts22p5_c[int(primind) - 1, 0]\n                basemprimendpts_c[2] = -basemprimendpts22p5_c[int(primind) - 1, 2]\n                # %reverse the angle as well\n                # print(\n                #     '%d : %d %d %d onto %d %d %d\\n'\n                #     % (\n                #         primind - 1,\n                #         basemprimendpts22p5_c[int(primind) - 1, 0],\n                #         basemprimendpts22p5_c[int(primind) - 1, 1],\n                #         basemprimendpts22p5_c[int(primind) - 1, 2],\n                #         basemprimendpts_c[0],\n                #         basemprimendpts_c[1],\n                #         basemprimendpts_c[2],\n                #     )\n                # )\n                angle = currentangle - (67.5 * np.pi) / 180.0\n                print('67p5\\n')\n\n            # commented out because basemprimendpts11p25_c is undefined\n            # elif ((currentangle_36000int - 5625) % 9000) == 0:\n            #     basemprimendpts_c = (\n            #         1 * basemprimendpts11p25_c[primind, :]\n            #     )  # 1* to force deep copy to avoid reference update below\n            #     basemprimendpts_c[0] = basemprimendpts11p25_c[primind, 1]\n            #     # %reverse x and y\n            #     basemprimendpts_c[1] = basemprimendpts11p25_c[primind, 0]\n            #     basemprimendpts_c[2] = -basemprimendpts11p25_c[primind, 2]\n            #     # %reverse the angle as well\n            #     angle = currentangle - (56.25 * np.pi) / 180.0\n            #     print('56p25\\n')\n\n            # commented out because basemprimendpts33p75_c is undefined\n            # elif ((currentangle_36000int - 3375) % 9000) == 0:\n            #     basemprimendpts_c = basemprimendpts33p75_c[int(primind), :]\n            #     angle = currentangle - (33.75 * np.pi) / 180.0\n            #     print('33p75\\n')\n\n            elif ((currentangle_36000int - 2250) % 9000) == 0:\n                basemprimendpts_c = basemprimendpts22p5_c[int(primind) - 1, :]\n                angle = currentangle - (22.5 * np.pi) / 180.0\n                print('22p5\\n')\n\n            # commented out because basemprimendpts11p25_c is undefined\n            # elif ((currentangle_36000int - 1125) % 9000) == 0:\n            #     basemprimendpts_c = basemprimendpts11p25_c[int(primind), :]\n            #     angle = currentangle - (11.25 * np.pi) / 180.0\n            #     print('11p25\\n')\n\n            else:\n                print('ERROR: invalid angular resolution. angle = %d\\n' % currentangle_36000int)\n                return []\n\n            # %now figure out what action will be\n            baseendpose_c = basemprimendpts_c[0:3]\n            additionalactioncostmult = basemprimendpts_c[3]\n            endx_c = np.round((baseendpose_c[0] * np.cos(angle)) - (baseendpose_c[1] * np.sin(angle)))\n            endy_c = np.round((baseendpose_c[0] * np.sin(angle)) + (baseendpose_c[1] * np.cos(angle)))\n            endtheta_c = np.fmod(angleind - 1 + baseendpose_c[2], numberofangles)\n            endpose_c = np.array(np.hstack((endx_c, endy_c, endtheta_c)))\n            print(\"endpose_c=\", endpose_c)\n            print(('rotation angle=%f\\n' % (angle * 180.0 / np.pi)))\n            # if np.logical_and(baseendpose_c[1] == 0., baseendpose_c[2] == 0.):\n            # %fprintf(1, 'endpose=%d %d %d\\n', endpose_c(1), endpose_c(2), endpose_c(3));\n\n            # %generate intermediate poses (remember they are w.r.t 0,0 (and not\n            # %centers of the cells)\n            numofsamples = 10\n            intermcells_m = np.zeros((numofsamples, 3))\n            if UNICYCLE_MPRIM_16DEGS == 1.0:\n                startpt = np.array(np.hstack((0.0, 0.0, currentangle)))\n                endpt = np.array(\n                    np.hstack(\n                        (\n                            (endpose_c[0] * resolution),\n                            (endpose_c[1] * resolution),\n                            (\n                                ((np.fmod(angleind - 1 + baseendpose_c[2], numberofangles)) * 2.0 * np.pi)\n                                / numberofangles\n                            ),\n                        )\n                    )\n                )\n\n                print(\"startpt =\", startpt)\n                print(\"endpt   =\", endpt)\n                intermcells_m = np.zeros((numofsamples, 3))\n                if np.logical_or(np.logical_and(endx_c == 0.0, endy_c == 0.0), baseendpose_c[2] == 0.0):\n                    # %turn in place or move forward\n                    for iind in np.arange(1.0, (numofsamples) + 1):\n                        fraction = float(iind - 1) / (numofsamples - 1)\n                        intermcells_m[int(iind) - 1, :] = np.array(\n                            (\n                                startpt[0] + (endpt[0] - startpt[0]) * fraction,\n                                startpt[1] + (endpt[1] - startpt[1]) * fraction,\n                                0,\n                            )\n                        )\n                        rotation_angle = baseendpose_c[2] * (2.0 * np.pi / numberofangles)\n                        intermcells_m[int(iind) - 1, 2] = np.fmod(startpt[2] + rotation_angle * fraction, (2.0 * np.pi))\n                        # print \" \",iind,\"  of \",numofsamples,\" fraction=\",fraction,\" rotation=\",rotation_angle\n\n                else:\n                    # %unicycle-based move forward or backward  (http://sbpl.net/node/53)\n                    R = np.array(\n                        np.vstack(\n                            (\n                                np.hstack((np.cos(startpt[2]), np.sin(endpt[2]) - np.sin(startpt[2]))),\n                                np.hstack((np.sin(startpt[2]), -np.cos(endpt[2]) + np.cos(startpt[2]))),\n                            )\n                        )\n                    )\n\n                    S = np.dot(np.linalg.pinv(R), np.array(np.vstack((endpt[0] - startpt[0], endpt[1] - startpt[1]))))\n                    l = S[0]\n                    tvoverrv = S[1]\n                    rv = (baseendpose_c[2] * 2.0 * np.pi / numberofangles) + l / tvoverrv\n                    tv = tvoverrv * rv\n\n                    # print \"R=\\n\",R\n                    # print \"Rpi=\\n\",np.linalg.pinv(R)\n                    # print \"S=\\n\",S\n                    # print \"l=\",l\n                    # print \"tvoverrv=\",tvoverrv\n                    # print \"rv=\",rv\n                    # print \"tv=\",tv\n\n                    if l < 0.0:\n                        print(('WARNING: l = %f < 0 -> bad action start/end points\\n' % (l)))\n                        l = 0.0\n\n                    # %compute rv\n                    # %rv = baseendpose_c(3)*2*pi/numberofangles;\n                    # %compute tv\n                    # %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3)))\n                    # %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3)))\n                    # %tv = (tvx + tvy)/2.0;\n                    # %generate samples\n                    for iind in np.arange(1, numofsamples + 1):\n                        dt = (iind - 1) / (numofsamples - 1)\n                        # %dtheta = rv*dt + startpt(3);\n                        # %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ...\n                        # %                        startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ...\n                        # %                        dtheta];\n                        if (dt * tv) < l:\n                            intermcells_m[int(iind) - 1, :] = np.array(\n                                np.hstack(\n                                    (\n                                        startpt[0] + dt * tv * np.cos(startpt[2]),\n                                        startpt[1] + dt * tv * np.sin(startpt[2]),\n                                        startpt[2],\n                                    )\n                                )\n                            )\n                        else:\n                            dtheta = rv * (dt - l / tv) + startpt[2]\n                            intermcells_m[int(iind) - 1, :] = np.array(\n                                np.hstack(\n                                    (\n                                        startpt[0]\n                                        + l * np.cos(startpt[2])\n                                        + tvoverrv * (np.sin(dtheta) - np.sin(startpt[2])),\n                                        startpt[1]\n                                        + l * np.sin(startpt[2])\n                                        - tvoverrv * (np.cos(dtheta) - np.cos(startpt[2])),\n                                        dtheta,\n                                    )\n                                )\n                            )\n\n                    # %correct\n                    errorxy = np.array(\n                        np.hstack(\n                            (\n                                endpt[0] - intermcells_m[int(numofsamples) - 1, 0],\n                                endpt[1] - intermcells_m[int(numofsamples) - 1, 1],\n                            )\n                        )\n                    )\n                    # print('l=%f errx=%f erry=%f\\n'%(l, errorxy[0], errorxy[1]))\n                    interpfactor = np.array(\n                        np.hstack((np.arange(0.0, 1.0 + (1.0 / (numofsamples)), 1.0 / (numofsamples - 1))))\n                    )\n\n                    # print \"intermcells_m=\",intermcells_m\n                    # print \"interp'=\",interpfactor.conj().T\n\n                    intermcells_m[:, 0] = intermcells_m[:, 0] + errorxy[0] * interpfactor.conj().T\n                    intermcells_m[:, 1] = intermcells_m[:, 1] + errorxy[1] * interpfactor.conj().T\n\n            # %write out\n            fout.write('endpose_c: %d %d %d\\n' % (endpose_c[0], endpose_c[1], endpose_c[2]))\n            fout.write('additionalactioncostmult: %d\\n' % (additionalactioncostmult))\n            fout.write('intermediateposes: %d\\n' % (matrix_size(intermcells_m, 1.0)))\n            for interind in np.arange(1.0, (matrix_size(intermcells_m, 1.0)) + 1):\n                fout.write(\n                    '%.4f %.4f %.4f\\n'\n                    % (\n                        intermcells_m[int(interind) - 1, 0],\n                        intermcells_m[int(interind) - 1, 1],\n                        intermcells_m[int(interind) - 1, 2],\n                    )\n                )\n\n            if visualize:\n                plt.plot(intermcells_m[:, 0], intermcells_m[:, 1], linestyle=\"-\", marker=\"o\")\n                plt.text(endpt[0], endpt[1], '{:2.0f}'.format(endpose_c[2]))\n        # if (visualize):\n        #    plt.waitforbuttonpress()  # uncomment to plot each primitive set one at a time\n\n    fout.close()\n    if visualize:\n        #    plt.waitforbuttonpress()  # hold until buttom pressed\n        plt.show()  # Keep windows open until the program is terminated\n    return []\n\n\nif __name__ == \"__main__\":\n    rospack = rospkg.RosPack()\n    outfilename = rospack.get_path('mir_navigation') + '/mprim/unicycle_highcost_5cm.mprim'\n    genmprim_unicycle(outfilename, visualize=True)\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm.mprim",
    "content": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 80\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0278 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0389 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0500 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 8 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0167 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0278 0.0000 0.0000\n-0.0333 0.0000 0.0000\n-0.0389 0.0000 0.0000\n-0.0444 0.0000 0.0000\n-0.0500 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 8 1 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 8 -1 -1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0111 0.0056 0.3927\n0.0222 0.0111 0.3927\n0.0333 0.0167 0.3927\n0.0444 0.0222 0.3927\n0.0556 0.0278 0.3927\n0.0667 0.0333 0.3927\n0.0778 0.0389 0.3927\n0.0889 0.0444 0.3927\n0.1000 0.0500 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0111 -0.0056 0.3927\n-0.0222 -0.0111 0.3927\n-0.0333 -0.0167 0.3927\n-0.0444 -0.0222 0.3927\n-0.0556 -0.0278 0.3927\n-0.0667 -0.0333 0.3927\n-0.0778 -0.0389 0.3927\n-0.0889 -0.0444 0.3927\n-0.1000 -0.0500 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 5 4 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 7 2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0056 0.0056 0.7854\n0.0111 0.0111 0.7854\n0.0167 0.0167 0.7854\n0.0222 0.0222 0.7854\n0.0278 0.0278 0.7854\n0.0333 0.0333 0.7854\n0.0389 0.0389 0.7854\n0.0444 0.0444 0.7854\n0.0500 0.0500 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 6 6 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0056 -0.0056 0.7854\n-0.0111 -0.0111 0.7854\n-0.0167 -0.0167 0.7854\n-0.0222 -0.0222 0.7854\n-0.0278 -0.0278 0.7854\n-0.0333 -0.0333 0.7854\n-0.0389 -0.0389 0.7854\n-0.0444 -0.0444 0.7854\n-0.0500 -0.0500 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 5 7 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 7 5 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0056 0.0111 1.1781\n0.0111 0.0222 1.1781\n0.0167 0.0333 1.1781\n0.0222 0.0444 1.1781\n0.0278 0.0556 1.1781\n0.0333 0.0667 1.1781\n0.0389 0.0778 1.1781\n0.0444 0.0889 1.1781\n0.0500 0.1000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0056 -0.0111 1.1781\n-0.0111 -0.0222 1.1781\n-0.0167 -0.0333 1.1781\n-0.0222 -0.0444 1.1781\n-0.0278 -0.0556 1.1781\n-0.0333 -0.0667 1.1781\n-0.0389 -0.0778 1.1781\n-0.0444 -0.0889 1.1781\n-0.0500 -0.1000 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 4 5 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0278 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0389 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0500 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 8 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0167 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0278 1.5708\n0.0000 -0.0333 1.5708\n0.0000 -0.0389 1.5708\n0.0000 -0.0444 1.5708\n0.0000 -0.0500 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -1 8 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 1 8 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0000 0.0452 1.5708\n-0.0000 0.0904 1.5708\n-0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0056 0.0111 1.9635\n-0.0111 0.0222 1.9635\n-0.0167 0.0333 1.9635\n-0.0222 0.0444 1.9635\n-0.0278 0.0556 1.9635\n-0.0333 0.0667 1.9635\n-0.0389 0.0778 1.9635\n-0.0444 0.0889 1.9635\n-0.0500 0.1000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0056 -0.0111 1.9635\n0.0111 -0.0222 1.9635\n0.0167 -0.0333 1.9635\n0.0222 -0.0444 1.9635\n0.0278 -0.0556 1.9635\n0.0333 -0.0667 1.9635\n0.0389 -0.0778 1.9635\n0.0444 -0.0889 1.9635\n0.0500 -0.1000 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -4 5 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0056 0.0056 2.3562\n-0.0111 0.0111 2.3562\n-0.0167 0.0167 2.3562\n-0.0222 0.0222 2.3562\n-0.0278 0.0278 2.3562\n-0.0333 0.0333 2.3562\n-0.0389 0.0389 2.3562\n-0.0444 0.0444 2.3562\n-0.0500 0.0500 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -6 6 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0056 -0.0056 2.3562\n0.0111 -0.0111 2.3562\n0.0167 -0.0167 2.3562\n0.0222 -0.0222 2.3562\n0.0278 -0.0278 2.3562\n0.0333 -0.0333 2.3562\n0.0389 -0.0389 2.3562\n0.0444 -0.0444 2.3562\n0.0500 -0.0500 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -7 5 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -5 7 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0111 0.0056 2.7489\n-0.0222 0.0111 2.7489\n-0.0333 0.0167 2.7489\n-0.0444 0.0222 2.7489\n-0.0556 0.0278 2.7489\n-0.0667 0.0333 2.7489\n-0.0778 0.0389 2.7489\n-0.0889 0.0444 2.7489\n-0.1000 0.0500 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0111 -0.0056 2.7489\n0.0222 -0.0111 2.7489\n0.0333 -0.0167 2.7489\n0.0444 -0.0222 2.7489\n0.0556 -0.0278 2.7489\n0.0667 -0.0333 2.7489\n0.0778 -0.0389 2.7489\n0.0889 -0.0444 2.7489\n0.1000 -0.0500 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -5 4 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -7 2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0278 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0389 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0500 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -8 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0167 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0278 0.0000 3.1416\n0.0333 0.0000 3.1416\n0.0389 0.0000 3.1416\n0.0444 0.0000 3.1416\n0.0500 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -8 -1 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -8 1 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0111 -0.0056 3.5343\n-0.0222 -0.0111 3.5343\n-0.0333 -0.0167 3.5343\n-0.0444 -0.0222 3.5343\n-0.0556 -0.0278 3.5343\n-0.0667 -0.0333 3.5343\n-0.0778 -0.0389 3.5343\n-0.0889 -0.0444 3.5343\n-0.1000 -0.0500 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0111 0.0056 3.5343\n0.0222 0.0111 3.5343\n0.0333 0.0167 3.5343\n0.0444 0.0222 3.5343\n0.0556 0.0278 3.5343\n0.0667 0.0333 3.5343\n0.0778 0.0389 3.5343\n0.0889 0.0444 3.5343\n0.1000 0.0500 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -5 -4 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -7 -2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0056 -0.0056 3.9270\n-0.0111 -0.0111 3.9270\n-0.0167 -0.0167 3.9270\n-0.0222 -0.0222 3.9270\n-0.0278 -0.0278 3.9270\n-0.0333 -0.0333 3.9270\n-0.0389 -0.0389 3.9270\n-0.0444 -0.0444 3.9270\n-0.0500 -0.0500 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -6 -6 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0056 0.0056 3.9270\n0.0111 0.0111 3.9270\n0.0167 0.0167 3.9270\n0.0222 0.0222 3.9270\n0.0278 0.0278 3.9270\n0.0333 0.0333 3.9270\n0.0389 0.0389 3.9270\n0.0444 0.0444 3.9270\n0.0500 0.0500 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -5 -7 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -7 -5 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0056 -0.0111 4.3197\n-0.0111 -0.0222 4.3197\n-0.0167 -0.0333 4.3197\n-0.0222 -0.0444 4.3197\n-0.0278 -0.0556 4.3197\n-0.0333 -0.0667 4.3197\n-0.0389 -0.0778 4.3197\n-0.0444 -0.0889 4.3197\n-0.0500 -0.1000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0056 0.0111 4.3197\n0.0111 0.0222 4.3197\n0.0167 0.0333 4.3197\n0.0222 0.0444 4.3197\n0.0278 0.0556 4.3197\n0.0333 0.0667 4.3197\n0.0389 0.0778 4.3197\n0.0444 0.0889 4.3197\n0.0500 0.1000 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -4 -5 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0278 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0389 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0500 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -8 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0167 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0278 4.7124\n0.0000 0.0333 4.7124\n0.0000 0.0389 4.7124\n0.0000 0.0444 4.7124\n0.0000 0.0500 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 1 -8 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -1 -8 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0056 -0.0111 5.1051\n0.0111 -0.0222 5.1051\n0.0167 -0.0333 5.1051\n0.0222 -0.0444 5.1051\n0.0278 -0.0556 5.1051\n0.0333 -0.0667 5.1051\n0.0389 -0.0778 5.1051\n0.0444 -0.0889 5.1051\n0.0500 -0.1000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0056 0.0111 5.1051\n-0.0111 0.0222 5.1051\n-0.0167 0.0333 5.1051\n-0.0222 0.0444 5.1051\n-0.0278 0.0556 5.1051\n-0.0333 0.0667 5.1051\n-0.0389 0.0778 5.1051\n-0.0444 0.0889 5.1051\n-0.0500 0.1000 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 4 -5 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0056 -0.0056 5.4978\n0.0111 -0.0111 5.4978\n0.0167 -0.0167 5.4978\n0.0222 -0.0222 5.4978\n0.0278 -0.0278 5.4978\n0.0333 -0.0333 5.4978\n0.0389 -0.0389 5.4978\n0.0444 -0.0444 5.4978\n0.0500 -0.0500 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 6 -6 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0056 0.0056 5.4978\n-0.0111 0.0111 5.4978\n-0.0167 0.0167 5.4978\n-0.0222 0.0222 5.4978\n-0.0278 0.0278 5.4978\n-0.0333 0.0333 5.4978\n-0.0389 0.0389 5.4978\n-0.0444 0.0444 5.4978\n-0.0500 0.0500 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 7 -5 15\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 5 -7 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0111 -0.0056 5.8905\n0.0222 -0.0111 5.8905\n0.0333 -0.0167 5.8905\n0.0444 -0.0222 5.8905\n0.0556 -0.0278 5.8905\n0.0667 -0.0333 5.8905\n0.0778 -0.0389 5.8905\n0.0889 -0.0444 5.8905\n0.1000 -0.0500 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0111 0.0056 5.8905\n-0.0222 0.0111 5.8905\n-0.0333 0.0167 5.8905\n-0.0444 0.0222 5.8905\n-0.0556 0.0278 5.8905\n-0.0667 0.0333 5.8905\n-0.0778 0.0389 5.8905\n-0.0889 0.0444 5.8905\n-0.1000 0.0500 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 5 -4 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 7 -2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim",
    "content": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0278 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0389 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0500 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 8 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0167 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0278 0.0000 0.0000\n-0.0333 0.0000 0.0000\n-0.0389 0.0000 0.0000\n-0.0444 0.0000 0.0000\n-0.0500 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 8 1 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 8 -1 -1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0111 0.0056 0.3927\n0.0222 0.0111 0.3927\n0.0333 0.0167 0.3927\n0.0444 0.0222 0.3927\n0.0556 0.0278 0.3927\n0.0667 0.0333 0.3927\n0.0778 0.0389 0.3927\n0.0889 0.0444 0.3927\n0.1000 0.0500 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0111 -0.0056 0.3927\n-0.0222 -0.0111 0.3927\n-0.0333 -0.0167 0.3927\n-0.0444 -0.0222 0.3927\n-0.0556 -0.0278 0.3927\n-0.0667 -0.0333 0.3927\n-0.0778 -0.0389 0.3927\n-0.0889 -0.0444 0.3927\n-0.1000 -0.0500 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 5 4 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 7 2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 -0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0056 0.0056 0.7854\n0.0111 0.0111 0.7854\n0.0167 0.0167 0.7854\n0.0222 0.0222 0.7854\n0.0278 0.0278 0.7854\n0.0333 0.0333 0.7854\n0.0389 0.0389 0.7854\n0.0444 0.0444 0.7854\n0.0500 0.0500 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 6 6 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0056 -0.0056 0.7854\n-0.0111 -0.0111 0.7854\n-0.0167 -0.0167 0.7854\n-0.0222 -0.0222 0.7854\n-0.0278 -0.0278 0.7854\n-0.0333 -0.0333 0.7854\n-0.0389 -0.0389 0.7854\n-0.0444 -0.0444 0.7854\n-0.0500 -0.0500 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 5 7 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 7 5 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0056 0.0111 1.1781\n0.0111 0.0222 1.1781\n0.0167 0.0333 1.1781\n0.0222 0.0444 1.1781\n0.0278 0.0556 1.1781\n0.0333 0.0667 1.1781\n0.0389 0.0778 1.1781\n0.0444 0.0889 1.1781\n0.0500 0.1000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0056 -0.0111 1.1781\n-0.0111 -0.0222 1.1781\n-0.0167 -0.0333 1.1781\n-0.0222 -0.0444 1.1781\n-0.0278 -0.0556 1.1781\n-0.0333 -0.0667 1.1781\n-0.0389 -0.0778 1.1781\n-0.0444 -0.0889 1.1781\n-0.0500 -0.1000 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 4 5 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0278 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0389 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0500 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 8 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0167 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0278 1.5708\n0.0000 -0.0333 1.5708\n0.0000 -0.0389 1.5708\n0.0000 -0.0444 1.5708\n0.0000 -0.0500 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -1 8 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 1 8 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0056 0.0111 1.9635\n-0.0111 0.0222 1.9635\n-0.0167 0.0333 1.9635\n-0.0222 0.0444 1.9635\n-0.0278 0.0556 1.9635\n-0.0333 0.0667 1.9635\n-0.0389 0.0778 1.9635\n-0.0444 0.0889 1.9635\n-0.0500 0.1000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0056 -0.0111 1.9635\n0.0111 -0.0222 1.9635\n0.0167 -0.0333 1.9635\n0.0222 -0.0444 1.9635\n0.0278 -0.0556 1.9635\n0.0333 -0.0667 1.9635\n0.0389 -0.0778 1.9635\n0.0444 -0.0889 1.9635\n0.0500 -0.1000 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -4 5 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0056 0.0056 2.3562\n-0.0111 0.0111 2.3562\n-0.0167 0.0167 2.3562\n-0.0222 0.0222 2.3562\n-0.0278 0.0278 2.3562\n-0.0333 0.0333 2.3562\n-0.0389 0.0389 2.3562\n-0.0444 0.0444 2.3562\n-0.0500 0.0500 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -6 6 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0056 -0.0056 2.3562\n0.0111 -0.0111 2.3562\n0.0167 -0.0167 2.3562\n0.0222 -0.0222 2.3562\n0.0278 -0.0278 2.3562\n0.0333 -0.0333 2.3562\n0.0389 -0.0389 2.3562\n0.0444 -0.0444 2.3562\n0.0500 -0.0500 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -7 5 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -5 7 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0111 0.0056 2.7489\n-0.0222 0.0111 2.7489\n-0.0333 0.0167 2.7489\n-0.0444 0.0222 2.7489\n-0.0556 0.0278 2.7489\n-0.0667 0.0333 2.7489\n-0.0778 0.0389 2.7489\n-0.0889 0.0444 2.7489\n-0.1000 0.0500 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0111 -0.0056 2.7489\n0.0222 -0.0111 2.7489\n0.0333 -0.0167 2.7489\n0.0444 -0.0222 2.7489\n0.0556 -0.0278 2.7489\n0.0667 -0.0333 2.7489\n0.0778 -0.0389 2.7489\n0.0889 -0.0444 2.7489\n0.1000 -0.0500 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -5 4 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -7 2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0278 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0389 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0500 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -8 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0167 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0278 0.0000 3.1416\n0.0333 0.0000 3.1416\n0.0389 0.0000 3.1416\n0.0444 0.0000 3.1416\n0.0500 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -8 -1 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -8 1 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0111 -0.0056 3.5343\n-0.0222 -0.0111 3.5343\n-0.0333 -0.0167 3.5343\n-0.0444 -0.0222 3.5343\n-0.0556 -0.0278 3.5343\n-0.0667 -0.0333 3.5343\n-0.0778 -0.0389 3.5343\n-0.0889 -0.0444 3.5343\n-0.1000 -0.0500 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0111 0.0056 3.5343\n0.0222 0.0111 3.5343\n0.0333 0.0167 3.5343\n0.0444 0.0222 3.5343\n0.0556 0.0278 3.5343\n0.0667 0.0333 3.5343\n0.0778 0.0389 3.5343\n0.0889 0.0444 3.5343\n0.1000 0.0500 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -5 -4 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -7 -2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0056 -0.0056 3.9270\n-0.0111 -0.0111 3.9270\n-0.0167 -0.0167 3.9270\n-0.0222 -0.0222 3.9270\n-0.0278 -0.0278 3.9270\n-0.0333 -0.0333 3.9270\n-0.0389 -0.0389 3.9270\n-0.0444 -0.0444 3.9270\n-0.0500 -0.0500 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -6 -6 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0056 0.0056 3.9270\n0.0111 0.0111 3.9270\n0.0167 0.0167 3.9270\n0.0222 0.0222 3.9270\n0.0278 0.0278 3.9270\n0.0333 0.0333 3.9270\n0.0389 0.0389 3.9270\n0.0444 0.0444 3.9270\n0.0500 0.0500 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -5 -7 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -7 -5 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0056 -0.0111 4.3197\n-0.0111 -0.0222 4.3197\n-0.0167 -0.0333 4.3197\n-0.0222 -0.0444 4.3197\n-0.0278 -0.0556 4.3197\n-0.0333 -0.0667 4.3197\n-0.0389 -0.0778 4.3197\n-0.0444 -0.0889 4.3197\n-0.0500 -0.1000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0056 0.0111 4.3197\n0.0111 0.0222 4.3197\n0.0167 0.0333 4.3197\n0.0222 0.0444 4.3197\n0.0278 0.0556 4.3197\n0.0333 0.0667 4.3197\n0.0389 0.0778 4.3197\n0.0444 0.0889 4.3197\n0.0500 0.1000 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -4 -5 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0278 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0389 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0500 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -8 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0167 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0278 4.7124\n0.0000 0.0333 4.7124\n0.0000 0.0389 4.7124\n0.0000 0.0444 4.7124\n0.0000 0.0500 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 1 -8 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0452 4.7124\n0.0000 -0.0904 4.7124\n0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -1 -8 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0056 -0.0111 5.1051\n0.0111 -0.0222 5.1051\n0.0167 -0.0333 5.1051\n0.0222 -0.0444 5.1051\n0.0278 -0.0556 5.1051\n0.0333 -0.0667 5.1051\n0.0389 -0.0778 5.1051\n0.0444 -0.0889 5.1051\n0.0500 -0.1000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0056 0.0111 5.1051\n-0.0111 0.0222 5.1051\n-0.0167 0.0333 5.1051\n-0.0222 0.0444 5.1051\n-0.0278 0.0556 5.1051\n-0.0333 0.0667 5.1051\n-0.0389 0.0778 5.1051\n-0.0444 0.0889 5.1051\n-0.0500 0.1000 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 4 -5 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0056 -0.0056 5.4978\n0.0111 -0.0111 5.4978\n0.0167 -0.0167 5.4978\n0.0222 -0.0222 5.4978\n0.0278 -0.0278 5.4978\n0.0333 -0.0333 5.4978\n0.0389 -0.0389 5.4978\n0.0444 -0.0444 5.4978\n0.0500 -0.0500 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 6 -6 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0056 0.0056 5.4978\n-0.0111 0.0111 5.4978\n-0.0167 0.0167 5.4978\n-0.0222 0.0222 5.4978\n-0.0278 0.0278 5.4978\n-0.0333 0.0333 5.4978\n-0.0389 0.0389 5.4978\n-0.0444 0.0444 5.4978\n-0.0500 0.0500 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 7 -5 15\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 5 -7 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0111 -0.0056 5.8905\n0.0222 -0.0111 5.8905\n0.0333 -0.0167 5.8905\n0.0444 -0.0222 5.8905\n0.0556 -0.0278 5.8905\n0.0667 -0.0333 5.8905\n0.0778 -0.0389 5.8905\n0.0889 -0.0444 5.8905\n0.1000 -0.0500 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 5\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0111 0.0056 5.8905\n-0.0222 0.0111 5.8905\n-0.0333 0.0167 5.8905\n-0.0444 0.0222 5.8905\n-0.0556 0.0278 5.8905\n-0.0667 0.0333 5.8905\n-0.0778 0.0389 5.8905\n-0.0889 0.0444 5.8905\n-0.1000 0.0500 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 5 -4 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 7 -2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim",
    "content": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0278 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0389 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0500 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 8 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0167 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0278 0.0000 0.0000\n-0.0333 0.0000 0.0000\n-0.0389 0.0000 0.0000\n-0.0444 0.0000 0.0000\n-0.0500 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 8 1 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 8 -1 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0111 0.0056 0.3927\n0.0222 0.0111 0.3927\n0.0333 0.0167 0.3927\n0.0444 0.0222 0.3927\n0.0556 0.0278 0.3927\n0.0667 0.0333 0.3927\n0.0778 0.0389 0.3927\n0.0889 0.0444 0.3927\n0.1000 0.0500 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0111 -0.0056 0.3927\n-0.0222 -0.0111 0.3927\n-0.0333 -0.0167 0.3927\n-0.0444 -0.0222 0.3927\n-0.0556 -0.0278 0.3927\n-0.0667 -0.0333 0.3927\n-0.0778 -0.0389 0.3927\n-0.0889 -0.0444 0.3927\n-0.1000 -0.0500 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 5 4 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 7 2 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 -0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0056 0.0056 0.7854\n0.0111 0.0111 0.7854\n0.0167 0.0167 0.7854\n0.0222 0.0222 0.7854\n0.0278 0.0278 0.7854\n0.0333 0.0333 0.7854\n0.0389 0.0389 0.7854\n0.0444 0.0444 0.7854\n0.0500 0.0500 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 6 6 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0056 -0.0056 0.7854\n-0.0111 -0.0111 0.7854\n-0.0167 -0.0167 0.7854\n-0.0222 -0.0222 0.7854\n-0.0278 -0.0278 0.7854\n-0.0333 -0.0333 0.7854\n-0.0389 -0.0389 0.7854\n-0.0444 -0.0444 0.7854\n-0.0500 -0.0500 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 5 7 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 7 5 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0056 0.0111 1.1781\n0.0111 0.0222 1.1781\n0.0167 0.0333 1.1781\n0.0222 0.0444 1.1781\n0.0278 0.0556 1.1781\n0.0333 0.0667 1.1781\n0.0389 0.0778 1.1781\n0.0444 0.0889 1.1781\n0.0500 0.1000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0056 -0.0111 1.1781\n-0.0111 -0.0222 1.1781\n-0.0167 -0.0333 1.1781\n-0.0222 -0.0444 1.1781\n-0.0278 -0.0556 1.1781\n-0.0333 -0.0667 1.1781\n-0.0389 -0.0778 1.1781\n-0.0444 -0.0889 1.1781\n-0.0500 -0.1000 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 4 5 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 2 7 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0278 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0389 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0500 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 8 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0167 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0278 1.5708\n0.0000 -0.0333 1.5708\n0.0000 -0.0389 1.5708\n0.0000 -0.0444 1.5708\n0.0000 -0.0500 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -1 8 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 1 8 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0056 0.0111 1.9635\n-0.0111 0.0222 1.9635\n-0.0167 0.0333 1.9635\n-0.0222 0.0444 1.9635\n-0.0278 0.0556 1.9635\n-0.0333 0.0667 1.9635\n-0.0389 0.0778 1.9635\n-0.0444 0.0889 1.9635\n-0.0500 0.1000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0056 -0.0111 1.9635\n0.0111 -0.0222 1.9635\n0.0167 -0.0333 1.9635\n0.0222 -0.0444 1.9635\n0.0278 -0.0556 1.9635\n0.0333 -0.0667 1.9635\n0.0389 -0.0778 1.9635\n0.0444 -0.0889 1.9635\n0.0500 -0.1000 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -4 5 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -2 7 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0056 0.0056 2.3562\n-0.0111 0.0111 2.3562\n-0.0167 0.0167 2.3562\n-0.0222 0.0222 2.3562\n-0.0278 0.0278 2.3562\n-0.0333 0.0333 2.3562\n-0.0389 0.0389 2.3562\n-0.0444 0.0444 2.3562\n-0.0500 0.0500 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -6 6 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0056 -0.0056 2.3562\n0.0111 -0.0111 2.3562\n0.0167 -0.0167 2.3562\n0.0222 -0.0222 2.3562\n0.0278 -0.0278 2.3562\n0.0333 -0.0333 2.3562\n0.0389 -0.0389 2.3562\n0.0444 -0.0444 2.3562\n0.0500 -0.0500 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -7 5 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -5 7 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0111 0.0056 2.7489\n-0.0222 0.0111 2.7489\n-0.0333 0.0167 2.7489\n-0.0444 0.0222 2.7489\n-0.0556 0.0278 2.7489\n-0.0667 0.0333 2.7489\n-0.0778 0.0389 2.7489\n-0.0889 0.0444 2.7489\n-0.1000 0.0500 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0111 -0.0056 2.7489\n0.0222 -0.0111 2.7489\n0.0333 -0.0167 2.7489\n0.0444 -0.0222 2.7489\n0.0556 -0.0278 2.7489\n0.0667 -0.0333 2.7489\n0.0778 -0.0389 2.7489\n0.0889 -0.0444 2.7489\n0.1000 -0.0500 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -5 4 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -7 2 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0278 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0389 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0500 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -8 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0167 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0278 0.0000 3.1416\n0.0333 0.0000 3.1416\n0.0389 0.0000 3.1416\n0.0444 0.0000 3.1416\n0.0500 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -8 -1 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -8 1 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0111 -0.0056 3.5343\n-0.0222 -0.0111 3.5343\n-0.0333 -0.0167 3.5343\n-0.0444 -0.0222 3.5343\n-0.0556 -0.0278 3.5343\n-0.0667 -0.0333 3.5343\n-0.0778 -0.0389 3.5343\n-0.0889 -0.0444 3.5343\n-0.1000 -0.0500 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0111 0.0056 3.5343\n0.0222 0.0111 3.5343\n0.0333 0.0167 3.5343\n0.0444 0.0222 3.5343\n0.0556 0.0278 3.5343\n0.0667 0.0333 3.5343\n0.0778 0.0389 3.5343\n0.0889 0.0444 3.5343\n0.1000 0.0500 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -5 -4 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -7 -2 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0056 -0.0056 3.9270\n-0.0111 -0.0111 3.9270\n-0.0167 -0.0167 3.9270\n-0.0222 -0.0222 3.9270\n-0.0278 -0.0278 3.9270\n-0.0333 -0.0333 3.9270\n-0.0389 -0.0389 3.9270\n-0.0444 -0.0444 3.9270\n-0.0500 -0.0500 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -6 -6 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0056 0.0056 3.9270\n0.0111 0.0111 3.9270\n0.0167 0.0167 3.9270\n0.0222 0.0222 3.9270\n0.0278 0.0278 3.9270\n0.0333 0.0333 3.9270\n0.0389 0.0389 3.9270\n0.0444 0.0444 3.9270\n0.0500 0.0500 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -5 -7 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -7 -5 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0056 -0.0111 4.3197\n-0.0111 -0.0222 4.3197\n-0.0167 -0.0333 4.3197\n-0.0222 -0.0444 4.3197\n-0.0278 -0.0556 4.3197\n-0.0333 -0.0667 4.3197\n-0.0389 -0.0778 4.3197\n-0.0444 -0.0889 4.3197\n-0.0500 -0.1000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0056 0.0111 4.3197\n0.0111 0.0222 4.3197\n0.0167 0.0333 4.3197\n0.0222 0.0444 4.3197\n0.0278 0.0556 4.3197\n0.0333 0.0667 4.3197\n0.0389 0.0778 4.3197\n0.0444 0.0889 4.3197\n0.0500 0.1000 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -4 -5 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -2 -7 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0278 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0389 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0500 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -8 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0167 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0278 4.7124\n0.0000 0.0333 4.7124\n0.0000 0.0389 4.7124\n0.0000 0.0444 4.7124\n0.0000 0.0500 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 1 -8 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0452 4.7124\n0.0000 -0.0904 4.7124\n0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -1 -8 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0056 -0.0111 5.1051\n0.0111 -0.0222 5.1051\n0.0167 -0.0333 5.1051\n0.0222 -0.0444 5.1051\n0.0278 -0.0556 5.1051\n0.0333 -0.0667 5.1051\n0.0389 -0.0778 5.1051\n0.0444 -0.0889 5.1051\n0.0500 -0.1000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0056 0.0111 5.1051\n-0.0111 0.0222 5.1051\n-0.0167 0.0333 5.1051\n-0.0222 0.0444 5.1051\n-0.0278 0.0556 5.1051\n-0.0333 0.0667 5.1051\n-0.0389 0.0778 5.1051\n-0.0444 0.0889 5.1051\n-0.0500 0.1000 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 4 -5 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 2 -7 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0056 -0.0056 5.4978\n0.0111 -0.0111 5.4978\n0.0167 -0.0167 5.4978\n0.0222 -0.0222 5.4978\n0.0278 -0.0278 5.4978\n0.0333 -0.0333 5.4978\n0.0389 -0.0389 5.4978\n0.0444 -0.0444 5.4978\n0.0500 -0.0500 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 6 -6 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0056 0.0056 5.4978\n-0.0111 0.0111 5.4978\n-0.0167 0.0167 5.4978\n-0.0222 0.0222 5.4978\n-0.0278 0.0278 5.4978\n-0.0333 0.0333 5.4978\n-0.0389 0.0389 5.4978\n-0.0444 0.0444 5.4978\n-0.0500 0.0500 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 7 -5 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 5 -7 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0111 -0.0056 5.8905\n0.0222 -0.0111 5.8905\n0.0333 -0.0167 5.8905\n0.0444 -0.0222 5.8905\n0.0556 -0.0278 5.8905\n0.0667 -0.0333 5.8905\n0.0778 -0.0389 5.8905\n0.0889 -0.0444 5.8905\n0.1000 -0.0500 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0111 0.0056 5.8905\n-0.0222 0.0111 5.8905\n-0.0333 0.0167 5.8905\n-0.0444 0.0222 5.8905\n-0.0556 0.0278 5.8905\n-0.0667 0.0333 5.8905\n-0.0778 0.0389 5.8905\n-0.0889 0.0444 5.8905\n-0.1000 0.0500 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 5 -4 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 7 -2 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 200\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim",
    "content": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 160\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0278 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0389 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0500 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 8 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: 16 4 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0904 0.0095 0.0349\n0.1806 0.0222 0.0699\n0.2707 0.0381 0.1048\n0.3604 0.0572 0.1398\n0.4496 0.0795 0.1747\n0.5383 0.1050 0.2097\n0.6264 0.1335 0.2446\n0.7136 0.1652 0.2796\n0.8000 0.2000 0.3145\nprimID: 3\nstartangle_c: 0\nendpose_c: 16 -4 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0904 -0.0095 -0.0349\n0.1806 -0.0222 -0.0699\n0.2707 -0.0381 -0.1048\n0.3604 -0.0572 -0.1398\n0.4496 -0.0795 -0.1747\n0.5383 -0.1050 -0.2097\n0.6264 -0.1335 -0.2446\n0.7136 -0.1652 -0.2796\n0.8000 -0.2000 -0.3145\nprimID: 4\nstartangle_c: 0\nendpose_c: 5 2 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0280 0.0085 0.0223\n0.0559 0.0177 0.0445\n0.0839 0.0275 0.0668\n0.1117 0.0380 0.0890\n0.1396 0.0491 0.1113\n0.1673 0.0609 0.1335\n0.1950 0.0733 0.1558\n0.2225 0.0863 0.1781\n0.2500 0.1000 0.2003\nprimID: 5\nstartangle_c: 0\nendpose_c: 5 -2 -1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0280 -0.0085 -0.0223\n0.0559 -0.0177 -0.0445\n0.0839 -0.0275 -0.0668\n0.1117 -0.0380 -0.0890\n0.1396 -0.0491 -0.1113\n0.1673 -0.0609 -0.1335\n0.1950 -0.0733 -0.1558\n0.2225 -0.0863 -0.1781\n0.2500 -0.1000 -0.2003\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 7\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 8\nstartangle_c: 0\nendpose_c: 8 1 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0056 0.0000\n0.0889 0.0111 0.0000\n0.1333 0.0167 0.0000\n0.1778 0.0222 0.0000\n0.2222 0.0278 0.0000\n0.2667 0.0333 0.0000\n0.3111 0.0389 0.0000\n0.3556 0.0444 0.0000\n0.4000 0.0500 0.0000\nprimID: 9\nstartangle_c: 0\nendpose_c: 8 -1 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 -0.0056 0.0000\n0.0889 -0.0111 0.0000\n0.1333 -0.0167 0.0000\n0.1778 -0.0222 0.0000\n0.2222 -0.0278 0.0000\n0.2667 -0.0333 0.0000\n0.3111 -0.0389 0.0000\n0.3556 -0.0444 0.0000\n0.4000 -0.0500 0.0000\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0111 0.0056 0.3927\n0.0222 0.0111 0.3927\n0.0333 0.0167 0.3927\n0.0444 0.0222 0.3927\n0.0556 0.0278 0.3927\n0.0667 0.0333 0.3927\n0.0778 0.0389 0.3927\n0.0889 0.0444 0.3927\n0.1000 0.0500 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: 13 9 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0793 0.0378 0.4329\n0.1572 0.0787 0.4732\n0.2334 0.1229 0.5134\n0.3079 0.1701 0.5537\n0.3805 0.2204 0.5939\n0.4512 0.2736 0.6342\n0.5197 0.3296 0.6744\n0.5860 0.3885 0.7147\n0.6500 0.4500 0.7549\nprimID: 3\nstartangle_c: 1\nendpose_c: 14 3 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0741 0.0305 0.3774\n0.1493 0.0582 0.3302\n0.2256 0.0824 0.2830\n0.3031 0.1030 0.2359\n0.3814 0.1199 0.1887\n0.4604 0.1330 0.1415\n0.5400 0.1424 0.0943\n0.6199 0.1481 0.0472\n0.7000 0.1500 -0.0000\nprimID: 4\nstartangle_c: 1\nendpose_c: 5 4 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 5\nstartangle_c: 1\nendpose_c: 6 1 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0320 0.0105 0.3551\n0.0644 0.0197 0.3174\n0.0973 0.0278 0.2798\n0.1304 0.0346 0.2421\n0.1639 0.0402 0.2045\n0.1977 0.0446 0.1669\n0.2316 0.0476 0.1292\n0.2658 0.0495 0.0916\n0.3000 0.0500 0.0540\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 7\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 8\nstartangle_c: 1\nendpose_c: 7 2 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0389 0.0111 0.3927\n0.0778 0.0222 0.3927\n0.1167 0.0333 0.3927\n0.1556 0.0444 0.3927\n0.1944 0.0556 0.3927\n0.2333 0.0667 0.3927\n0.2722 0.0778 0.3927\n0.3111 0.0889 0.3927\n0.3500 0.1000 0.3927\nprimID: 9\nstartangle_c: 1\nendpose_c: 5 4 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0278 0.0222 0.3927\n0.0556 0.0444 0.3927\n0.0833 0.0667 0.3927\n0.1111 0.0889 0.3927\n0.1389 0.1111 0.3927\n0.1667 0.1333 0.3927\n0.1944 0.1556 0.3927\n0.2222 0.1778 0.3927\n0.2500 0.2000 0.3927\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0056 0.0056 0.7854\n0.0111 0.0111 0.7854\n0.0167 0.0167 0.7854\n0.0222 0.0222 0.7854\n0.0278 0.0278 0.7854\n0.0333 0.0333 0.7854\n0.0389 0.0389 0.7854\n0.0444 0.0444 0.7854\n0.0500 0.0500 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 6 6 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: 11 14 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0705 0.0705 0.7854\n0.1411 0.1411 0.7854\n0.2116 0.2116 0.7854\n0.2816 0.2828 0.8201\n0.3469 0.3581 0.8917\n0.4068 0.4379 0.9633\n0.4607 0.5218 1.0349\n0.5086 0.6093 1.1065\n0.5500 0.7000 1.1781\nprimID: 3\nstartangle_c: 2\nendpose_c: 14 11 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0705 0.0705 0.7854\n0.1411 0.1411 0.7854\n0.2116 0.2116 0.7854\n0.2828 0.2816 0.7507\n0.3581 0.3469 0.6791\n0.4379 0.4068 0.6075\n0.5218 0.4607 0.5359\n0.6093 0.5086 0.4643\n0.7000 0.5500 0.3927\nprimID: 4\nstartangle_c: 2\nendpose_c: 4 6 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0278 0.0292 0.8288\n0.0543 0.0595 0.8722\n0.0795 0.0910 0.9156\n0.1033 0.1235 0.9590\n0.1257 0.1571 1.0024\n0.1466 0.1916 1.0458\n0.1659 0.2269 1.0892\n0.1838 0.2631 1.1326\n0.2000 0.3000 1.1760\nprimID: 5\nstartangle_c: 2\nendpose_c: 6 4 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0292 0.0278 0.7420\n0.0595 0.0543 0.6986\n0.0910 0.0795 0.6552\n0.1235 0.1033 0.6118\n0.1571 0.1257 0.5684\n0.1916 0.1466 0.5250\n0.2269 0.1659 0.4816\n0.2631 0.1838 0.4382\n0.3000 0.2000 0.3948\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 7\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 8\nstartangle_c: 2\nendpose_c: 6 7 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0389 0.7854\n0.0667 0.0778 0.7854\n0.1000 0.1167 0.7854\n0.1333 0.1556 0.7854\n0.1667 0.1944 0.7854\n0.2000 0.2333 0.7854\n0.2333 0.2722 0.7854\n0.2667 0.3111 0.7854\n0.3000 0.3500 0.7854\nprimID: 9\nstartangle_c: 2\nendpose_c: 7 6 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0389 0.0333 0.7854\n0.0778 0.0667 0.7854\n0.1167 0.1000 0.7854\n0.1556 0.1333 0.7854\n0.1944 0.1667 0.7854\n0.2333 0.2000 0.7854\n0.2722 0.2333 0.7854\n0.3111 0.2667 0.7854\n0.3500 0.3000 0.7854\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0056 0.0111 1.1781\n0.0111 0.0222 1.1781\n0.0167 0.0333 1.1781\n0.0222 0.0444 1.1781\n0.0278 0.0556 1.1781\n0.0333 0.0667 1.1781\n0.0389 0.0778 1.1781\n0.0444 0.0889 1.1781\n0.0500 0.1000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: 9 13 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0378 0.0793 1.1378\n0.0787 0.1572 1.0976\n0.1229 0.2334 1.0574\n0.1701 0.3079 1.0171\n0.2204 0.3805 0.9769\n0.2736 0.4512 0.9366\n0.3296 0.5197 0.8964\n0.3885 0.5860 0.8561\n0.4500 0.6500 0.8159\nprimID: 3\nstartangle_c: 3\nendpose_c: 3 14 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0305 0.0741 1.1934\n0.0582 0.1493 1.2406\n0.0824 0.2256 1.2878\n0.1030 0.3031 1.3349\n0.1199 0.3814 1.3821\n0.1330 0.4604 1.4293\n0.1424 0.5400 1.4765\n0.1481 0.6199 1.5236\n0.1500 0.7000 1.5708\nprimID: 4\nstartangle_c: 3\nendpose_c: 4 5 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 5\nstartangle_c: 3\nendpose_c: 1 6 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0105 0.0320 1.2157\n0.0197 0.0644 1.2534\n0.0278 0.0973 1.2910\n0.0346 0.1304 1.3286\n0.0402 0.1639 1.3663\n0.0446 0.1977 1.4039\n0.0476 0.2316 1.4416\n0.0495 0.2658 1.4792\n0.0500 0.3000 1.5168\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 7\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 8\nstartangle_c: 3\nendpose_c: 2 7 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0111 0.0389 1.1781\n0.0222 0.0778 1.1781\n0.0333 0.1167 1.1781\n0.0444 0.1556 1.1781\n0.0556 0.1944 1.1781\n0.0667 0.2333 1.1781\n0.0778 0.2722 1.1781\n0.0889 0.3111 1.1781\n0.1000 0.3500 1.1781\nprimID: 9\nstartangle_c: 3\nendpose_c: 4 5 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0222 0.0278 1.1781\n0.0444 0.0556 1.1781\n0.0667 0.0833 1.1781\n0.0889 0.1111 1.1781\n0.1111 0.1389 1.1781\n0.1333 0.1667 1.1781\n0.1556 0.1944 1.1781\n0.1778 0.2222 1.1781\n0.2000 0.2500 1.1781\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0278 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0389 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0500 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 8 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: -4 16 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0095 0.0904 1.6057\n-0.0222 0.1806 1.6407\n-0.0381 0.2707 1.6756\n-0.0572 0.3604 1.7106\n-0.0795 0.4496 1.7455\n-0.1050 0.5383 1.7805\n-0.1335 0.6264 1.8154\n-0.1652 0.7136 1.8503\n-0.2000 0.8000 1.8853\nprimID: 3\nstartangle_c: 4\nendpose_c: 4 16 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0095 0.0904 1.5359\n0.0222 0.1806 1.5009\n0.0381 0.2707 1.4660\n0.0572 0.3604 1.4310\n0.0795 0.4496 1.3961\n0.1050 0.5383 1.3611\n0.1335 0.6264 1.3262\n0.1652 0.7136 1.2912\n0.2000 0.8000 1.2563\nprimID: 4\nstartangle_c: 4\nendpose_c: -2 5 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0085 0.0280 1.5931\n-0.0177 0.0559 1.6153\n-0.0275 0.0839 1.6376\n-0.0380 0.1117 1.6598\n-0.0491 0.1396 1.6821\n-0.0609 0.1673 1.7043\n-0.0733 0.1950 1.7266\n-0.0863 0.2225 1.7489\n-0.1000 0.2500 1.7711\nprimID: 5\nstartangle_c: 4\nendpose_c: 2 5 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0085 0.0280 1.5485\n0.0177 0.0559 1.5263\n0.0275 0.0839 1.5040\n0.0380 0.1117 1.4818\n0.0491 0.1396 1.4595\n0.0609 0.1673 1.4373\n0.0733 0.1950 1.4150\n0.0863 0.2225 1.3927\n0.1000 0.2500 1.3705\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 7\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 8\nstartangle_c: 4\nendpose_c: -1 8 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0056 0.0444 1.5708\n-0.0111 0.0889 1.5708\n-0.0167 0.1333 1.5708\n-0.0222 0.1778 1.5708\n-0.0278 0.2222 1.5708\n-0.0333 0.2667 1.5708\n-0.0389 0.3111 1.5708\n-0.0444 0.3556 1.5708\n-0.0500 0.4000 1.5708\nprimID: 9\nstartangle_c: 4\nendpose_c: 1 8 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0056 0.0444 1.5708\n0.0111 0.0889 1.5708\n0.0167 0.1333 1.5708\n0.0222 0.1778 1.5708\n0.0278 0.2222 1.5708\n0.0333 0.2667 1.5708\n0.0389 0.3111 1.5708\n0.0444 0.3556 1.5708\n0.0500 0.4000 1.5708\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0056 0.0111 1.9635\n-0.0111 0.0222 1.9635\n-0.0167 0.0333 1.9635\n-0.0222 0.0444 1.9635\n-0.0278 0.0556 1.9635\n-0.0333 0.0667 1.9635\n-0.0389 0.0778 1.9635\n-0.0444 0.0889 1.9635\n-0.0500 0.1000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: -9 13 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0378 0.0793 2.0037\n-0.0787 0.1572 2.0440\n-0.1229 0.2334 2.0842\n-0.1701 0.3079 2.1245\n-0.2204 0.3805 2.1647\n-0.2736 0.4512 2.2050\n-0.3296 0.5197 2.2452\n-0.3885 0.5860 2.2855\n-0.4500 0.6500 2.3257\nprimID: 3\nstartangle_c: 5\nendpose_c: -3 14 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0305 0.0741 1.9482\n-0.0582 0.1493 1.9010\n-0.0824 0.2256 1.8538\n-0.1030 0.3031 1.8067\n-0.1199 0.3814 1.7595\n-0.1330 0.4604 1.7123\n-0.1424 0.5400 1.6651\n-0.1481 0.6199 1.6180\n-0.1500 0.7000 1.5708\nprimID: 4\nstartangle_c: 5\nendpose_c: -4 5 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 5\nstartangle_c: 5\nendpose_c: -1 6 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0105 0.0320 1.9259\n-0.0197 0.0644 1.8882\n-0.0278 0.0973 1.8506\n-0.0346 0.1304 1.8129\n-0.0402 0.1639 1.7753\n-0.0446 0.1977 1.7377\n-0.0476 0.2316 1.7000\n-0.0495 0.2658 1.6624\n-0.0500 0.3000 1.6248\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 7\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 8\nstartangle_c: 5\nendpose_c: -2 7 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0111 0.0389 1.9635\n-0.0222 0.0778 1.9635\n-0.0333 0.1167 1.9635\n-0.0444 0.1556 1.9635\n-0.0556 0.1944 1.9635\n-0.0667 0.2333 1.9635\n-0.0778 0.2722 1.9635\n-0.0889 0.3111 1.9635\n-0.1000 0.3500 1.9635\nprimID: 9\nstartangle_c: 5\nendpose_c: -4 5 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0222 0.0278 1.9635\n-0.0444 0.0556 1.9635\n-0.0667 0.0833 1.9635\n-0.0889 0.1111 1.9635\n-0.1111 0.1389 1.9635\n-0.1333 0.1667 1.9635\n-0.1556 0.1944 1.9635\n-0.1778 0.2222 1.9635\n-0.2000 0.2500 1.9635\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0056 0.0056 2.3562\n-0.0111 0.0111 2.3562\n-0.0167 0.0167 2.3562\n-0.0222 0.0222 2.3562\n-0.0278 0.0278 2.3562\n-0.0333 0.0333 2.3562\n-0.0389 0.0389 2.3562\n-0.0444 0.0444 2.3562\n-0.0500 0.0500 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -6 6 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: -14 11 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0705 0.0705 2.3562\n-0.1411 0.1411 2.3562\n-0.2116 0.2116 2.3562\n-0.2828 0.2816 2.3909\n-0.3581 0.3469 2.4625\n-0.4379 0.4068 2.5341\n-0.5218 0.4607 2.6057\n-0.6093 0.5086 2.6773\n-0.7000 0.5500 2.7489\nprimID: 3\nstartangle_c: 6\nendpose_c: -11 14 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0705 0.0705 2.3562\n-0.1411 0.1411 2.3562\n-0.2116 0.2116 2.3562\n-0.2816 0.2828 2.3215\n-0.3469 0.3581 2.2499\n-0.4068 0.4379 2.1783\n-0.4607 0.5218 2.1067\n-0.5086 0.6093 2.0351\n-0.5500 0.7000 1.9635\nprimID: 4\nstartangle_c: 6\nendpose_c: -6 4 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0292 0.0278 2.3996\n-0.0595 0.0543 2.4430\n-0.0910 0.0795 2.4864\n-0.1235 0.1033 2.5298\n-0.1571 0.1257 2.5732\n-0.1916 0.1466 2.6166\n-0.2269 0.1659 2.6600\n-0.2631 0.1838 2.7034\n-0.3000 0.2000 2.7468\nprimID: 5\nstartangle_c: 6\nendpose_c: -4 6 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0278 0.0292 2.3128\n-0.0543 0.0595 2.2694\n-0.0795 0.0910 2.2260\n-0.1033 0.1235 2.1826\n-0.1257 0.1571 2.1392\n-0.1466 0.1916 2.0958\n-0.1659 0.2269 2.0524\n-0.1838 0.2631 2.0090\n-0.2000 0.3000 1.9656\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 7\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 8\nstartangle_c: 6\nendpose_c: -7 6 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0389 0.0333 2.3562\n-0.0778 0.0667 2.3562\n-0.1167 0.1000 2.3562\n-0.1556 0.1333 2.3562\n-0.1944 0.1667 2.3562\n-0.2333 0.2000 2.3562\n-0.2722 0.2333 2.3562\n-0.3111 0.2667 2.3562\n-0.3500 0.3000 2.3562\nprimID: 9\nstartangle_c: 6\nendpose_c: -6 7 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0389 2.3562\n-0.0667 0.0778 2.3562\n-0.1000 0.1167 2.3562\n-0.1333 0.1556 2.3562\n-0.1667 0.1944 2.3562\n-0.2000 0.2333 2.3562\n-0.2333 0.2722 2.3562\n-0.2667 0.3111 2.3562\n-0.3000 0.3500 2.3562\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0111 0.0056 2.7489\n-0.0222 0.0111 2.7489\n-0.0333 0.0167 2.7489\n-0.0444 0.0222 2.7489\n-0.0556 0.0278 2.7489\n-0.0667 0.0333 2.7489\n-0.0778 0.0389 2.7489\n-0.0889 0.0444 2.7489\n-0.1000 0.0500 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: -13 9 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0793 0.0378 2.7086\n-0.1572 0.0787 2.6684\n-0.2334 0.1229 2.6281\n-0.3079 0.1701 2.5879\n-0.3805 0.2204 2.5477\n-0.4512 0.2736 2.5074\n-0.5197 0.3296 2.4672\n-0.5860 0.3885 2.4269\n-0.6500 0.4500 2.3867\nprimID: 3\nstartangle_c: 7\nendpose_c: -14 3 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0741 0.0305 2.7642\n-0.1493 0.0582 2.8114\n-0.2256 0.0824 2.8586\n-0.3031 0.1030 2.9057\n-0.3814 0.1199 2.9529\n-0.4604 0.1330 3.0001\n-0.5400 0.1424 3.0472\n-0.6199 0.1481 3.0944\n-0.7000 0.1500 3.1416\nprimID: 4\nstartangle_c: 7\nendpose_c: -5 4 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 5\nstartangle_c: 7\nendpose_c: -6 1 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0320 0.0105 2.7865\n-0.0644 0.0197 2.8242\n-0.0973 0.0278 2.8618\n-0.1304 0.0346 2.8994\n-0.1639 0.0402 2.9371\n-0.1977 0.0446 2.9747\n-0.2316 0.0476 3.0124\n-0.2658 0.0495 3.0500\n-0.3000 0.0500 3.0876\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 7\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 8\nstartangle_c: 7\nendpose_c: -7 2 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0389 0.0111 2.7489\n-0.0778 0.0222 2.7489\n-0.1167 0.0333 2.7489\n-0.1556 0.0444 2.7489\n-0.1944 0.0556 2.7489\n-0.2333 0.0667 2.7489\n-0.2722 0.0778 2.7489\n-0.3111 0.0889 2.7489\n-0.3500 0.1000 2.7489\nprimID: 9\nstartangle_c: 7\nendpose_c: -5 4 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0278 0.0222 2.7489\n-0.0556 0.0444 2.7489\n-0.0833 0.0667 2.7489\n-0.1111 0.0889 2.7489\n-0.1389 0.1111 2.7489\n-0.1667 0.1333 2.7489\n-0.1944 0.1556 2.7489\n-0.2222 0.1778 2.7489\n-0.2500 0.2000 2.7489\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0278 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0389 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0500 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -8 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: -16 -4 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0904 -0.0095 3.1765\n-0.1806 -0.0222 3.2115\n-0.2707 -0.0381 3.2464\n-0.3604 -0.0572 3.2814\n-0.4496 -0.0795 3.3163\n-0.5383 -0.1050 3.3513\n-0.6264 -0.1335 3.3862\n-0.7136 -0.1652 3.4211\n-0.8000 -0.2000 3.4561\nprimID: 3\nstartangle_c: 8\nendpose_c: -16 4 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0904 0.0095 3.1066\n-0.1806 0.0222 3.0717\n-0.2707 0.0381 3.0368\n-0.3604 0.0572 3.0018\n-0.4496 0.0795 2.9669\n-0.5383 0.1050 2.9319\n-0.6264 0.1335 2.8970\n-0.7136 0.1652 2.8620\n-0.8000 0.2000 2.8271\nprimID: 4\nstartangle_c: 8\nendpose_c: -5 -2 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0280 -0.0085 3.1639\n-0.0559 -0.0177 3.1861\n-0.0839 -0.0275 3.2084\n-0.1117 -0.0380 3.2306\n-0.1396 -0.0491 3.2529\n-0.1673 -0.0609 3.2751\n-0.1950 -0.0733 3.2974\n-0.2225 -0.0863 3.3197\n-0.2500 -0.1000 3.3419\nprimID: 5\nstartangle_c: 8\nendpose_c: -5 2 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0280 0.0085 3.1193\n-0.0559 0.0177 3.0971\n-0.0839 0.0275 3.0748\n-0.1117 0.0380 3.0526\n-0.1396 0.0491 3.0303\n-0.1673 0.0609 3.0080\n-0.1950 0.0733 2.9858\n-0.2225 0.0863 2.9635\n-0.2500 0.1000 2.9413\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 7\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 8\nstartangle_c: 8\nendpose_c: -8 -1 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 -0.0056 3.1416\n-0.0889 -0.0111 3.1416\n-0.1333 -0.0167 3.1416\n-0.1778 -0.0222 3.1416\n-0.2222 -0.0278 3.1416\n-0.2667 -0.0333 3.1416\n-0.3111 -0.0389 3.1416\n-0.3556 -0.0444 3.1416\n-0.4000 -0.0500 3.1416\nprimID: 9\nstartangle_c: 8\nendpose_c: -8 1 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0056 3.1416\n-0.0889 0.0111 3.1416\n-0.1333 0.0167 3.1416\n-0.1778 0.0222 3.1416\n-0.2222 0.0278 3.1416\n-0.2667 0.0333 3.1416\n-0.3111 0.0389 3.1416\n-0.3556 0.0444 3.1416\n-0.4000 0.0500 3.1416\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0111 -0.0056 3.5343\n-0.0222 -0.0111 3.5343\n-0.0333 -0.0167 3.5343\n-0.0444 -0.0222 3.5343\n-0.0556 -0.0278 3.5343\n-0.0667 -0.0333 3.5343\n-0.0778 -0.0389 3.5343\n-0.0889 -0.0444 3.5343\n-0.1000 -0.0500 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: -13 -9 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0793 -0.0378 3.5745\n-0.1572 -0.0787 3.6148\n-0.2334 -0.1229 3.6550\n-0.3079 -0.1701 3.6953\n-0.3805 -0.2204 3.7355\n-0.4512 -0.2736 3.7758\n-0.5197 -0.3296 3.8160\n-0.5860 -0.3885 3.8563\n-0.6500 -0.4500 3.8965\nprimID: 3\nstartangle_c: 9\nendpose_c: -14 -3 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0741 -0.0305 3.5190\n-0.1493 -0.0582 3.4718\n-0.2256 -0.0824 3.4246\n-0.3031 -0.1030 3.3775\n-0.3814 -0.1199 3.3303\n-0.4604 -0.1330 3.2831\n-0.5400 -0.1424 3.2359\n-0.6199 -0.1481 3.1888\n-0.7000 -0.1500 3.1416\nprimID: 4\nstartangle_c: 9\nendpose_c: -5 -4 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 5\nstartangle_c: 9\nendpose_c: -6 -1 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0320 -0.0105 3.4967\n-0.0644 -0.0197 3.4590\n-0.0973 -0.0278 3.4214\n-0.1304 -0.0346 3.3837\n-0.1639 -0.0402 3.3461\n-0.1977 -0.0446 3.3085\n-0.2316 -0.0476 3.2708\n-0.2658 -0.0495 3.2332\n-0.3000 -0.0500 3.1955\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 7\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 8\nstartangle_c: 9\nendpose_c: -7 -2 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0389 -0.0111 3.5343\n-0.0778 -0.0222 3.5343\n-0.1167 -0.0333 3.5343\n-0.1556 -0.0444 3.5343\n-0.1944 -0.0556 3.5343\n-0.2333 -0.0667 3.5343\n-0.2722 -0.0778 3.5343\n-0.3111 -0.0889 3.5343\n-0.3500 -0.1000 3.5343\nprimID: 9\nstartangle_c: 9\nendpose_c: -5 -4 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0278 -0.0222 3.5343\n-0.0556 -0.0444 3.5343\n-0.0833 -0.0667 3.5343\n-0.1111 -0.0889 3.5343\n-0.1389 -0.1111 3.5343\n-0.1667 -0.1333 3.5343\n-0.1944 -0.1556 3.5343\n-0.2222 -0.1778 3.5343\n-0.2500 -0.2000 3.5343\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0056 -0.0056 3.9270\n-0.0111 -0.0111 3.9270\n-0.0167 -0.0167 3.9270\n-0.0222 -0.0222 3.9270\n-0.0278 -0.0278 3.9270\n-0.0333 -0.0333 3.9270\n-0.0389 -0.0389 3.9270\n-0.0444 -0.0444 3.9270\n-0.0500 -0.0500 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -6 -6 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: -11 -14 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0705 -0.0705 3.9270\n-0.1411 -0.1411 3.9270\n-0.2116 -0.2116 3.9270\n-0.2816 -0.2828 3.9617\n-0.3469 -0.3581 4.0333\n-0.4068 -0.4379 4.1049\n-0.4607 -0.5218 4.1765\n-0.5086 -0.6093 4.2481\n-0.5500 -0.7000 4.3197\nprimID: 3\nstartangle_c: 10\nendpose_c: -14 -11 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0705 -0.0705 3.9270\n-0.1411 -0.1411 3.9270\n-0.2116 -0.2116 3.9270\n-0.2828 -0.2816 3.8923\n-0.3581 -0.3469 3.8207\n-0.4379 -0.4068 3.7491\n-0.5218 -0.4607 3.6775\n-0.6093 -0.5086 3.6059\n-0.7000 -0.5500 3.5343\nprimID: 4\nstartangle_c: 10\nendpose_c: -4 -6 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0278 -0.0292 3.9704\n-0.0543 -0.0595 4.0138\n-0.0795 -0.0910 4.0572\n-0.1033 -0.1235 4.1006\n-0.1257 -0.1571 4.1440\n-0.1466 -0.1916 4.1874\n-0.1659 -0.2269 4.2308\n-0.1838 -0.2631 4.2742\n-0.2000 -0.3000 4.3176\nprimID: 5\nstartangle_c: 10\nendpose_c: -6 -4 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0292 -0.0278 3.8836\n-0.0595 -0.0543 3.8402\n-0.0910 -0.0795 3.7968\n-0.1235 -0.1033 3.7534\n-0.1571 -0.1257 3.7100\n-0.1916 -0.1466 3.6666\n-0.2269 -0.1659 3.6232\n-0.2631 -0.1838 3.5798\n-0.3000 -0.2000 3.5364\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 7\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 8\nstartangle_c: 10\nendpose_c: -6 -7 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0389 3.9270\n-0.0667 -0.0778 3.9270\n-0.1000 -0.1167 3.9270\n-0.1333 -0.1556 3.9270\n-0.1667 -0.1944 3.9270\n-0.2000 -0.2333 3.9270\n-0.2333 -0.2722 3.9270\n-0.2667 -0.3111 3.9270\n-0.3000 -0.3500 3.9270\nprimID: 9\nstartangle_c: 10\nendpose_c: -7 -6 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0389 -0.0333 3.9270\n-0.0778 -0.0667 3.9270\n-0.1167 -0.1000 3.9270\n-0.1556 -0.1333 3.9270\n-0.1944 -0.1667 3.9270\n-0.2333 -0.2000 3.9270\n-0.2722 -0.2333 3.9270\n-0.3111 -0.2667 3.9270\n-0.3500 -0.3000 3.9270\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0056 -0.0111 4.3197\n-0.0111 -0.0222 4.3197\n-0.0167 -0.0333 4.3197\n-0.0222 -0.0444 4.3197\n-0.0278 -0.0556 4.3197\n-0.0333 -0.0667 4.3197\n-0.0389 -0.0778 4.3197\n-0.0444 -0.0889 4.3197\n-0.0500 -0.1000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: -9 -13 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0378 -0.0793 4.2794\n-0.0787 -0.1572 4.2392\n-0.1229 -0.2334 4.1989\n-0.1701 -0.3079 4.1587\n-0.2204 -0.3805 4.1185\n-0.2736 -0.4512 4.0782\n-0.3296 -0.5197 4.0380\n-0.3885 -0.5860 3.9977\n-0.4500 -0.6500 3.9575\nprimID: 3\nstartangle_c: 11\nendpose_c: -3 -14 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0305 -0.0741 4.3350\n-0.0582 -0.1493 4.3822\n-0.0824 -0.2256 4.4294\n-0.1030 -0.3031 4.4765\n-0.1199 -0.3814 4.5237\n-0.1330 -0.4604 4.5709\n-0.1424 -0.5400 4.6180\n-0.1481 -0.6199 4.6652\n-0.1500 -0.7000 4.7124\nprimID: 4\nstartangle_c: 11\nendpose_c: -4 -5 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 5\nstartangle_c: 11\nendpose_c: -1 -6 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0105 -0.0320 4.3573\n-0.0197 -0.0644 4.3950\n-0.0278 -0.0973 4.4326\n-0.0346 -0.1304 4.4702\n-0.0402 -0.1639 4.5079\n-0.0446 -0.1977 4.5455\n-0.0476 -0.2316 4.5832\n-0.0495 -0.2658 4.6208\n-0.0500 -0.3000 4.6584\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 7\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 8\nstartangle_c: 11\nendpose_c: -2 -7 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0111 -0.0389 4.3197\n-0.0222 -0.0778 4.3197\n-0.0333 -0.1167 4.3197\n-0.0444 -0.1556 4.3197\n-0.0556 -0.1944 4.3197\n-0.0667 -0.2333 4.3197\n-0.0778 -0.2722 4.3197\n-0.0889 -0.3111 4.3197\n-0.1000 -0.3500 4.3197\nprimID: 9\nstartangle_c: 11\nendpose_c: -4 -5 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0222 -0.0278 4.3197\n-0.0444 -0.0556 4.3197\n-0.0667 -0.0833 4.3197\n-0.0889 -0.1111 4.3197\n-0.1111 -0.1389 4.3197\n-0.1333 -0.1667 4.3197\n-0.1556 -0.1944 4.3197\n-0.1778 -0.2222 4.3197\n-0.2000 -0.2500 4.3197\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0278 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0389 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0500 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -8 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 4 -16 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0095 -0.0904 4.7473\n0.0222 -0.1806 4.7823\n0.0381 -0.2707 4.8172\n0.0572 -0.3604 4.8522\n0.0795 -0.4496 4.8871\n0.1050 -0.5383 4.9221\n0.1335 -0.6264 4.9570\n0.1652 -0.7136 4.9919\n0.2000 -0.8000 5.0269\nprimID: 3\nstartangle_c: 12\nendpose_c: -4 -16 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0095 -0.0904 4.6774\n-0.0222 -0.1806 4.6425\n-0.0381 -0.2707 4.6076\n-0.0572 -0.3604 4.5726\n-0.0795 -0.4496 4.5377\n-0.1050 -0.5383 4.5027\n-0.1335 -0.6264 4.4678\n-0.1652 -0.7136 4.4328\n-0.2000 -0.8000 4.3979\nprimID: 4\nstartangle_c: 12\nendpose_c: 2 -5 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0085 -0.0280 4.7346\n0.0177 -0.0559 4.7569\n0.0275 -0.0839 4.7792\n0.0380 -0.1117 4.8014\n0.0491 -0.1396 4.8237\n0.0609 -0.1673 4.8459\n0.0733 -0.1950 4.8682\n0.0863 -0.2225 4.8904\n0.1000 -0.2500 4.9127\nprimID: 5\nstartangle_c: 12\nendpose_c: -2 -5 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0085 -0.0280 4.6901\n-0.0177 -0.0559 4.6679\n-0.0275 -0.0839 4.6456\n-0.0380 -0.1117 4.6234\n-0.0491 -0.1396 4.6011\n-0.0609 -0.1673 4.5788\n-0.0733 -0.1950 4.5566\n-0.0863 -0.2225 4.5343\n-0.1000 -0.2500 4.5121\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 7\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 8\nstartangle_c: 12\nendpose_c: 1 -8 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0056 -0.0444 4.7124\n0.0111 -0.0889 4.7124\n0.0167 -0.1333 4.7124\n0.0222 -0.1778 4.7124\n0.0278 -0.2222 4.7124\n0.0333 -0.2667 4.7124\n0.0389 -0.3111 4.7124\n0.0444 -0.3556 4.7124\n0.0500 -0.4000 4.7124\nprimID: 9\nstartangle_c: 12\nendpose_c: -1 -8 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0056 -0.0444 4.7124\n-0.0111 -0.0889 4.7124\n-0.0167 -0.1333 4.7124\n-0.0222 -0.1778 4.7124\n-0.0278 -0.2222 4.7124\n-0.0333 -0.2667 4.7124\n-0.0389 -0.3111 4.7124\n-0.0444 -0.3556 4.7124\n-0.0500 -0.4000 4.7124\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0056 -0.0111 5.1051\n0.0111 -0.0222 5.1051\n0.0167 -0.0333 5.1051\n0.0222 -0.0444 5.1051\n0.0278 -0.0556 5.1051\n0.0333 -0.0667 5.1051\n0.0389 -0.0778 5.1051\n0.0444 -0.0889 5.1051\n0.0500 -0.1000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: 9 -13 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0378 -0.0793 5.1453\n0.0787 -0.1572 5.1856\n0.1229 -0.2334 5.2258\n0.1701 -0.3079 5.2661\n0.2204 -0.3805 5.3063\n0.2736 -0.4512 5.3466\n0.3296 -0.5197 5.3868\n0.3885 -0.5860 5.4271\n0.4500 -0.6500 5.4673\nprimID: 3\nstartangle_c: 13\nendpose_c: 3 -14 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0305 -0.0741 5.0898\n0.0582 -0.1493 5.0426\n0.0824 -0.2256 4.9954\n0.1030 -0.3031 4.9482\n0.1199 -0.3814 4.9011\n0.1330 -0.4604 4.8539\n0.1424 -0.5400 4.8067\n0.1481 -0.6199 4.7596\n0.1500 -0.7000 4.7124\nprimID: 4\nstartangle_c: 13\nendpose_c: 4 -5 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 5\nstartangle_c: 13\nendpose_c: 1 -6 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0105 -0.0320 5.0674\n0.0197 -0.0644 5.0298\n0.0278 -0.0973 4.9922\n0.0346 -0.1304 4.9545\n0.0402 -0.1639 4.9169\n0.0446 -0.1977 4.8793\n0.0476 -0.2316 4.8416\n0.0495 -0.2658 4.8040\n0.0500 -0.3000 4.7663\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 7\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 8\nstartangle_c: 13\nendpose_c: 2 -7 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0111 -0.0389 5.1051\n0.0222 -0.0778 5.1051\n0.0333 -0.1167 5.1051\n0.0444 -0.1556 5.1051\n0.0556 -0.1944 5.1051\n0.0667 -0.2333 5.1051\n0.0778 -0.2722 5.1051\n0.0889 -0.3111 5.1051\n0.1000 -0.3500 5.1051\nprimID: 9\nstartangle_c: 13\nendpose_c: 4 -5 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0222 -0.0278 5.1051\n0.0444 -0.0556 5.1051\n0.0667 -0.0833 5.1051\n0.0889 -0.1111 5.1051\n0.1111 -0.1389 5.1051\n0.1333 -0.1667 5.1051\n0.1556 -0.1944 5.1051\n0.1778 -0.2222 5.1051\n0.2000 -0.2500 5.1051\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0056 -0.0056 5.4978\n0.0111 -0.0111 5.4978\n0.0167 -0.0167 5.4978\n0.0222 -0.0222 5.4978\n0.0278 -0.0278 5.4978\n0.0333 -0.0333 5.4978\n0.0389 -0.0389 5.4978\n0.0444 -0.0444 5.4978\n0.0500 -0.0500 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 6 -6 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: 14 -11 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0705 -0.0705 5.4978\n0.1411 -0.1411 5.4978\n0.2116 -0.2116 5.4978\n0.2828 -0.2816 5.5325\n0.3581 -0.3469 5.6041\n0.4379 -0.4068 5.6757\n0.5218 -0.4607 5.7473\n0.6093 -0.5086 5.8189\n0.7000 -0.5500 5.8905\nprimID: 3\nstartangle_c: 14\nendpose_c: 11 -14 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0705 -0.0705 5.4978\n0.1411 -0.1411 5.4978\n0.2116 -0.2116 5.4978\n0.2816 -0.2828 5.4631\n0.3469 -0.3581 5.3915\n0.4068 -0.4379 5.3199\n0.4607 -0.5218 5.2483\n0.5086 -0.6093 5.1767\n0.5500 -0.7000 5.1051\nprimID: 4\nstartangle_c: 14\nendpose_c: 6 -4 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0292 -0.0278 5.5412\n0.0595 -0.0543 5.5846\n0.0910 -0.0795 5.6280\n0.1235 -0.1033 5.6714\n0.1571 -0.1257 5.7148\n0.1916 -0.1466 5.7582\n0.2269 -0.1659 5.8016\n0.2631 -0.1838 5.8450\n0.3000 -0.2000 5.8884\nprimID: 5\nstartangle_c: 14\nendpose_c: 4 -6 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0278 -0.0292 5.4544\n0.0543 -0.0595 5.4110\n0.0795 -0.0910 5.3676\n0.1033 -0.1235 5.3242\n0.1257 -0.1571 5.2808\n0.1466 -0.1916 5.2374\n0.1659 -0.2269 5.1940\n0.1838 -0.2631 5.1506\n0.2000 -0.3000 5.1072\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 7\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 8\nstartangle_c: 14\nendpose_c: 7 -6 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0389 -0.0333 5.4978\n0.0778 -0.0667 5.4978\n0.1167 -0.1000 5.4978\n0.1556 -0.1333 5.4978\n0.1944 -0.1667 5.4978\n0.2333 -0.2000 5.4978\n0.2722 -0.2333 5.4978\n0.3111 -0.2667 5.4978\n0.3500 -0.3000 5.4978\nprimID: 9\nstartangle_c: 14\nendpose_c: 6 -7 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0389 5.4978\n0.0667 -0.0778 5.4978\n0.1000 -0.1167 5.4978\n0.1333 -0.1556 5.4978\n0.1667 -0.1944 5.4978\n0.2000 -0.2333 5.4978\n0.2333 -0.2722 5.4978\n0.2667 -0.3111 5.4978\n0.3000 -0.3500 5.4978\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0111 -0.0056 5.8905\n0.0222 -0.0111 5.8905\n0.0333 -0.0167 5.8905\n0.0444 -0.0222 5.8905\n0.0556 -0.0278 5.8905\n0.0667 -0.0333 5.8905\n0.0778 -0.0389 5.8905\n0.0889 -0.0444 5.8905\n0.1000 -0.0500 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: 13 -9 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0793 -0.0378 5.8502\n0.1572 -0.0787 5.8100\n0.2334 -0.1229 5.7697\n0.3079 -0.1701 5.7295\n0.3805 -0.2204 5.6892\n0.4512 -0.2736 5.6490\n0.5197 -0.3296 5.6088\n0.5860 -0.3885 5.5685\n0.6500 -0.4500 5.5283\nprimID: 3\nstartangle_c: 15\nendpose_c: 14 -3 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0741 -0.0305 5.9058\n0.1493 -0.0582 5.9530\n0.2256 -0.0824 6.0002\n0.3031 -0.1030 6.0473\n0.3814 -0.1199 6.0945\n0.4604 -0.1330 6.1417\n0.5400 -0.1424 6.1888\n0.6199 -0.1481 6.2360\n0.7000 -0.1500 6.2832\nprimID: 4\nstartangle_c: 15\nendpose_c: 5 -4 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 5\nstartangle_c: 15\nendpose_c: 6 -1 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0320 -0.0105 5.9281\n0.0644 -0.0197 5.9658\n0.0973 -0.0278 6.0034\n0.1304 -0.0346 6.0410\n0.1639 -0.0402 6.0787\n0.1977 -0.0446 6.1163\n0.2316 -0.0476 6.1540\n0.2658 -0.0495 6.1916\n0.3000 -0.0500 6.2292\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 7\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 1000\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\nprimID: 8\nstartangle_c: 15\nendpose_c: 7 -2 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0389 -0.0111 5.8905\n0.0778 -0.0222 5.8905\n0.1167 -0.0333 5.8905\n0.1556 -0.0444 5.8905\n0.1944 -0.0556 5.8905\n0.2333 -0.0667 5.8905\n0.2722 -0.0778 5.8905\n0.3111 -0.0889 5.8905\n0.3500 -0.1000 5.8905\nprimID: 9\nstartangle_c: 15\nendpose_c: 5 -4 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0278 -0.0222 5.8905\n0.0556 -0.0444 5.8905\n0.0833 -0.0667 5.8905\n0.1111 -0.0889 5.8905\n0.1389 -0.1111 5.8905\n0.1667 -0.1333 5.8905\n0.1944 -0.1556 5.8905\n0.2222 -0.1778 5.8905\n0.2500 -0.2000 5.8905\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_10cm.mprim",
    "content": "resolution_m: 0.100000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0556 0.0000 0.0000\n0.0667 0.0000 0.0000\n0.0778 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1000 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 4 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0333 0.0000 0.0000\n-0.0444 0.0000 0.0000\n-0.0556 0.0000 0.0000\n-0.0667 0.0000 0.0000\n-0.0778 0.0000 0.0000\n-0.0889 0.0000 0.0000\n-0.1000 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 4 1 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0048 0.0349\n0.0903 0.0111 0.0699\n0.1353 0.0191 0.1048\n0.1802 0.0286 0.1398\n0.2248 0.0398 0.1747\n0.2692 0.0525 0.2097\n0.3132 0.0668 0.2446\n0.3568 0.0826 0.2796\n0.4000 0.1000 0.3145\nprimID: 4\nstartangle_c: 0\nendpose_c: 4 -1 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0048 -0.0349\n0.0903 -0.0111 -0.0699\n0.1353 -0.0191 -0.1048\n0.1802 -0.0286 -0.1398\n0.2248 -0.0398 -0.1747\n0.2692 -0.0525 -0.2097\n0.3132 -0.0668 -0.2446\n0.3568 -0.0826 -0.2796\n0.4000 -0.1000 -0.3145\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0222 0.0111 0.3927\n0.0444 0.0222 0.3927\n0.0667 0.0333 0.3927\n0.0889 0.0444 0.3927\n0.1111 0.0556 0.3927\n0.1333 0.0667 0.3927\n0.1556 0.0778 0.3927\n0.1778 0.0889 0.3927\n0.2000 0.1000 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0667 0.0333 0.3927\n0.1333 0.0667 0.3927\n0.2000 0.1000 0.3927\n0.2667 0.1333 0.3927\n0.3333 0.1667 0.3927\n0.4000 0.2000 0.3927\n0.4667 0.2333 0.3927\n0.5333 0.2667 0.3927\n0.6000 0.3000 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0222 -0.0111 0.3927\n-0.0444 -0.0222 0.3927\n-0.0667 -0.0333 0.3927\n-0.0889 -0.0444 0.3927\n-0.1111 -0.0556 0.3927\n-0.1333 -0.0667 0.3927\n-0.1556 -0.0778 0.3927\n-0.1778 -0.0889 0.3927\n-0.2000 -0.1000 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 3 2 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0369 0.0162 0.4345\n0.0731 0.0339 0.4783\n0.1085 0.0533 0.5222\n0.1430 0.0741 0.5661\n0.1766 0.0965 0.6099\n0.2091 0.1203 0.6538\n0.2405 0.1455 0.6977\n0.2709 0.1721 0.7415\n0.3000 0.2000 0.7854\nprimID: 4\nstartangle_c: 1\nendpose_c: 4 1 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0427 0.0177 0.3927\n0.0854 0.0354 0.3927\n0.1283 0.0523 0.3477\n0.1722 0.0668 0.2898\n0.2168 0.0787 0.2318\n0.2621 0.0880 0.1739\n0.3078 0.0947 0.1159\n0.3538 0.0987 0.0580\n0.4000 0.1000 0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0111 0.0111 0.7854\n0.0222 0.0222 0.7854\n0.0333 0.0333 0.7854\n0.0444 0.0444 0.7854\n0.0556 0.0556 0.7854\n0.0667 0.0667 0.7854\n0.0778 0.0778 0.7854\n0.0889 0.0889 0.7854\n0.1000 0.1000 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 3 3 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0111 -0.0111 0.7854\n-0.0222 -0.0222 0.7854\n-0.0333 -0.0333 0.7854\n-0.0444 -0.0444 0.7854\n-0.0556 -0.0556 0.7854\n-0.0667 -0.0667 0.7854\n-0.0778 -0.0778 0.7854\n-0.0889 -0.0889 0.7854\n-0.1000 -0.1000 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 2 4 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0262 0.0411 0.8119\n0.0515 0.0831 0.8384\n0.0758 0.1260 0.8649\n0.0991 0.1697 0.8913\n0.1214 0.2142 0.9178\n0.1426 0.2595 0.9443\n0.1628 0.3056 0.9708\n0.1820 0.3525 0.9973\n0.2000 0.4000 1.0238\nprimID: 4\nstartangle_c: 2\nendpose_c: 4 2 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0411 0.0262 0.7589\n0.0831 0.0515 0.7324\n0.1260 0.0758 0.7059\n0.1697 0.0991 0.6795\n0.2142 0.1214 0.6530\n0.2595 0.1426 0.6265\n0.3056 0.1628 0.6000\n0.3525 0.1820 0.5735\n0.4000 0.2000 0.5470\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0111 0.0222 1.1781\n0.0222 0.0444 1.1781\n0.0333 0.0667 1.1781\n0.0444 0.0889 1.1781\n0.0556 0.1111 1.1781\n0.0667 0.1333 1.1781\n0.0778 0.1556 1.1781\n0.0889 0.1778 1.1781\n0.1000 0.2000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0333 0.0667 1.1781\n0.0667 0.1333 1.1781\n0.1000 0.2000 1.1781\n0.1333 0.2667 1.1781\n0.1667 0.3333 1.1781\n0.2000 0.4000 1.1781\n0.2333 0.4667 1.1781\n0.2667 0.5333 1.1781\n0.3000 0.6000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0111 -0.0222 1.1781\n-0.0222 -0.0444 1.1781\n-0.0333 -0.0667 1.1781\n-0.0444 -0.0889 1.1781\n-0.0556 -0.1111 1.1781\n-0.0667 -0.1333 1.1781\n-0.0778 -0.1556 1.1781\n-0.0889 -0.1778 1.1781\n-0.1000 -0.2000 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 2 3 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0162 0.0369 1.1363\n0.0339 0.0731 1.0925\n0.0533 0.1085 1.0486\n0.0741 0.1430 1.0047\n0.0965 0.1766 0.9609\n0.1203 0.2091 0.9170\n0.1455 0.2405 0.8731\n0.1721 0.2709 0.8293\n0.2000 0.3000 0.7854\nprimID: 4\nstartangle_c: 3\nendpose_c: 1 4 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0177 0.0427 1.1781\n0.0354 0.0854 1.1781\n0.0523 0.1283 1.2231\n0.0668 0.1722 1.2810\n0.0787 0.2168 1.3390\n0.0880 0.2621 1.3969\n0.0947 0.3078 1.4549\n0.0987 0.3538 1.5128\n0.1000 0.4000 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0556 1.5708\n0.0000 0.0667 1.5708\n0.0000 0.0778 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1000 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 4 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0333 1.5708\n0.0000 -0.0444 1.5708\n0.0000 -0.0556 1.5708\n0.0000 -0.0667 1.5708\n0.0000 -0.0778 1.5708\n0.0000 -0.0889 1.5708\n0.0000 -0.1000 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -1 4 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0048 0.0452 1.6057\n-0.0111 0.0903 1.6407\n-0.0191 0.1353 1.6756\n-0.0286 0.1802 1.7106\n-0.0398 0.2248 1.7455\n-0.0525 0.2692 1.7805\n-0.0668 0.3132 1.8154\n-0.0826 0.3568 1.8503\n-0.1000 0.4000 1.8853\nprimID: 4\nstartangle_c: 4\nendpose_c: 1 4 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0048 0.0452 1.5359\n0.0111 0.0903 1.5009\n0.0191 0.1353 1.4660\n0.0286 0.1802 1.4310\n0.0398 0.2248 1.3961\n0.0525 0.2692 1.3611\n0.0668 0.3132 1.3262\n0.0826 0.3568 1.2912\n0.1000 0.4000 1.2563\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0111 0.0222 1.9635\n-0.0222 0.0444 1.9635\n-0.0333 0.0667 1.9635\n-0.0444 0.0889 1.9635\n-0.0556 0.1111 1.9635\n-0.0667 0.1333 1.9635\n-0.0778 0.1556 1.9635\n-0.0889 0.1778 1.9635\n-0.1000 0.2000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0333 0.0667 1.9635\n-0.0667 0.1333 1.9635\n-0.1000 0.2000 1.9635\n-0.1333 0.2667 1.9635\n-0.1667 0.3333 1.9635\n-0.2000 0.4000 1.9635\n-0.2333 0.4667 1.9635\n-0.2667 0.5333 1.9635\n-0.3000 0.6000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0111 -0.0222 1.9635\n0.0222 -0.0444 1.9635\n0.0333 -0.0667 1.9635\n0.0444 -0.0889 1.9635\n0.0556 -0.1111 1.9635\n0.0667 -0.1333 1.9635\n0.0778 -0.1556 1.9635\n0.0889 -0.1778 1.9635\n0.1000 -0.2000 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -2 3 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0162 0.0369 2.0053\n-0.0339 0.0731 2.0491\n-0.0533 0.1085 2.0930\n-0.0741 0.1430 2.1369\n-0.0965 0.1766 2.1807\n-0.1203 0.2091 2.2246\n-0.1455 0.2405 2.2685\n-0.1721 0.2709 2.3123\n-0.2000 0.3000 2.3562\nprimID: 4\nstartangle_c: 5\nendpose_c: -1 4 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0177 0.0427 1.9635\n-0.0354 0.0854 1.9635\n-0.0523 0.1283 1.9185\n-0.0668 0.1722 1.8606\n-0.0787 0.2168 1.8026\n-0.0880 0.2621 1.7447\n-0.0947 0.3078 1.6867\n-0.0987 0.3538 1.6287\n-0.1000 0.4000 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0111 0.0111 2.3562\n-0.0222 0.0222 2.3562\n-0.0333 0.0333 2.3562\n-0.0444 0.0444 2.3562\n-0.0556 0.0556 2.3562\n-0.0667 0.0667 2.3562\n-0.0778 0.0778 2.3562\n-0.0889 0.0889 2.3562\n-0.1000 0.1000 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -3 3 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0111 -0.0111 2.3562\n0.0222 -0.0222 2.3562\n0.0333 -0.0333 2.3562\n0.0444 -0.0444 2.3562\n0.0556 -0.0556 2.3562\n0.0667 -0.0667 2.3562\n0.0778 -0.0778 2.3562\n0.0889 -0.0889 2.3562\n0.1000 -0.1000 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -4 2 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0411 0.0262 2.3827\n-0.0831 0.0515 2.4092\n-0.1260 0.0758 2.4357\n-0.1697 0.0991 2.4621\n-0.2142 0.1214 2.4886\n-0.2595 0.1426 2.5151\n-0.3056 0.1628 2.5416\n-0.3525 0.1820 2.5681\n-0.4000 0.2000 2.5946\nprimID: 4\nstartangle_c: 6\nendpose_c: -2 4 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0262 0.0411 2.3297\n-0.0515 0.0831 2.3032\n-0.0758 0.1260 2.2767\n-0.0991 0.1697 2.2502\n-0.1214 0.2142 2.2238\n-0.1426 0.2595 2.1973\n-0.1628 0.3056 2.1708\n-0.1820 0.3525 2.1443\n-0.2000 0.4000 2.1178\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0222 0.0111 2.7489\n-0.0444 0.0222 2.7489\n-0.0667 0.0333 2.7489\n-0.0889 0.0444 2.7489\n-0.1111 0.0556 2.7489\n-0.1333 0.0667 2.7489\n-0.1556 0.0778 2.7489\n-0.1778 0.0889 2.7489\n-0.2000 0.1000 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0667 0.0333 2.7489\n-0.1333 0.0667 2.7489\n-0.2000 0.1000 2.7489\n-0.2667 0.1333 2.7489\n-0.3333 0.1667 2.7489\n-0.4000 0.2000 2.7489\n-0.4667 0.2333 2.7489\n-0.5333 0.2667 2.7489\n-0.6000 0.3000 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0222 -0.0111 2.7489\n0.0444 -0.0222 2.7489\n0.0667 -0.0333 2.7489\n0.0889 -0.0444 2.7489\n0.1111 -0.0556 2.7489\n0.1333 -0.0667 2.7489\n0.1556 -0.0778 2.7489\n0.1778 -0.0889 2.7489\n0.2000 -0.1000 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -3 2 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0369 0.0162 2.7071\n-0.0731 0.0339 2.6633\n-0.1085 0.0533 2.6194\n-0.1430 0.0741 2.5755\n-0.1766 0.0965 2.5317\n-0.2091 0.1203 2.4878\n-0.2405 0.1455 2.4439\n-0.2709 0.1721 2.4001\n-0.3000 0.2000 2.3562\nprimID: 4\nstartangle_c: 7\nendpose_c: -4 1 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0427 0.0177 2.7489\n-0.0854 0.0354 2.7489\n-0.1283 0.0523 2.7939\n-0.1722 0.0668 2.8518\n-0.2168 0.0787 2.9098\n-0.2621 0.0880 2.9677\n-0.3078 0.0947 3.0257\n-0.3538 0.0987 3.0836\n-0.4000 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0556 0.0000 3.1416\n-0.0667 0.0000 3.1416\n-0.0778 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1000 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -4 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0333 0.0000 3.1416\n0.0444 0.0000 3.1416\n0.0556 0.0000 3.1416\n0.0667 0.0000 3.1416\n0.0778 0.0000 3.1416\n0.0889 0.0000 3.1416\n0.1000 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -4 -1 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 -0.0048 3.1765\n-0.0903 -0.0111 3.2115\n-0.1353 -0.0191 3.2464\n-0.1802 -0.0286 3.2814\n-0.2248 -0.0398 3.3163\n-0.2692 -0.0525 3.3513\n-0.3132 -0.0668 3.3862\n-0.3568 -0.0826 3.4211\n-0.4000 -0.1000 3.4561\nprimID: 4\nstartangle_c: 8\nendpose_c: -4 1 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0048 3.1066\n-0.0903 0.0111 3.0717\n-0.1353 0.0191 3.0368\n-0.1802 0.0286 3.0018\n-0.2248 0.0398 2.9669\n-0.2692 0.0525 2.9319\n-0.3132 0.0668 2.8970\n-0.3568 0.0826 2.8620\n-0.4000 0.1000 2.8271\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0222 -0.0111 3.5343\n-0.0444 -0.0222 3.5343\n-0.0667 -0.0333 3.5343\n-0.0889 -0.0444 3.5343\n-0.1111 -0.0556 3.5343\n-0.1333 -0.0667 3.5343\n-0.1556 -0.0778 3.5343\n-0.1778 -0.0889 3.5343\n-0.2000 -0.1000 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0667 -0.0333 3.5343\n-0.1333 -0.0667 3.5343\n-0.2000 -0.1000 3.5343\n-0.2667 -0.1333 3.5343\n-0.3333 -0.1667 3.5343\n-0.4000 -0.2000 3.5343\n-0.4667 -0.2333 3.5343\n-0.5333 -0.2667 3.5343\n-0.6000 -0.3000 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0222 0.0111 3.5343\n0.0444 0.0222 3.5343\n0.0667 0.0333 3.5343\n0.0889 0.0444 3.5343\n0.1111 0.0556 3.5343\n0.1333 0.0667 3.5343\n0.1556 0.0778 3.5343\n0.1778 0.0889 3.5343\n0.2000 0.1000 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -3 -2 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0369 -0.0162 3.5761\n-0.0731 -0.0339 3.6199\n-0.1085 -0.0533 3.6638\n-0.1430 -0.0741 3.7077\n-0.1766 -0.0965 3.7515\n-0.2091 -0.1203 3.7954\n-0.2405 -0.1455 3.8393\n-0.2709 -0.1721 3.8831\n-0.3000 -0.2000 3.9270\nprimID: 4\nstartangle_c: 9\nendpose_c: -4 -1 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0427 -0.0177 3.5343\n-0.0854 -0.0354 3.5343\n-0.1283 -0.0523 3.4893\n-0.1722 -0.0668 3.4313\n-0.2168 -0.0787 3.3734\n-0.2621 -0.0880 3.3154\n-0.3078 -0.0947 3.2575\n-0.3538 -0.0987 3.1995\n-0.4000 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0111 -0.0111 3.9270\n-0.0222 -0.0222 3.9270\n-0.0333 -0.0333 3.9270\n-0.0444 -0.0444 3.9270\n-0.0556 -0.0556 3.9270\n-0.0667 -0.0667 3.9270\n-0.0778 -0.0778 3.9270\n-0.0889 -0.0889 3.9270\n-0.1000 -0.1000 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -3 -3 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0111 0.0111 3.9270\n0.0222 0.0222 3.9270\n0.0333 0.0333 3.9270\n0.0444 0.0444 3.9270\n0.0556 0.0556 3.9270\n0.0667 0.0667 3.9270\n0.0778 0.0778 3.9270\n0.0889 0.0889 3.9270\n0.1000 0.1000 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -2 -4 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0262 -0.0411 3.9535\n-0.0515 -0.0831 3.9800\n-0.0758 -0.1260 4.0064\n-0.0991 -0.1697 4.0329\n-0.1214 -0.2142 4.0594\n-0.1426 -0.2595 4.0859\n-0.1628 -0.3056 4.1124\n-0.1820 -0.3525 4.1389\n-0.2000 -0.4000 4.1654\nprimID: 4\nstartangle_c: 10\nendpose_c: -4 -2 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0411 -0.0262 3.9005\n-0.0831 -0.0515 3.8740\n-0.1260 -0.0758 3.8475\n-0.1697 -0.0991 3.8210\n-0.2142 -0.1214 3.7946\n-0.2595 -0.1426 3.7681\n-0.3056 -0.1628 3.7416\n-0.3525 -0.1820 3.7151\n-0.4000 -0.2000 3.6886\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0111 -0.0222 4.3197\n-0.0222 -0.0444 4.3197\n-0.0333 -0.0667 4.3197\n-0.0444 -0.0889 4.3197\n-0.0556 -0.1111 4.3197\n-0.0667 -0.1333 4.3197\n-0.0778 -0.1556 4.3197\n-0.0889 -0.1778 4.3197\n-0.1000 -0.2000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0333 -0.0667 4.3197\n-0.0667 -0.1333 4.3197\n-0.1000 -0.2000 4.3197\n-0.1333 -0.2667 4.3197\n-0.1667 -0.3333 4.3197\n-0.2000 -0.4000 4.3197\n-0.2333 -0.4667 4.3197\n-0.2667 -0.5333 4.3197\n-0.3000 -0.6000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0111 0.0222 4.3197\n0.0222 0.0444 4.3197\n0.0333 0.0667 4.3197\n0.0444 0.0889 4.3197\n0.0556 0.1111 4.3197\n0.0667 0.1333 4.3197\n0.0778 0.1556 4.3197\n0.0889 0.1778 4.3197\n0.1000 0.2000 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -2 -3 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0162 -0.0369 4.2779\n-0.0339 -0.0731 4.2341\n-0.0533 -0.1085 4.1902\n-0.0741 -0.1430 4.1463\n-0.0965 -0.1766 4.1025\n-0.1203 -0.2091 4.0586\n-0.1455 -0.2405 4.0147\n-0.1721 -0.2709 3.9709\n-0.2000 -0.3000 3.9270\nprimID: 4\nstartangle_c: 11\nendpose_c: -1 -4 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0177 -0.0427 4.3197\n-0.0354 -0.0854 4.3197\n-0.0523 -0.1283 4.3647\n-0.0668 -0.1722 4.4226\n-0.0787 -0.2168 4.4806\n-0.0880 -0.2621 4.5385\n-0.0947 -0.3078 4.5965\n-0.0987 -0.3538 4.6544\n-0.1000 -0.4000 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0556 4.7124\n0.0000 -0.0667 4.7124\n0.0000 -0.0778 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1000 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -4 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0333 4.7124\n0.0000 0.0444 4.7124\n0.0000 0.0556 4.7124\n0.0000 0.0667 4.7124\n0.0000 0.0778 4.7124\n0.0000 0.0889 4.7124\n0.0000 0.1000 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 1 -4 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0048 -0.0452 4.7473\n0.0111 -0.0903 4.7823\n0.0191 -0.1353 4.8172\n0.0286 -0.1802 4.8522\n0.0398 -0.2248 4.8871\n0.0525 -0.2692 4.9221\n0.0668 -0.3132 4.9570\n0.0826 -0.3568 4.9919\n0.1000 -0.4000 5.0269\nprimID: 4\nstartangle_c: 12\nendpose_c: -1 -4 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0048 -0.0452 4.6774\n-0.0111 -0.0903 4.6425\n-0.0191 -0.1353 4.6076\n-0.0286 -0.1802 4.5726\n-0.0398 -0.2248 4.5377\n-0.0525 -0.2692 4.5027\n-0.0668 -0.3132 4.4678\n-0.0826 -0.3568 4.4328\n-0.1000 -0.4000 4.3979\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0111 -0.0222 5.1051\n0.0222 -0.0444 5.1051\n0.0333 -0.0667 5.1051\n0.0444 -0.0889 5.1051\n0.0556 -0.1111 5.1051\n0.0667 -0.1333 5.1051\n0.0778 -0.1556 5.1051\n0.0889 -0.1778 5.1051\n0.1000 -0.2000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0333 -0.0667 5.1051\n0.0667 -0.1333 5.1051\n0.1000 -0.2000 5.1051\n0.1333 -0.2667 5.1051\n0.1667 -0.3333 5.1051\n0.2000 -0.4000 5.1051\n0.2333 -0.4667 5.1051\n0.2667 -0.5333 5.1051\n0.3000 -0.6000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0111 0.0222 5.1051\n-0.0222 0.0444 5.1051\n-0.0333 0.0667 5.1051\n-0.0444 0.0889 5.1051\n-0.0556 0.1111 5.1051\n-0.0667 0.1333 5.1051\n-0.0778 0.1556 5.1051\n-0.0889 0.1778 5.1051\n-0.1000 0.2000 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 2 -3 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0162 -0.0369 5.1469\n0.0339 -0.0731 5.1907\n0.0533 -0.1085 5.2346\n0.0741 -0.1430 5.2785\n0.0965 -0.1766 5.3223\n0.1203 -0.2091 5.3662\n0.1455 -0.2405 5.4101\n0.1721 -0.2709 5.4539\n0.2000 -0.3000 5.4978\nprimID: 4\nstartangle_c: 13\nendpose_c: 1 -4 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0177 -0.0427 5.1051\n0.0354 -0.0854 5.1051\n0.0523 -0.1283 5.0601\n0.0668 -0.1722 5.0021\n0.0787 -0.2168 4.9442\n0.0880 -0.2621 4.8862\n0.0947 -0.3078 4.8283\n0.0987 -0.3538 4.7703\n0.1000 -0.4000 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0111 -0.0111 5.4978\n0.0222 -0.0222 5.4978\n0.0333 -0.0333 5.4978\n0.0444 -0.0444 5.4978\n0.0556 -0.0556 5.4978\n0.0667 -0.0667 5.4978\n0.0778 -0.0778 5.4978\n0.0889 -0.0889 5.4978\n0.1000 -0.1000 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 3 -3 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0111 0.0111 5.4978\n-0.0222 0.0222 5.4978\n-0.0333 0.0333 5.4978\n-0.0444 0.0444 5.4978\n-0.0556 0.0556 5.4978\n-0.0667 0.0667 5.4978\n-0.0778 0.0778 5.4978\n-0.0889 0.0889 5.4978\n-0.1000 0.1000 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 4 -2 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0411 -0.0262 5.5243\n0.0831 -0.0515 5.5508\n0.1260 -0.0758 5.5772\n0.1697 -0.0991 5.6037\n0.2142 -0.1214 5.6302\n0.2595 -0.1426 5.6567\n0.3056 -0.1628 5.6832\n0.3525 -0.1820 5.7097\n0.4000 -0.2000 5.7362\nprimID: 4\nstartangle_c: 14\nendpose_c: 2 -4 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0262 -0.0411 5.4713\n0.0515 -0.0831 5.4448\n0.0758 -0.1260 5.4183\n0.0991 -0.1697 5.3918\n0.1214 -0.2142 5.3654\n0.1426 -0.2595 5.3389\n0.1628 -0.3056 5.3124\n0.1820 -0.3525 5.2859\n0.2000 -0.4000 5.2594\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0222 -0.0111 5.8905\n0.0444 -0.0222 5.8905\n0.0667 -0.0333 5.8905\n0.0889 -0.0444 5.8905\n0.1111 -0.0556 5.8905\n0.1333 -0.0667 5.8905\n0.1556 -0.0778 5.8905\n0.1778 -0.0889 5.8905\n0.2000 -0.1000 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0667 -0.0333 5.8905\n0.1333 -0.0667 5.8905\n0.2000 -0.1000 5.8905\n0.2667 -0.1333 5.8905\n0.3333 -0.1667 5.8905\n0.4000 -0.2000 5.8905\n0.4667 -0.2333 5.8905\n0.5333 -0.2667 5.8905\n0.6000 -0.3000 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0222 0.0111 5.8905\n-0.0444 0.0222 5.8905\n-0.0667 0.0333 5.8905\n-0.0889 0.0444 5.8905\n-0.1111 0.0556 5.8905\n-0.1333 0.0667 5.8905\n-0.1556 0.0778 5.8905\n-0.1778 0.0889 5.8905\n-0.2000 0.1000 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 3 -2 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0369 -0.0162 5.8487\n0.0731 -0.0339 5.8049\n0.1085 -0.0533 5.7610\n0.1430 -0.0741 5.7171\n0.1766 -0.0965 5.6733\n0.2091 -0.1203 5.6294\n0.2405 -0.1455 5.5855\n0.2709 -0.1721 5.5417\n0.3000 -0.2000 5.4978\nprimID: 4\nstartangle_c: 15\nendpose_c: 4 -1 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0427 -0.0177 5.8905\n0.0854 -0.0354 5.8905\n0.1283 -0.0523 5.9355\n0.1722 -0.0668 5.9934\n0.2168 -0.0787 6.0514\n0.2621 -0.0880 6.1093\n0.3078 -0.0947 6.1673\n0.3538 -0.0987 6.2252\n0.4000 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_1cm.mprim",
    "content": "resolution_m: 0.010000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0011 0.0000 0.0000\n0.0022 0.0000 0.0000\n0.0033 0.0000 0.0000\n0.0044 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0067 0.0000 0.0000\n0.0078 0.0000 0.0000\n0.0089 0.0000 0.0000\n0.0100 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 20 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0667 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1111 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1556 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0011 0.0000 0.0000\n-0.0022 0.0000 0.0000\n-0.0033 0.0000 0.0000\n-0.0044 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0067 0.0000 0.0000\n-0.0078 0.0000 0.0000\n-0.0089 0.0000 0.0000\n-0.0100 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 40 5 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 40 -5 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0022 0.0011 0.3927\n0.0044 0.0022 0.3927\n0.0067 0.0033 0.3927\n0.0089 0.0044 0.3927\n0.0111 0.0056 0.3927\n0.0133 0.0067 0.3927\n0.0156 0.0078 0.3927\n0.0178 0.0089 0.3927\n0.0200 0.0100 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 20 10 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0222 0.0111 0.3927\n0.0444 0.0222 0.3927\n0.0667 0.0333 0.3927\n0.0889 0.0444 0.3927\n0.1111 0.0556 0.3927\n0.1333 0.0667 0.3927\n0.1556 0.0778 0.3927\n0.1778 0.0889 0.3927\n0.2000 0.1000 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0022 -0.0011 0.3927\n-0.0044 -0.0022 0.3927\n-0.0067 -0.0033 0.3927\n-0.0089 -0.0044 0.3927\n-0.0111 -0.0056 0.3927\n-0.0133 -0.0067 0.3927\n-0.0156 -0.0078 0.3927\n-0.0178 -0.0089 0.3927\n-0.0200 -0.0100 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 25 20 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 35 10 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 -0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0011 0.0011 0.7854\n0.0022 0.0022 0.7854\n0.0033 0.0033 0.7854\n0.0044 0.0044 0.7854\n0.0056 0.0056 0.7854\n0.0067 0.0067 0.7854\n0.0078 0.0078 0.7854\n0.0089 0.0089 0.7854\n0.0100 0.0100 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 10 10 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0111 0.0111 0.7854\n0.0222 0.0222 0.7854\n0.0333 0.0333 0.7854\n0.0444 0.0444 0.7854\n0.0556 0.0556 0.7854\n0.0667 0.0667 0.7854\n0.0778 0.0778 0.7854\n0.0889 0.0889 0.7854\n0.1000 0.1000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0011 -0.0011 0.7854\n-0.0022 -0.0022 0.7854\n-0.0033 -0.0033 0.7854\n-0.0044 -0.0044 0.7854\n-0.0056 -0.0056 0.7854\n-0.0067 -0.0067 0.7854\n-0.0078 -0.0078 0.7854\n-0.0089 -0.0089 0.7854\n-0.0100 -0.0100 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 25 35 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 35 25 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0011 0.0022 1.1781\n0.0022 0.0044 1.1781\n0.0033 0.0067 1.1781\n0.0044 0.0089 1.1781\n0.0056 0.0111 1.1781\n0.0067 0.0133 1.1781\n0.0078 0.0156 1.1781\n0.0089 0.0178 1.1781\n0.0100 0.0200 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 10 20 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0111 0.0222 1.1781\n0.0222 0.0444 1.1781\n0.0333 0.0667 1.1781\n0.0444 0.0889 1.1781\n0.0556 0.1111 1.1781\n0.0667 0.1333 1.1781\n0.0778 0.1556 1.1781\n0.0889 0.1778 1.1781\n0.1000 0.2000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0011 -0.0022 1.1781\n-0.0022 -0.0044 1.1781\n-0.0033 -0.0067 1.1781\n-0.0044 -0.0089 1.1781\n-0.0056 -0.0111 1.1781\n-0.0067 -0.0133 1.1781\n-0.0078 -0.0156 1.1781\n-0.0089 -0.0178 1.1781\n-0.0100 -0.0200 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 20 25 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 10 35 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0011 1.5708\n0.0000 0.0022 1.5708\n0.0000 0.0033 1.5708\n0.0000 0.0044 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0067 1.5708\n0.0000 0.0078 1.5708\n0.0000 0.0089 1.5708\n0.0000 0.0100 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 20 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0667 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1111 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1556 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0011 1.5708\n0.0000 -0.0022 1.5708\n0.0000 -0.0033 1.5708\n0.0000 -0.0044 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0067 1.5708\n0.0000 -0.0078 1.5708\n0.0000 -0.0089 1.5708\n0.0000 -0.0100 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -5 40 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 5 40 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0011 0.0022 1.9635\n-0.0022 0.0044 1.9635\n-0.0033 0.0067 1.9635\n-0.0044 0.0089 1.9635\n-0.0056 0.0111 1.9635\n-0.0067 0.0133 1.9635\n-0.0078 0.0156 1.9635\n-0.0089 0.0178 1.9635\n-0.0100 0.0200 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -10 20 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0111 0.0222 1.9635\n-0.0222 0.0444 1.9635\n-0.0333 0.0667 1.9635\n-0.0444 0.0889 1.9635\n-0.0556 0.1111 1.9635\n-0.0667 0.1333 1.9635\n-0.0778 0.1556 1.9635\n-0.0889 0.1778 1.9635\n-0.1000 0.2000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0011 -0.0022 1.9635\n0.0022 -0.0044 1.9635\n0.0033 -0.0067 1.9635\n0.0044 -0.0089 1.9635\n0.0056 -0.0111 1.9635\n0.0067 -0.0133 1.9635\n0.0078 -0.0156 1.9635\n0.0089 -0.0178 1.9635\n0.0100 -0.0200 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -20 25 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -10 35 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0011 0.0011 2.3562\n-0.0022 0.0022 2.3562\n-0.0033 0.0033 2.3562\n-0.0044 0.0044 2.3562\n-0.0056 0.0056 2.3562\n-0.0067 0.0067 2.3562\n-0.0078 0.0078 2.3562\n-0.0089 0.0089 2.3562\n-0.0100 0.0100 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -10 10 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0111 0.0111 2.3562\n-0.0222 0.0222 2.3562\n-0.0333 0.0333 2.3562\n-0.0444 0.0444 2.3562\n-0.0556 0.0556 2.3562\n-0.0667 0.0667 2.3562\n-0.0778 0.0778 2.3562\n-0.0889 0.0889 2.3562\n-0.1000 0.1000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0011 -0.0011 2.3562\n0.0022 -0.0022 2.3562\n0.0033 -0.0033 2.3562\n0.0044 -0.0044 2.3562\n0.0056 -0.0056 2.3562\n0.0067 -0.0067 2.3562\n0.0078 -0.0078 2.3562\n0.0089 -0.0089 2.3562\n0.0100 -0.0100 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -35 25 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -25 35 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0022 0.0011 2.7489\n-0.0044 0.0022 2.7489\n-0.0067 0.0033 2.7489\n-0.0089 0.0044 2.7489\n-0.0111 0.0056 2.7489\n-0.0133 0.0067 2.7489\n-0.0156 0.0078 2.7489\n-0.0178 0.0089 2.7489\n-0.0200 0.0100 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -20 10 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0222 0.0111 2.7489\n-0.0444 0.0222 2.7489\n-0.0667 0.0333 2.7489\n-0.0889 0.0444 2.7489\n-0.1111 0.0556 2.7489\n-0.1333 0.0667 2.7489\n-0.1556 0.0778 2.7489\n-0.1778 0.0889 2.7489\n-0.2000 0.1000 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0022 -0.0011 2.7489\n0.0044 -0.0022 2.7489\n0.0067 -0.0033 2.7489\n0.0089 -0.0044 2.7489\n0.0111 -0.0056 2.7489\n0.0133 -0.0067 2.7489\n0.0156 -0.0078 2.7489\n0.0178 -0.0089 2.7489\n0.0200 -0.0100 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -25 20 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -35 10 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0011 0.0000 3.1416\n-0.0022 0.0000 3.1416\n-0.0033 0.0000 3.1416\n-0.0044 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0067 0.0000 3.1416\n-0.0078 0.0000 3.1416\n-0.0089 0.0000 3.1416\n-0.0100 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -20 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0667 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1111 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1556 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0011 0.0000 3.1416\n0.0022 0.0000 3.1416\n0.0033 0.0000 3.1416\n0.0044 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0067 0.0000 3.1416\n0.0078 0.0000 3.1416\n0.0089 0.0000 3.1416\n0.0100 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -40 -5 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -40 5 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0022 -0.0011 3.5343\n-0.0044 -0.0022 3.5343\n-0.0067 -0.0033 3.5343\n-0.0089 -0.0044 3.5343\n-0.0111 -0.0056 3.5343\n-0.0133 -0.0067 3.5343\n-0.0156 -0.0078 3.5343\n-0.0178 -0.0089 3.5343\n-0.0200 -0.0100 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -20 -10 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0222 -0.0111 3.5343\n-0.0444 -0.0222 3.5343\n-0.0667 -0.0333 3.5343\n-0.0889 -0.0444 3.5343\n-0.1111 -0.0556 3.5343\n-0.1333 -0.0667 3.5343\n-0.1556 -0.0778 3.5343\n-0.1778 -0.0889 3.5343\n-0.2000 -0.1000 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0022 0.0011 3.5343\n0.0044 0.0022 3.5343\n0.0067 0.0033 3.5343\n0.0089 0.0044 3.5343\n0.0111 0.0056 3.5343\n0.0133 0.0067 3.5343\n0.0156 0.0078 3.5343\n0.0178 0.0089 3.5343\n0.0200 0.0100 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -25 -20 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -35 -10 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0011 -0.0011 3.9270\n-0.0022 -0.0022 3.9270\n-0.0033 -0.0033 3.9270\n-0.0044 -0.0044 3.9270\n-0.0056 -0.0056 3.9270\n-0.0067 -0.0067 3.9270\n-0.0078 -0.0078 3.9270\n-0.0089 -0.0089 3.9270\n-0.0100 -0.0100 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -10 -10 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0111 -0.0111 3.9270\n-0.0222 -0.0222 3.9270\n-0.0333 -0.0333 3.9270\n-0.0444 -0.0444 3.9270\n-0.0556 -0.0556 3.9270\n-0.0667 -0.0667 3.9270\n-0.0778 -0.0778 3.9270\n-0.0889 -0.0889 3.9270\n-0.1000 -0.1000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0011 0.0011 3.9270\n0.0022 0.0022 3.9270\n0.0033 0.0033 3.9270\n0.0044 0.0044 3.9270\n0.0056 0.0056 3.9270\n0.0067 0.0067 3.9270\n0.0078 0.0078 3.9270\n0.0089 0.0089 3.9270\n0.0100 0.0100 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -25 -35 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -35 -25 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0011 -0.0022 4.3197\n-0.0022 -0.0044 4.3197\n-0.0033 -0.0067 4.3197\n-0.0044 -0.0089 4.3197\n-0.0056 -0.0111 4.3197\n-0.0067 -0.0133 4.3197\n-0.0078 -0.0156 4.3197\n-0.0089 -0.0178 4.3197\n-0.0100 -0.0200 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -10 -20 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0111 -0.0222 4.3197\n-0.0222 -0.0444 4.3197\n-0.0333 -0.0667 4.3197\n-0.0444 -0.0889 4.3197\n-0.0556 -0.1111 4.3197\n-0.0667 -0.1333 4.3197\n-0.0778 -0.1556 4.3197\n-0.0889 -0.1778 4.3197\n-0.1000 -0.2000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0011 0.0022 4.3197\n0.0022 0.0044 4.3197\n0.0033 0.0067 4.3197\n0.0044 0.0089 4.3197\n0.0056 0.0111 4.3197\n0.0067 0.0133 4.3197\n0.0078 0.0156 4.3197\n0.0089 0.0178 4.3197\n0.0100 0.0200 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -20 -25 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -10 -35 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0011 4.7124\n0.0000 -0.0022 4.7124\n0.0000 -0.0033 4.7124\n0.0000 -0.0044 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0067 4.7124\n0.0000 -0.0078 4.7124\n0.0000 -0.0089 4.7124\n0.0000 -0.0100 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -20 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0667 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1111 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1556 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0011 4.7124\n0.0000 0.0022 4.7124\n0.0000 0.0033 4.7124\n0.0000 0.0044 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0067 4.7124\n0.0000 0.0078 4.7124\n0.0000 0.0089 4.7124\n0.0000 0.0100 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 5 -40 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0452 4.7124\n0.0000 -0.0904 4.7124\n0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -5 -40 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0011 -0.0022 5.1051\n0.0022 -0.0044 5.1051\n0.0033 -0.0067 5.1051\n0.0044 -0.0089 5.1051\n0.0056 -0.0111 5.1051\n0.0067 -0.0133 5.1051\n0.0078 -0.0156 5.1051\n0.0089 -0.0178 5.1051\n0.0100 -0.0200 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 10 -20 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0111 -0.0222 5.1051\n0.0222 -0.0444 5.1051\n0.0333 -0.0667 5.1051\n0.0444 -0.0889 5.1051\n0.0556 -0.1111 5.1051\n0.0667 -0.1333 5.1051\n0.0778 -0.1556 5.1051\n0.0889 -0.1778 5.1051\n0.1000 -0.2000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0011 0.0022 5.1051\n-0.0022 0.0044 5.1051\n-0.0033 0.0067 5.1051\n-0.0044 0.0089 5.1051\n-0.0056 0.0111 5.1051\n-0.0067 0.0133 5.1051\n-0.0078 0.0156 5.1051\n-0.0089 0.0178 5.1051\n-0.0100 0.0200 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 20 -25 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 10 -35 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0011 -0.0011 5.4978\n0.0022 -0.0022 5.4978\n0.0033 -0.0033 5.4978\n0.0044 -0.0044 5.4978\n0.0056 -0.0056 5.4978\n0.0067 -0.0067 5.4978\n0.0078 -0.0078 5.4978\n0.0089 -0.0089 5.4978\n0.0100 -0.0100 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 10 -10 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0111 -0.0111 5.4978\n0.0222 -0.0222 5.4978\n0.0333 -0.0333 5.4978\n0.0444 -0.0444 5.4978\n0.0556 -0.0556 5.4978\n0.0667 -0.0667 5.4978\n0.0778 -0.0778 5.4978\n0.0889 -0.0889 5.4978\n0.1000 -0.1000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0011 0.0011 5.4978\n-0.0022 0.0022 5.4978\n-0.0033 0.0033 5.4978\n-0.0044 0.0044 5.4978\n-0.0056 0.0056 5.4978\n-0.0067 0.0067 5.4978\n-0.0078 0.0078 5.4978\n-0.0089 0.0089 5.4978\n-0.0100 0.0100 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 35 -25 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 25 -35 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0022 -0.0011 5.8905\n0.0044 -0.0022 5.8905\n0.0067 -0.0033 5.8905\n0.0089 -0.0044 5.8905\n0.0111 -0.0056 5.8905\n0.0133 -0.0067 5.8905\n0.0156 -0.0078 5.8905\n0.0178 -0.0089 5.8905\n0.0200 -0.0100 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 20 -10 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0222 -0.0111 5.8905\n0.0444 -0.0222 5.8905\n0.0667 -0.0333 5.8905\n0.0889 -0.0444 5.8905\n0.1111 -0.0556 5.8905\n0.1333 -0.0667 5.8905\n0.1556 -0.0778 5.8905\n0.1778 -0.0889 5.8905\n0.2000 -0.1000 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0022 0.0011 5.8905\n-0.0044 0.0022 5.8905\n-0.0067 0.0033 5.8905\n-0.0089 0.0044 5.8905\n-0.0111 0.0056 5.8905\n-0.0133 0.0067 5.8905\n-0.0156 0.0078 5.8905\n-0.0178 0.0089 5.8905\n-0.0200 0.0100 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 25 -20 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 35 -10 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_2_5cm.mprim",
    "content": "resolution_m: 0.025000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0028 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0083 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0139 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0194 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0250 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 12 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0667 0.0000 0.0000\n0.1000 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1667 0.0000 0.0000\n0.2000 0.0000 0.0000\n0.2333 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0028 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0083 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0139 0.0000 0.0000\n-0.0167 0.0000 0.0000\n-0.0194 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0250 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 16 2 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 16 -2 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0056 0.0028 0.3927\n0.0111 0.0056 0.3927\n0.0167 0.0083 0.3927\n0.0222 0.0111 0.3927\n0.0278 0.0139 0.3927\n0.0333 0.0167 0.3927\n0.0389 0.0194 0.3927\n0.0444 0.0222 0.3927\n0.0500 0.0250 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 12 6 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0056 -0.0028 0.3927\n-0.0111 -0.0056 0.3927\n-0.0167 -0.0083 0.3927\n-0.0222 -0.0111 0.3927\n-0.0278 -0.0139 0.3927\n-0.0333 -0.0167 0.3927\n-0.0389 -0.0194 0.3927\n-0.0444 -0.0222 0.3927\n-0.0500 -0.0250 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 10 8 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 14 4 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 -0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0028 0.0028 0.7854\n0.0056 0.0056 0.7854\n0.0083 0.0083 0.7854\n0.0111 0.0111 0.7854\n0.0139 0.0139 0.7854\n0.0167 0.0167 0.7854\n0.0194 0.0194 0.7854\n0.0222 0.0222 0.7854\n0.0250 0.0250 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 12 12 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0028 -0.0028 0.7854\n-0.0056 -0.0056 0.7854\n-0.0083 -0.0083 0.7854\n-0.0111 -0.0111 0.7854\n-0.0139 -0.0139 0.7854\n-0.0167 -0.0167 0.7854\n-0.0194 -0.0194 0.7854\n-0.0222 -0.0222 0.7854\n-0.0250 -0.0250 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 10 14 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 14 10 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0028 0.0056 1.1781\n0.0056 0.0111 1.1781\n0.0083 0.0167 1.1781\n0.0111 0.0222 1.1781\n0.0139 0.0278 1.1781\n0.0167 0.0333 1.1781\n0.0194 0.0389 1.1781\n0.0222 0.0444 1.1781\n0.0250 0.0500 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 6 12 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0028 -0.0056 1.1781\n-0.0056 -0.0111 1.1781\n-0.0083 -0.0167 1.1781\n-0.0111 -0.0222 1.1781\n-0.0139 -0.0278 1.1781\n-0.0167 -0.0333 1.1781\n-0.0194 -0.0389 1.1781\n-0.0222 -0.0444 1.1781\n-0.0250 -0.0500 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 8 10 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 4 14 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0028 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0083 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0139 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0194 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0250 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 12 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0667 1.5708\n0.0000 0.1000 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1667 1.5708\n0.0000 0.2000 1.5708\n0.0000 0.2333 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0028 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0083 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0139 1.5708\n0.0000 -0.0167 1.5708\n0.0000 -0.0194 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0250 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -2 16 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 2 16 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0028 0.0056 1.9635\n-0.0056 0.0111 1.9635\n-0.0083 0.0167 1.9635\n-0.0111 0.0222 1.9635\n-0.0139 0.0278 1.9635\n-0.0167 0.0333 1.9635\n-0.0194 0.0389 1.9635\n-0.0222 0.0444 1.9635\n-0.0250 0.0500 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -6 12 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0028 -0.0056 1.9635\n0.0056 -0.0111 1.9635\n0.0083 -0.0167 1.9635\n0.0111 -0.0222 1.9635\n0.0139 -0.0278 1.9635\n0.0167 -0.0333 1.9635\n0.0194 -0.0389 1.9635\n0.0222 -0.0444 1.9635\n0.0250 -0.0500 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -8 10 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -4 14 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0028 0.0028 2.3562\n-0.0056 0.0056 2.3562\n-0.0083 0.0083 2.3562\n-0.0111 0.0111 2.3562\n-0.0139 0.0139 2.3562\n-0.0167 0.0167 2.3562\n-0.0194 0.0194 2.3562\n-0.0222 0.0222 2.3562\n-0.0250 0.0250 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -12 12 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0028 -0.0028 2.3562\n0.0056 -0.0056 2.3562\n0.0083 -0.0083 2.3562\n0.0111 -0.0111 2.3562\n0.0139 -0.0139 2.3562\n0.0167 -0.0167 2.3562\n0.0194 -0.0194 2.3562\n0.0222 -0.0222 2.3562\n0.0250 -0.0250 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -14 10 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -10 14 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0056 0.0028 2.7489\n-0.0111 0.0056 2.7489\n-0.0167 0.0083 2.7489\n-0.0222 0.0111 2.7489\n-0.0278 0.0139 2.7489\n-0.0333 0.0167 2.7489\n-0.0389 0.0194 2.7489\n-0.0444 0.0222 2.7489\n-0.0500 0.0250 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -12 6 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0056 -0.0028 2.7489\n0.0111 -0.0056 2.7489\n0.0167 -0.0083 2.7489\n0.0222 -0.0111 2.7489\n0.0278 -0.0139 2.7489\n0.0333 -0.0167 2.7489\n0.0389 -0.0194 2.7489\n0.0444 -0.0222 2.7489\n0.0500 -0.0250 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -10 8 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -14 4 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0028 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0083 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0139 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0194 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0250 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -12 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0667 0.0000 3.1416\n-0.1000 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1667 0.0000 3.1416\n-0.2000 0.0000 3.1416\n-0.2333 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0028 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0083 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0139 0.0000 3.1416\n0.0167 0.0000 3.1416\n0.0194 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0250 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -16 -2 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -16 2 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0056 -0.0028 3.5343\n-0.0111 -0.0056 3.5343\n-0.0167 -0.0083 3.5343\n-0.0222 -0.0111 3.5343\n-0.0278 -0.0139 3.5343\n-0.0333 -0.0167 3.5343\n-0.0389 -0.0194 3.5343\n-0.0444 -0.0222 3.5343\n-0.0500 -0.0250 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -12 -6 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0056 0.0028 3.5343\n0.0111 0.0056 3.5343\n0.0167 0.0083 3.5343\n0.0222 0.0111 3.5343\n0.0278 0.0139 3.5343\n0.0333 0.0167 3.5343\n0.0389 0.0194 3.5343\n0.0444 0.0222 3.5343\n0.0500 0.0250 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -10 -8 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -14 -4 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0028 -0.0028 3.9270\n-0.0056 -0.0056 3.9270\n-0.0083 -0.0083 3.9270\n-0.0111 -0.0111 3.9270\n-0.0139 -0.0139 3.9270\n-0.0167 -0.0167 3.9270\n-0.0194 -0.0194 3.9270\n-0.0222 -0.0222 3.9270\n-0.0250 -0.0250 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -12 -12 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0028 0.0028 3.9270\n0.0056 0.0056 3.9270\n0.0083 0.0083 3.9270\n0.0111 0.0111 3.9270\n0.0139 0.0139 3.9270\n0.0167 0.0167 3.9270\n0.0194 0.0194 3.9270\n0.0222 0.0222 3.9270\n0.0250 0.0250 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -10 -14 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -14 -10 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0028 -0.0056 4.3197\n-0.0056 -0.0111 4.3197\n-0.0083 -0.0167 4.3197\n-0.0111 -0.0222 4.3197\n-0.0139 -0.0278 4.3197\n-0.0167 -0.0333 4.3197\n-0.0194 -0.0389 4.3197\n-0.0222 -0.0444 4.3197\n-0.0250 -0.0500 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -6 -12 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0028 0.0056 4.3197\n0.0056 0.0111 4.3197\n0.0083 0.0167 4.3197\n0.0111 0.0222 4.3197\n0.0139 0.0278 4.3197\n0.0167 0.0333 4.3197\n0.0194 0.0389 4.3197\n0.0222 0.0444 4.3197\n0.0250 0.0500 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -8 -10 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -4 -14 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0028 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0083 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0139 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0194 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0250 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -12 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0667 4.7124\n0.0000 -0.1000 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1667 4.7124\n0.0000 -0.2000 4.7124\n0.0000 -0.2333 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0028 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0083 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0139 4.7124\n0.0000 0.0167 4.7124\n0.0000 0.0194 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0250 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 2 -16 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0452 4.7124\n0.0000 -0.0904 4.7124\n0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -2 -16 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0028 -0.0056 5.1051\n0.0056 -0.0111 5.1051\n0.0083 -0.0167 5.1051\n0.0111 -0.0222 5.1051\n0.0139 -0.0278 5.1051\n0.0167 -0.0333 5.1051\n0.0194 -0.0389 5.1051\n0.0222 -0.0444 5.1051\n0.0250 -0.0500 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 6 -12 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0028 0.0056 5.1051\n-0.0056 0.0111 5.1051\n-0.0083 0.0167 5.1051\n-0.0111 0.0222 5.1051\n-0.0139 0.0278 5.1051\n-0.0167 0.0333 5.1051\n-0.0194 0.0389 5.1051\n-0.0222 0.0444 5.1051\n-0.0250 0.0500 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 8 -10 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 4 -14 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0028 -0.0028 5.4978\n0.0056 -0.0056 5.4978\n0.0083 -0.0083 5.4978\n0.0111 -0.0111 5.4978\n0.0139 -0.0139 5.4978\n0.0167 -0.0167 5.4978\n0.0194 -0.0194 5.4978\n0.0222 -0.0222 5.4978\n0.0250 -0.0250 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 12 -12 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0028 0.0028 5.4978\n-0.0056 0.0056 5.4978\n-0.0083 0.0083 5.4978\n-0.0111 0.0111 5.4978\n-0.0139 0.0139 5.4978\n-0.0167 0.0167 5.4978\n-0.0194 0.0194 5.4978\n-0.0222 0.0222 5.4978\n-0.0250 0.0250 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 14 -10 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 10 -14 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0056 -0.0028 5.8905\n0.0111 -0.0056 5.8905\n0.0167 -0.0083 5.8905\n0.0222 -0.0111 5.8905\n0.0278 -0.0139 5.8905\n0.0333 -0.0167 5.8905\n0.0389 -0.0194 5.8905\n0.0444 -0.0222 5.8905\n0.0500 -0.0250 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 12 -6 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0056 0.0028 5.8905\n-0.0111 0.0056 5.8905\n-0.0167 0.0083 5.8905\n-0.0222 0.0111 5.8905\n-0.0278 0.0139 5.8905\n-0.0333 0.0167 5.8905\n-0.0389 0.0194 5.8905\n-0.0444 0.0222 5.8905\n-0.0500 0.0250 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 10 -8 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 14 -4 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_2cm.mprim",
    "content": "resolution_m: 0.020000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0022 0.0000 0.0000\n0.0044 0.0000 0.0000\n0.0067 0.0000 0.0000\n0.0089 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0133 0.0000 0.0000\n0.0156 0.0000 0.0000\n0.0178 0.0000 0.0000\n0.0200 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 20 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0022 0.0000 0.0000\n-0.0044 0.0000 0.0000\n-0.0067 0.0000 0.0000\n-0.0089 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0133 0.0000 0.0000\n-0.0156 0.0000 0.0000\n-0.0178 0.0000 0.0000\n-0.0200 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 15 3 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0342 0.0008 0.0434\n0.0683 0.0031 0.0868\n0.1023 0.0069 0.1302\n0.1361 0.0121 0.1736\n0.1696 0.0188 0.2170\n0.2029 0.0270 0.2604\n0.2357 0.0366 0.3038\n0.2681 0.0476 0.3472\n0.3000 0.0600 0.3906\nprimID: 4\nstartangle_c: 0\nendpose_c: 15 -3 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0342 -0.0008 -0.0434\n0.0683 -0.0031 -0.0868\n0.1023 -0.0069 -0.1302\n0.1361 -0.0121 -0.1736\n0.1696 -0.0188 -0.2170\n0.2029 -0.0270 -0.2604\n0.2357 -0.0366 -0.3038\n0.2681 -0.0476 -0.3472\n0.3000 -0.0600 -0.3906\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0044 0.0022 0.3927\n0.0089 0.0044 0.3927\n0.0133 0.0067 0.3927\n0.0178 0.0089 0.3927\n0.0222 0.0111 0.3927\n0.0267 0.0133 0.3927\n0.0311 0.0156 0.3927\n0.0356 0.0178 0.3927\n0.0400 0.0200 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 15 8 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0178 0.3927\n0.0667 0.0356 0.3927\n0.1000 0.0533 0.3927\n0.1333 0.0711 0.3927\n0.1667 0.0889 0.3927\n0.2000 0.1067 0.3927\n0.2333 0.1244 0.3927\n0.2667 0.1422 0.3927\n0.3000 0.1600 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0044 -0.0022 0.3927\n-0.0089 -0.0044 0.3927\n-0.0133 -0.0067 0.3927\n-0.0178 -0.0089 0.3927\n-0.0222 -0.0111 0.3927\n-0.0267 -0.0133 0.3927\n-0.0311 -0.0156 0.3927\n-0.0356 -0.0178 0.3927\n-0.0400 -0.0200 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 12 10 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0285 0.0188 0.4210\n0.0566 0.0385 0.4492\n0.0842 0.0590 0.4775\n0.1115 0.0804 0.5057\n0.1382 0.1027 0.5340\n0.1645 0.1258 0.5623\n0.1902 0.1497 0.5905\n0.2154 0.1745 0.6188\n0.2400 0.2000 0.6470\nprimID: 4\nstartangle_c: 1\nendpose_c: 18 5 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0387 0.0160 0.3927\n0.0774 0.0320 0.3927\n0.1161 0.0481 0.3927\n0.1549 0.0636 0.3512\n0.1947 0.0766 0.2809\n0.2353 0.0868 0.2107\n0.2765 0.0941 0.1405\n0.3182 0.0985 0.0702\n0.3600 0.1000 0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0022 0.0022 0.7854\n0.0044 0.0044 0.7854\n0.0067 0.0067 0.7854\n0.0089 0.0089 0.7854\n0.0111 0.0111 0.7854\n0.0133 0.0133 0.7854\n0.0156 0.0156 0.7854\n0.0178 0.0178 0.7854\n0.0200 0.0200 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 15 15 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0022 -0.0022 0.7854\n-0.0044 -0.0044 0.7854\n-0.0067 -0.0067 0.7854\n-0.0089 -0.0089 0.7854\n-0.0111 -0.0111 0.7854\n-0.0133 -0.0133 0.7854\n-0.0156 -0.0156 0.7854\n-0.0178 -0.0178 0.7854\n-0.0200 -0.0200 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 12 18 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0334 0.0350 0.8288\n0.0652 0.0714 0.8722\n0.0954 0.1092 0.9156\n0.1240 0.1482 0.9590\n0.1508 0.1885 1.0024\n0.1759 0.2299 1.0458\n0.1991 0.2723 1.0892\n0.2205 0.3157 1.1326\n0.2400 0.3600 1.1760\nprimID: 4\nstartangle_c: 2\nendpose_c: 18 12 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0350 0.0334 0.7420\n0.0714 0.0652 0.6986\n0.1092 0.0954 0.6552\n0.1482 0.1240 0.6118\n0.1885 0.1508 0.5684\n0.2299 0.1759 0.5250\n0.2723 0.1991 0.4816\n0.3157 0.2205 0.4382\n0.3600 0.2400 0.3948\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0022 0.0044 1.1781\n0.0044 0.0089 1.1781\n0.0067 0.0133 1.1781\n0.0089 0.0178 1.1781\n0.0111 0.0222 1.1781\n0.0133 0.0267 1.1781\n0.0156 0.0311 1.1781\n0.0178 0.0356 1.1781\n0.0200 0.0400 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 8 15 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0178 0.0333 1.1781\n0.0356 0.0667 1.1781\n0.0533 0.1000 1.1781\n0.0711 0.1333 1.1781\n0.0889 0.1667 1.1781\n0.1067 0.2000 1.1781\n0.1244 0.2333 1.1781\n0.1422 0.2667 1.1781\n0.1600 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0022 -0.0044 1.1781\n-0.0044 -0.0089 1.1781\n-0.0067 -0.0133 1.1781\n-0.0089 -0.0178 1.1781\n-0.0111 -0.0222 1.1781\n-0.0133 -0.0267 1.1781\n-0.0156 -0.0311 1.1781\n-0.0178 -0.0356 1.1781\n-0.0200 -0.0400 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 10 12 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0188 0.0285 1.1498\n0.0385 0.0566 1.1216\n0.0590 0.0842 1.0933\n0.0804 0.1115 1.0651\n0.1027 0.1382 1.0368\n0.1258 0.1645 1.0085\n0.1497 0.1902 0.9803\n0.1745 0.2154 0.9520\n0.2000 0.2400 0.9238\nprimID: 4\nstartangle_c: 3\nendpose_c: 5 18 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0160 0.0387 1.1781\n0.0320 0.0774 1.1781\n0.0481 0.1161 1.1781\n0.0636 0.1549 1.2196\n0.0766 0.1947 1.2898\n0.0868 0.2353 1.3601\n0.0941 0.2765 1.4303\n0.0985 0.3182 1.5006\n0.1000 0.3600 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0022 1.5708\n0.0000 0.0044 1.5708\n0.0000 0.0067 1.5708\n0.0000 0.0089 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0133 1.5708\n0.0000 0.0156 1.5708\n0.0000 0.0178 1.5708\n0.0000 0.0200 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 20 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0022 1.5708\n0.0000 -0.0044 1.5708\n0.0000 -0.0067 1.5708\n0.0000 -0.0089 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0133 1.5708\n0.0000 -0.0156 1.5708\n0.0000 -0.0178 1.5708\n0.0000 -0.0200 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -3 15 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n-0.0008 0.0342 1.6142\n-0.0031 0.0683 1.6576\n-0.0069 0.1023 1.7010\n-0.0121 0.1361 1.7444\n-0.0188 0.1696 1.7878\n-0.0270 0.2029 1.8312\n-0.0366 0.2357 1.8746\n-0.0476 0.2681 1.9180\n-0.0600 0.3000 1.9614\nprimID: 4\nstartangle_c: 4\nendpose_c: 3 15 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0008 0.0342 1.5274\n0.0031 0.0683 1.4840\n0.0069 0.1023 1.4406\n0.0121 0.1361 1.3972\n0.0188 0.1696 1.3538\n0.0270 0.2029 1.3104\n0.0366 0.2357 1.2670\n0.0476 0.2681 1.2236\n0.0600 0.3000 1.1802\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0022 0.0044 1.9635\n-0.0044 0.0089 1.9635\n-0.0067 0.0133 1.9635\n-0.0089 0.0178 1.9635\n-0.0111 0.0222 1.9635\n-0.0133 0.0267 1.9635\n-0.0156 0.0311 1.9635\n-0.0178 0.0356 1.9635\n-0.0200 0.0400 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -8 15 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0178 0.0333 1.9635\n-0.0356 0.0667 1.9635\n-0.0533 0.1000 1.9635\n-0.0711 0.1333 1.9635\n-0.0889 0.1667 1.9635\n-0.1067 0.2000 1.9635\n-0.1244 0.2333 1.9635\n-0.1422 0.2667 1.9635\n-0.1600 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0022 -0.0044 1.9635\n0.0044 -0.0089 1.9635\n0.0067 -0.0133 1.9635\n0.0089 -0.0178 1.9635\n0.0111 -0.0222 1.9635\n0.0133 -0.0267 1.9635\n0.0156 -0.0311 1.9635\n0.0178 -0.0356 1.9635\n0.0200 -0.0400 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -10 12 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0188 0.0285 1.9918\n-0.0385 0.0566 2.0200\n-0.0590 0.0842 2.0483\n-0.0804 0.1115 2.0765\n-0.1027 0.1382 2.1048\n-0.1258 0.1645 2.1330\n-0.1497 0.1902 2.1613\n-0.1745 0.2154 2.1896\n-0.2000 0.2400 2.2178\nprimID: 4\nstartangle_c: 5\nendpose_c: -5 18 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0160 0.0387 1.9635\n-0.0320 0.0774 1.9635\n-0.0481 0.1161 1.9635\n-0.0636 0.1549 1.9220\n-0.0766 0.1947 1.8517\n-0.0868 0.2353 1.7815\n-0.0941 0.2765 1.7113\n-0.0985 0.3182 1.6410\n-0.1000 0.3600 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0022 0.0022 2.3562\n-0.0044 0.0044 2.3562\n-0.0067 0.0067 2.3562\n-0.0089 0.0089 2.3562\n-0.0111 0.0111 2.3562\n-0.0133 0.0133 2.3562\n-0.0156 0.0156 2.3562\n-0.0178 0.0178 2.3562\n-0.0200 0.0200 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -15 15 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0022 -0.0022 2.3562\n0.0044 -0.0044 2.3562\n0.0067 -0.0067 2.3562\n0.0089 -0.0089 2.3562\n0.0111 -0.0111 2.3562\n0.0133 -0.0133 2.3562\n0.0156 -0.0156 2.3562\n0.0178 -0.0178 2.3562\n0.0200 -0.0200 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -18 12 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0350 0.0334 2.3996\n-0.0714 0.0652 2.4430\n-0.1092 0.0954 2.4864\n-0.1482 0.1240 2.5298\n-0.1885 0.1508 2.5732\n-0.2299 0.1759 2.6166\n-0.2723 0.1991 2.6600\n-0.3157 0.2205 2.7034\n-0.3600 0.2400 2.7468\nprimID: 4\nstartangle_c: 6\nendpose_c: -12 18 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0334 0.0350 2.3128\n-0.0652 0.0714 2.2694\n-0.0954 0.1092 2.2260\n-0.1240 0.1482 2.1826\n-0.1508 0.1885 2.1392\n-0.1759 0.2299 2.0958\n-0.1991 0.2723 2.0524\n-0.2205 0.3157 2.0090\n-0.2400 0.3600 1.9656\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0044 0.0022 2.7489\n-0.0089 0.0044 2.7489\n-0.0133 0.0067 2.7489\n-0.0178 0.0089 2.7489\n-0.0222 0.0111 2.7489\n-0.0267 0.0133 2.7489\n-0.0311 0.0156 2.7489\n-0.0356 0.0178 2.7489\n-0.0400 0.0200 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -15 8 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0178 2.7489\n-0.0667 0.0356 2.7489\n-0.1000 0.0533 2.7489\n-0.1333 0.0711 2.7489\n-0.1667 0.0889 2.7489\n-0.2000 0.1067 2.7489\n-0.2333 0.1244 2.7489\n-0.2667 0.1422 2.7489\n-0.3000 0.1600 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0044 -0.0022 2.7489\n0.0089 -0.0044 2.7489\n0.0133 -0.0067 2.7489\n0.0178 -0.0089 2.7489\n0.0222 -0.0111 2.7489\n0.0267 -0.0133 2.7489\n0.0311 -0.0156 2.7489\n0.0356 -0.0178 2.7489\n0.0400 -0.0200 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -12 10 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0285 0.0188 2.7206\n-0.0566 0.0385 2.6924\n-0.0842 0.0590 2.6641\n-0.1115 0.0804 2.6359\n-0.1382 0.1027 2.6076\n-0.1645 0.1258 2.5793\n-0.1902 0.1497 2.5511\n-0.2154 0.1745 2.5228\n-0.2400 0.2000 2.4946\nprimID: 4\nstartangle_c: 7\nendpose_c: -18 5 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0387 0.0160 2.7489\n-0.0774 0.0320 2.7489\n-0.1161 0.0481 2.7489\n-0.1549 0.0636 2.7904\n-0.1947 0.0766 2.8606\n-0.2353 0.0868 2.9309\n-0.2765 0.0941 3.0011\n-0.3182 0.0985 3.0714\n-0.3600 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0022 0.0000 3.1416\n-0.0044 0.0000 3.1416\n-0.0067 0.0000 3.1416\n-0.0089 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0133 0.0000 3.1416\n-0.0156 0.0000 3.1416\n-0.0178 0.0000 3.1416\n-0.0200 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -20 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0022 0.0000 3.1416\n0.0044 0.0000 3.1416\n0.0067 0.0000 3.1416\n0.0089 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0133 0.0000 3.1416\n0.0156 0.0000 3.1416\n0.0178 0.0000 3.1416\n0.0200 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -15 -3 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0342 -0.0008 3.1850\n-0.0683 -0.0031 3.2284\n-0.1023 -0.0069 3.2718\n-0.1361 -0.0121 3.3152\n-0.1696 -0.0188 3.3586\n-0.2029 -0.0270 3.4020\n-0.2357 -0.0366 3.4454\n-0.2681 -0.0476 3.4888\n-0.3000 -0.0600 3.5322\nprimID: 4\nstartangle_c: 8\nendpose_c: -15 3 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0342 0.0008 3.0982\n-0.0683 0.0031 3.0548\n-0.1023 0.0069 3.0114\n-0.1361 0.0121 2.9680\n-0.1696 0.0188 2.9246\n-0.2029 0.0270 2.8812\n-0.2357 0.0366 2.8378\n-0.2681 0.0476 2.7944\n-0.3000 0.0600 2.7510\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0044 -0.0022 3.5343\n-0.0089 -0.0044 3.5343\n-0.0133 -0.0067 3.5343\n-0.0178 -0.0089 3.5343\n-0.0222 -0.0111 3.5343\n-0.0267 -0.0133 3.5343\n-0.0311 -0.0156 3.5343\n-0.0356 -0.0178 3.5343\n-0.0400 -0.0200 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -15 -8 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0178 3.5343\n-0.0667 -0.0356 3.5343\n-0.1000 -0.0533 3.5343\n-0.1333 -0.0711 3.5343\n-0.1667 -0.0889 3.5343\n-0.2000 -0.1067 3.5343\n-0.2333 -0.1244 3.5343\n-0.2667 -0.1422 3.5343\n-0.3000 -0.1600 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0044 0.0022 3.5343\n0.0089 0.0044 3.5343\n0.0133 0.0067 3.5343\n0.0178 0.0089 3.5343\n0.0222 0.0111 3.5343\n0.0267 0.0133 3.5343\n0.0311 0.0156 3.5343\n0.0356 0.0178 3.5343\n0.0400 0.0200 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -12 -10 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0285 -0.0188 3.5626\n-0.0566 -0.0385 3.5908\n-0.0842 -0.0590 3.6191\n-0.1115 -0.0804 3.6473\n-0.1382 -0.1027 3.6756\n-0.1645 -0.1258 3.7038\n-0.1902 -0.1497 3.7321\n-0.2154 -0.1745 3.7604\n-0.2400 -0.2000 3.7886\nprimID: 4\nstartangle_c: 9\nendpose_c: -18 -5 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0387 -0.0160 3.5343\n-0.0774 -0.0320 3.5343\n-0.1161 -0.0481 3.5343\n-0.1549 -0.0636 3.4928\n-0.1947 -0.0766 3.4225\n-0.2353 -0.0868 3.3523\n-0.2765 -0.0941 3.2821\n-0.3182 -0.0985 3.2118\n-0.3600 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0022 -0.0022 3.9270\n-0.0044 -0.0044 3.9270\n-0.0067 -0.0067 3.9270\n-0.0089 -0.0089 3.9270\n-0.0111 -0.0111 3.9270\n-0.0133 -0.0133 3.9270\n-0.0156 -0.0156 3.9270\n-0.0178 -0.0178 3.9270\n-0.0200 -0.0200 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -15 -15 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0022 0.0022 3.9270\n0.0044 0.0044 3.9270\n0.0067 0.0067 3.9270\n0.0089 0.0089 3.9270\n0.0111 0.0111 3.9270\n0.0133 0.0133 3.9270\n0.0156 0.0156 3.9270\n0.0178 0.0178 3.9270\n0.0200 0.0200 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -12 -18 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0334 -0.0350 3.9704\n-0.0652 -0.0714 4.0138\n-0.0954 -0.1092 4.0572\n-0.1240 -0.1482 4.1006\n-0.1508 -0.1885 4.1440\n-0.1759 -0.2299 4.1874\n-0.1991 -0.2723 4.2308\n-0.2205 -0.3157 4.2742\n-0.2400 -0.3600 4.3176\nprimID: 4\nstartangle_c: 10\nendpose_c: -18 -12 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0350 -0.0334 3.8836\n-0.0714 -0.0652 3.8402\n-0.1092 -0.0954 3.7968\n-0.1482 -0.1240 3.7534\n-0.1885 -0.1508 3.7100\n-0.2299 -0.1759 3.6666\n-0.2723 -0.1991 3.6232\n-0.3157 -0.2205 3.5798\n-0.3600 -0.2400 3.5364\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0022 -0.0044 4.3197\n-0.0044 -0.0089 4.3197\n-0.0067 -0.0133 4.3197\n-0.0089 -0.0178 4.3197\n-0.0111 -0.0222 4.3197\n-0.0133 -0.0267 4.3197\n-0.0156 -0.0311 4.3197\n-0.0178 -0.0356 4.3197\n-0.0200 -0.0400 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -8 -15 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0178 -0.0333 4.3197\n-0.0356 -0.0667 4.3197\n-0.0533 -0.1000 4.3197\n-0.0711 -0.1333 4.3197\n-0.0889 -0.1667 4.3197\n-0.1067 -0.2000 4.3197\n-0.1244 -0.2333 4.3197\n-0.1422 -0.2667 4.3197\n-0.1600 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0022 0.0044 4.3197\n0.0044 0.0089 4.3197\n0.0067 0.0133 4.3197\n0.0089 0.0178 4.3197\n0.0111 0.0222 4.3197\n0.0133 0.0267 4.3197\n0.0156 0.0311 4.3197\n0.0178 0.0356 4.3197\n0.0200 0.0400 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -10 -12 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0188 -0.0285 4.2914\n-0.0385 -0.0566 4.2632\n-0.0590 -0.0842 4.2349\n-0.0804 -0.1115 4.2067\n-0.1027 -0.1382 4.1784\n-0.1258 -0.1645 4.1501\n-0.1497 -0.1902 4.1219\n-0.1745 -0.2154 4.0936\n-0.2000 -0.2400 4.0654\nprimID: 4\nstartangle_c: 11\nendpose_c: -5 -18 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0160 -0.0387 4.3197\n-0.0320 -0.0774 4.3197\n-0.0481 -0.1161 4.3197\n-0.0636 -0.1549 4.3612\n-0.0766 -0.1947 4.4314\n-0.0868 -0.2353 4.5017\n-0.0941 -0.2765 4.5719\n-0.0985 -0.3182 4.6422\n-0.1000 -0.3600 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0022 4.7124\n0.0000 -0.0044 4.7124\n0.0000 -0.0067 4.7124\n0.0000 -0.0089 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0133 4.7124\n0.0000 -0.0156 4.7124\n0.0000 -0.0178 4.7124\n0.0000 -0.0200 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -20 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0022 4.7124\n0.0000 0.0044 4.7124\n0.0000 0.0067 4.7124\n0.0000 0.0089 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0133 4.7124\n0.0000 0.0156 4.7124\n0.0000 0.0178 4.7124\n0.0000 0.0200 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 3 -15 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0008 -0.0342 4.7558\n0.0031 -0.0683 4.7992\n0.0069 -0.1023 4.8426\n0.0121 -0.1361 4.8860\n0.0188 -0.1696 4.9294\n0.0270 -0.2029 4.9728\n0.0366 -0.2357 5.0162\n0.0476 -0.2681 5.0596\n0.0600 -0.3000 5.1030\nprimID: 4\nstartangle_c: 12\nendpose_c: -3 -15 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0008 -0.0342 4.6690\n-0.0031 -0.0683 4.6256\n-0.0069 -0.1023 4.5822\n-0.0121 -0.1361 4.5388\n-0.0188 -0.1696 4.4954\n-0.0270 -0.2029 4.4520\n-0.0366 -0.2357 4.4086\n-0.0476 -0.2681 4.3652\n-0.0600 -0.3000 4.3218\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0022 -0.0044 5.1051\n0.0044 -0.0089 5.1051\n0.0067 -0.0133 5.1051\n0.0089 -0.0178 5.1051\n0.0111 -0.0222 5.1051\n0.0133 -0.0267 5.1051\n0.0156 -0.0311 5.1051\n0.0178 -0.0356 5.1051\n0.0200 -0.0400 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 8 -15 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0178 -0.0333 5.1051\n0.0356 -0.0667 5.1051\n0.0533 -0.1000 5.1051\n0.0711 -0.1333 5.1051\n0.0889 -0.1667 5.1051\n0.1067 -0.2000 5.1051\n0.1244 -0.2333 5.1051\n0.1422 -0.2667 5.1051\n0.1600 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0022 0.0044 5.1051\n-0.0044 0.0089 5.1051\n-0.0067 0.0133 5.1051\n-0.0089 0.0178 5.1051\n-0.0111 0.0222 5.1051\n-0.0133 0.0267 5.1051\n-0.0156 0.0311 5.1051\n-0.0178 0.0356 5.1051\n-0.0200 0.0400 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 10 -12 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0188 -0.0285 5.1333\n0.0385 -0.0566 5.1616\n0.0590 -0.0842 5.1899\n0.0804 -0.1115 5.2181\n0.1027 -0.1382 5.2464\n0.1258 -0.1645 5.2746\n0.1497 -0.1902 5.3029\n0.1745 -0.2154 5.3312\n0.2000 -0.2400 5.3594\nprimID: 4\nstartangle_c: 13\nendpose_c: 5 -18 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0160 -0.0387 5.1051\n0.0320 -0.0774 5.1051\n0.0481 -0.1161 5.1051\n0.0636 -0.1549 5.0636\n0.0766 -0.1947 4.9933\n0.0868 -0.2353 4.9231\n0.0941 -0.2765 4.8529\n0.0985 -0.3182 4.7826\n0.1000 -0.3600 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0022 -0.0022 5.4978\n0.0044 -0.0044 5.4978\n0.0067 -0.0067 5.4978\n0.0089 -0.0089 5.4978\n0.0111 -0.0111 5.4978\n0.0133 -0.0133 5.4978\n0.0156 -0.0156 5.4978\n0.0178 -0.0178 5.4978\n0.0200 -0.0200 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 15 -15 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0022 0.0022 5.4978\n-0.0044 0.0044 5.4978\n-0.0067 0.0067 5.4978\n-0.0089 0.0089 5.4978\n-0.0111 0.0111 5.4978\n-0.0133 0.0133 5.4978\n-0.0156 0.0156 5.4978\n-0.0178 0.0178 5.4978\n-0.0200 0.0200 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 18 -12 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0350 -0.0334 5.5412\n0.0714 -0.0652 5.5846\n0.1092 -0.0954 5.6280\n0.1482 -0.1240 5.6714\n0.1885 -0.1508 5.7148\n0.2299 -0.1759 5.7582\n0.2723 -0.1991 5.8016\n0.3157 -0.2205 5.8450\n0.3600 -0.2400 5.8884\nprimID: 4\nstartangle_c: 14\nendpose_c: 12 -18 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0334 -0.0350 5.4544\n0.0652 -0.0714 5.4110\n0.0954 -0.1092 5.3676\n0.1240 -0.1482 5.3242\n0.1508 -0.1885 5.2808\n0.1759 -0.2299 5.2374\n0.1991 -0.2723 5.1940\n0.2205 -0.3157 5.1506\n0.2400 -0.3600 5.1072\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 10\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0044 -0.0022 5.8905\n0.0089 -0.0044 5.8905\n0.0133 -0.0067 5.8905\n0.0178 -0.0089 5.8905\n0.0222 -0.0111 5.8905\n0.0267 -0.0133 5.8905\n0.0311 -0.0156 5.8905\n0.0356 -0.0178 5.8905\n0.0400 -0.0200 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 15 -8 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0178 5.8905\n0.0667 -0.0356 5.8905\n0.1000 -0.0533 5.8905\n0.1333 -0.0711 5.8905\n0.1667 -0.0889 5.8905\n0.2000 -0.1067 5.8905\n0.2333 -0.1244 5.8905\n0.2667 -0.1422 5.8905\n0.3000 -0.1600 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 50\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0044 0.0022 5.8905\n-0.0089 0.0044 5.8905\n-0.0133 0.0067 5.8905\n-0.0178 0.0089 5.8905\n-0.0222 0.0111 5.8905\n-0.0267 0.0133 5.8905\n-0.0311 0.0156 5.8905\n-0.0356 0.0178 5.8905\n-0.0400 0.0200 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 12 -10 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0285 -0.0188 5.8622\n0.0566 -0.0385 5.8340\n0.0842 -0.0590 5.8057\n0.1115 -0.0804 5.7775\n0.1382 -0.1027 5.7492\n0.1645 -0.1258 5.7209\n0.1902 -0.1497 5.6927\n0.2154 -0.1745 5.6644\n0.2400 -0.2000 5.6362\nprimID: 4\nstartangle_c: 15\nendpose_c: 18 -5 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0387 -0.0160 5.8905\n0.0774 -0.0320 5.8905\n0.1161 -0.0481 5.8905\n0.1549 -0.0636 5.9320\n0.1947 -0.0766 6.0022\n0.2353 -0.0868 6.0725\n0.2765 -0.0941 6.1427\n0.3182 -0.0985 6.2129\n0.3600 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 100\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.2360\n0.0000 0.0000 4.5815\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.2725\n0.0000 0.0000 2.6180\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.3090\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_5cm.mprim",
    "content": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0056 0.0000 0.0000\n0.0111 0.0000 0.0000\n0.0167 0.0000 0.0000\n0.0222 0.0000 0.0000\n0.0278 0.0000 0.0000\n0.0333 0.0000 0.0000\n0.0389 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0500 0.0000 0.0000\nprimID: 1\nstartangle_c: 0\nendpose_c: 8 0 0\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0444 0.0000 0.0000\n0.0889 0.0000 0.0000\n0.1333 0.0000 0.0000\n0.1778 0.0000 0.0000\n0.2222 0.0000 0.0000\n0.2667 0.0000 0.0000\n0.3111 0.0000 0.0000\n0.3556 0.0000 0.0000\n0.4000 0.0000 0.0000\nprimID: 2\nstartangle_c: 0\nendpose_c: -1 0 0\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 0.0000\n-0.0056 0.0000 0.0000\n-0.0111 0.0000 0.0000\n-0.0167 0.0000 0.0000\n-0.0222 0.0000 0.0000\n-0.0278 0.0000 0.0000\n-0.0333 0.0000 0.0000\n-0.0389 0.0000 0.0000\n-0.0444 0.0000 0.0000\n-0.0500 0.0000 0.0000\nprimID: 3\nstartangle_c: 0\nendpose_c: 8 1 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 -0.0000 0.0000\n0.0904 -0.0000 0.0000\n0.1355 -0.0000 0.0000\n0.1807 0.0008 0.0488\n0.2257 0.0045 0.1176\n0.2703 0.0114 0.1864\n0.3144 0.0213 0.2551\n0.3577 0.0342 0.3239\n0.4000 0.0500 0.3927\nprimID: 4\nstartangle_c: 0\nendpose_c: 8 -1 -1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0452 0.0000 0.0000\n0.0904 0.0000 0.0000\n0.1355 0.0000 0.0000\n0.1807 -0.0008 -0.0488\n0.2257 -0.0045 -0.1176\n0.2703 -0.0114 -0.1864\n0.3144 -0.0213 -0.2551\n0.3577 -0.0342 -0.3239\n0.4000 -0.0500 -0.3927\nprimID: 5\nstartangle_c: 0\nendpose_c: 0 0 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3927\nprimID: 6\nstartangle_c: 0\nendpose_c: 0 0 -1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.0000\n0.0000 0.0000 -0.0436\n0.0000 0.0000 -0.0873\n0.0000 0.0000 -0.1309\n0.0000 0.0000 -0.1745\n0.0000 0.0000 -0.2182\n0.0000 0.0000 -0.2618\n0.0000 0.0000 -0.3054\n0.0000 0.0000 -0.3491\n0.0000 0.0000 -0.3927\nprimID: 0\nstartangle_c: 1\nendpose_c: 2 1 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0111 0.0056 0.3927\n0.0222 0.0111 0.3927\n0.0333 0.0167 0.3927\n0.0444 0.0222 0.3927\n0.0556 0.0278 0.3927\n0.0667 0.0333 0.3927\n0.0778 0.0389 0.3927\n0.0889 0.0444 0.3927\n0.1000 0.0500 0.3927\nprimID: 1\nstartangle_c: 1\nendpose_c: 6 3 1\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0333 0.0167 0.3927\n0.0667 0.0333 0.3927\n0.1000 0.0500 0.3927\n0.1333 0.0667 0.3927\n0.1667 0.0833 0.3927\n0.2000 0.1000 0.3927\n0.2333 0.1167 0.3927\n0.2667 0.1333 0.3927\n0.3000 0.1500 0.3927\nprimID: 2\nstartangle_c: 1\nendpose_c: -2 -1 1\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 0.3927\n-0.0111 -0.0056 0.3927\n-0.0222 -0.0111 0.3927\n-0.0333 -0.0167 0.3927\n-0.0444 -0.0222 0.3927\n-0.0556 -0.0278 0.3927\n-0.0667 -0.0333 0.3927\n-0.0778 -0.0389 0.3927\n-0.0889 -0.0444 0.3927\n-0.1000 -0.0500 0.3927\nprimID: 3\nstartangle_c: 1\nendpose_c: 5 4 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0298 0.0184 0.4230\n0.0592 0.0379 0.4533\n0.0881 0.0583 0.4836\n0.1165 0.0796 0.5139\n0.1444 0.1019 0.5442\n0.1717 0.1251 0.5745\n0.1984 0.1492 0.6048\n0.2245 0.1742 0.6351\n0.2500 0.2000 0.6654\nprimID: 4\nstartangle_c: 1\nendpose_c: 7 2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0377 0.0156 0.3927\n0.0754 0.0312 0.3927\n0.1131 0.0468 0.3927\n0.1508 0.0623 0.3736\n0.1893 0.0758 0.2989\n0.2287 0.0863 0.2242\n0.2687 0.0939 0.1494\n0.3092 0.0985 0.0747\n0.3500 0.1000 -0.0000\nprimID: 5\nstartangle_c: 1\nendpose_c: 0 0 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 1\nendpose_c: 0 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.3927\n0.0000 0.0000 0.3491\n0.0000 0.0000 0.3054\n0.0000 0.0000 0.2618\n0.0000 0.0000 0.2182\n0.0000 0.0000 0.1745\n0.0000 0.0000 0.1309\n0.0000 0.0000 0.0873\n0.0000 0.0000 0.0436\n0.0000 0.0000 0.0000\nprimID: 0\nstartangle_c: 2\nendpose_c: 1 1 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0056 0.0056 0.7854\n0.0111 0.0111 0.7854\n0.0167 0.0167 0.7854\n0.0222 0.0222 0.7854\n0.0278 0.0278 0.7854\n0.0333 0.0333 0.7854\n0.0389 0.0389 0.7854\n0.0444 0.0444 0.7854\n0.0500 0.0500 0.7854\nprimID: 1\nstartangle_c: 2\nendpose_c: 6 6 2\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0333 0.0333 0.7854\n0.0667 0.0667 0.7854\n0.1000 0.1000 0.7854\n0.1333 0.1333 0.7854\n0.1667 0.1667 0.7854\n0.2000 0.2000 0.7854\n0.2333 0.2333 0.7854\n0.2667 0.2667 0.7854\n0.3000 0.3000 0.7854\nprimID: 2\nstartangle_c: 2\nendpose_c: -1 -1 2\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 0.7854\n-0.0056 -0.0056 0.7854\n-0.0111 -0.0111 0.7854\n-0.0167 -0.0167 0.7854\n-0.0222 -0.0222 0.7854\n-0.0278 -0.0278 0.7854\n-0.0333 -0.0333 0.7854\n-0.0389 -0.0389 0.7854\n-0.0444 -0.0444 0.7854\n-0.0500 -0.0500 0.7854\nprimID: 3\nstartangle_c: 2\nendpose_c: 5 7 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0678 0.0684 0.8151\n0.1000 0.1043 0.8669\n0.1302 0.1418 0.9188\n0.1584 0.1809 0.9707\n0.1846 0.2213 1.0225\n0.2086 0.2631 1.0744\n0.2304 0.3060 1.1262\n0.2500 0.3500 1.1781\nprimID: 4\nstartangle_c: 2\nendpose_c: 7 5 1\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0341 0.0341 0.7854\n0.0684 0.0678 0.7557\n0.1043 0.1000 0.7039\n0.1418 0.1302 0.6520\n0.1809 0.1584 0.6001\n0.2213 0.1846 0.5483\n0.2631 0.2086 0.4964\n0.3060 0.2304 0.4446\n0.3500 0.2500 0.3927\nprimID: 5\nstartangle_c: 2\nendpose_c: 0 0 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.9599\n0.0000 0.0000 1.0036\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.1781\nprimID: 6\nstartangle_c: 2\nendpose_c: 0 0 1\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 0.7854\n0.0000 0.0000 0.7418\n0.0000 0.0000 0.6981\n0.0000 0.0000 0.6545\n0.0000 0.0000 0.6109\n0.0000 0.0000 0.5672\n0.0000 0.0000 0.5236\n0.0000 0.0000 0.4800\n0.0000 0.0000 0.4363\n0.0000 0.0000 0.3927\nprimID: 0\nstartangle_c: 3\nendpose_c: 1 2 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0056 0.0111 1.1781\n0.0111 0.0222 1.1781\n0.0167 0.0333 1.1781\n0.0222 0.0444 1.1781\n0.0278 0.0556 1.1781\n0.0333 0.0667 1.1781\n0.0389 0.0778 1.1781\n0.0444 0.0889 1.1781\n0.0500 0.1000 1.1781\nprimID: 1\nstartangle_c: 3\nendpose_c: 3 6 3\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0167 0.0333 1.1781\n0.0333 0.0667 1.1781\n0.0500 0.1000 1.1781\n0.0667 0.1333 1.1781\n0.0833 0.1667 1.1781\n0.1000 0.2000 1.1781\n0.1167 0.2333 1.1781\n0.1333 0.2667 1.1781\n0.1500 0.3000 1.1781\nprimID: 2\nstartangle_c: 3\nendpose_c: -1 -2 3\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 1.1781\n-0.0056 -0.0111 1.1781\n-0.0111 -0.0222 1.1781\n-0.0167 -0.0333 1.1781\n-0.0222 -0.0444 1.1781\n-0.0278 -0.0556 1.1781\n-0.0333 -0.0667 1.1781\n-0.0389 -0.0778 1.1781\n-0.0444 -0.0889 1.1781\n-0.0500 -0.1000 1.1781\nprimID: 3\nstartangle_c: 3\nendpose_c: 4 5 2\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0184 0.0298 1.1478\n0.0379 0.0592 1.1175\n0.0583 0.0881 1.0872\n0.0796 0.1165 1.0569\n0.1019 0.1444 1.0266\n0.1251 0.1717 0.9963\n0.1492 0.1984 0.9660\n0.1742 0.2245 0.9357\n0.2000 0.2500 0.9054\nprimID: 4\nstartangle_c: 3\nendpose_c: 2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0156 0.0377 1.1781\n0.0312 0.0754 1.1781\n0.0468 0.1131 1.1781\n0.0623 0.1508 1.1972\n0.0758 0.1893 1.2719\n0.0863 0.2287 1.3466\n0.0939 0.2687 1.4214\n0.0985 0.3092 1.4961\n0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 3\nendpose_c: 0 0 2\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.1345\n0.0000 0.0000 1.0908\n0.0000 0.0000 1.0472\n0.0000 0.0000 1.0036\n0.0000 0.0000 0.9599\n0.0000 0.0000 0.9163\n0.0000 0.0000 0.8727\n0.0000 0.0000 0.8290\n0.0000 0.0000 0.7854\nprimID: 6\nstartangle_c: 3\nendpose_c: 0 0 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.1781\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 4\nendpose_c: 0 1 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0056 1.5708\n0.0000 0.0111 1.5708\n0.0000 0.0167 1.5708\n0.0000 0.0222 1.5708\n0.0000 0.0278 1.5708\n0.0000 0.0333 1.5708\n0.0000 0.0389 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0500 1.5708\nprimID: 1\nstartangle_c: 4\nendpose_c: 0 8 4\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0444 1.5708\n0.0000 0.0889 1.5708\n0.0000 0.1333 1.5708\n0.0000 0.1778 1.5708\n0.0000 0.2222 1.5708\n0.0000 0.2667 1.5708\n0.0000 0.3111 1.5708\n0.0000 0.3556 1.5708\n0.0000 0.4000 1.5708\nprimID: 2\nstartangle_c: 4\nendpose_c: 0 -1 4\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 -0.0056 1.5708\n0.0000 -0.0111 1.5708\n0.0000 -0.0167 1.5708\n0.0000 -0.0222 1.5708\n0.0000 -0.0278 1.5708\n0.0000 -0.0333 1.5708\n0.0000 -0.0389 1.5708\n0.0000 -0.0444 1.5708\n0.0000 -0.0500 1.5708\nprimID: 3\nstartangle_c: 4\nendpose_c: -1 8 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n-0.0008 0.1807 1.6196\n-0.0045 0.2257 1.6884\n-0.0114 0.2703 1.7572\n-0.0213 0.3144 1.8259\n-0.0342 0.3577 1.8947\n-0.0500 0.4000 1.9635\nprimID: 4\nstartangle_c: 4\nendpose_c: 1 8 3\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0452 1.5708\n0.0000 0.0904 1.5708\n0.0000 0.1355 1.5708\n0.0008 0.1807 1.5220\n0.0045 0.2257 1.4532\n0.0114 0.2703 1.3844\n0.0213 0.3144 1.3156\n0.0342 0.3577 1.2469\n0.0500 0.4000 1.1781\nprimID: 5\nstartangle_c: 4\nendpose_c: 0 0 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.9635\nprimID: 6\nstartangle_c: 4\nendpose_c: 0 0 3\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.5708\n0.0000 0.0000 1.5272\n0.0000 0.0000 1.4835\n0.0000 0.0000 1.4399\n0.0000 0.0000 1.3963\n0.0000 0.0000 1.3526\n0.0000 0.0000 1.3090\n0.0000 0.0000 1.2654\n0.0000 0.0000 1.2217\n0.0000 0.0000 1.1781\nprimID: 0\nstartangle_c: 5\nendpose_c: -1 2 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0056 0.0111 1.9635\n-0.0111 0.0222 1.9635\n-0.0167 0.0333 1.9635\n-0.0222 0.0444 1.9635\n-0.0278 0.0556 1.9635\n-0.0333 0.0667 1.9635\n-0.0389 0.0778 1.9635\n-0.0444 0.0889 1.9635\n-0.0500 0.1000 1.9635\nprimID: 1\nstartangle_c: 5\nendpose_c: -3 6 5\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0167 0.0333 1.9635\n-0.0333 0.0667 1.9635\n-0.0500 0.1000 1.9635\n-0.0667 0.1333 1.9635\n-0.0833 0.1667 1.9635\n-0.1000 0.2000 1.9635\n-0.1167 0.2333 1.9635\n-0.1333 0.2667 1.9635\n-0.1500 0.3000 1.9635\nprimID: 2\nstartangle_c: 5\nendpose_c: 1 -2 5\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0056 -0.0111 1.9635\n0.0111 -0.0222 1.9635\n0.0167 -0.0333 1.9635\n0.0222 -0.0444 1.9635\n0.0278 -0.0556 1.9635\n0.0333 -0.0667 1.9635\n0.0389 -0.0778 1.9635\n0.0444 -0.0889 1.9635\n0.0500 -0.1000 1.9635\nprimID: 3\nstartangle_c: 5\nendpose_c: -4 5 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0184 0.0298 1.9938\n-0.0379 0.0592 2.0241\n-0.0583 0.0881 2.0544\n-0.0796 0.1165 2.0847\n-0.1019 0.1444 2.1150\n-0.1251 0.1717 2.1453\n-0.1492 0.1984 2.1756\n-0.1742 0.2245 2.2059\n-0.2000 0.2500 2.2362\nprimID: 4\nstartangle_c: 5\nendpose_c: -2 7 4\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 1.9635\n-0.0156 0.0377 1.9635\n-0.0312 0.0754 1.9635\n-0.0468 0.1131 1.9635\n-0.0623 0.1508 1.9444\n-0.0758 0.1893 1.8697\n-0.0863 0.2287 1.7950\n-0.0939 0.2687 1.7202\n-0.0985 0.3092 1.6455\n-0.1000 0.3500 1.5708\nprimID: 5\nstartangle_c: 5\nendpose_c: 0 0 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 2.0071\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 5\nendpose_c: 0 0 4\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 1.9635\n0.0000 0.0000 1.9199\n0.0000 0.0000 1.8762\n0.0000 0.0000 1.8326\n0.0000 0.0000 1.7890\n0.0000 0.0000 1.7453\n0.0000 0.0000 1.7017\n0.0000 0.0000 1.6581\n0.0000 0.0000 1.6144\n0.0000 0.0000 1.5708\nprimID: 0\nstartangle_c: 6\nendpose_c: -1 1 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0056 0.0056 2.3562\n-0.0111 0.0111 2.3562\n-0.0167 0.0167 2.3562\n-0.0222 0.0222 2.3562\n-0.0278 0.0278 2.3562\n-0.0333 0.0333 2.3562\n-0.0389 0.0389 2.3562\n-0.0444 0.0444 2.3562\n-0.0500 0.0500 2.3562\nprimID: 1\nstartangle_c: 6\nendpose_c: -6 6 6\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0333 0.0333 2.3562\n-0.0667 0.0667 2.3562\n-0.1000 0.1000 2.3562\n-0.1333 0.1333 2.3562\n-0.1667 0.1667 2.3562\n-0.2000 0.2000 2.3562\n-0.2333 0.2333 2.3562\n-0.2667 0.2667 2.3562\n-0.3000 0.3000 2.3562\nprimID: 2\nstartangle_c: 6\nendpose_c: 1 -1 6\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0056 -0.0056 2.3562\n0.0111 -0.0111 2.3562\n0.0167 -0.0167 2.3562\n0.0222 -0.0222 2.3562\n0.0278 -0.0278 2.3562\n0.0333 -0.0333 2.3562\n0.0389 -0.0389 2.3562\n0.0444 -0.0444 2.3562\n0.0500 -0.0500 2.3562\nprimID: 3\nstartangle_c: 6\nendpose_c: -7 5 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0684 0.0678 2.3859\n-0.1043 0.1000 2.4377\n-0.1418 0.1302 2.4896\n-0.1809 0.1584 2.5415\n-0.2213 0.1846 2.5933\n-0.2631 0.2086 2.6452\n-0.3060 0.2304 2.6970\n-0.3500 0.2500 2.7489\nprimID: 4\nstartangle_c: 6\nendpose_c: -5 7 5\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.3562\n-0.0341 0.0341 2.3562\n-0.0678 0.0684 2.3265\n-0.1000 0.1043 2.2747\n-0.1302 0.1418 2.2228\n-0.1584 0.1809 2.1709\n-0.1846 0.2213 2.1191\n-0.2086 0.2631 2.0672\n-0.2304 0.3060 2.0154\n-0.2500 0.3500 1.9635\nprimID: 5\nstartangle_c: 6\nendpose_c: 0 0 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.7489\nprimID: 6\nstartangle_c: 6\nendpose_c: 0 0 5\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.3562\n0.0000 0.0000 2.3126\n0.0000 0.0000 2.2689\n0.0000 0.0000 2.2253\n0.0000 0.0000 2.1817\n0.0000 0.0000 2.1380\n0.0000 0.0000 2.0944\n0.0000 0.0000 2.0508\n0.0000 0.0000 2.0071\n0.0000 0.0000 1.9635\nprimID: 0\nstartangle_c: 7\nendpose_c: -2 1 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0111 0.0056 2.7489\n-0.0222 0.0111 2.7489\n-0.0333 0.0167 2.7489\n-0.0444 0.0222 2.7489\n-0.0556 0.0278 2.7489\n-0.0667 0.0333 2.7489\n-0.0778 0.0389 2.7489\n-0.0889 0.0444 2.7489\n-0.1000 0.0500 2.7489\nprimID: 1\nstartangle_c: 7\nendpose_c: -6 3 7\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0333 0.0167 2.7489\n-0.0667 0.0333 2.7489\n-0.1000 0.0500 2.7489\n-0.1333 0.0667 2.7489\n-0.1667 0.0833 2.7489\n-0.2000 0.1000 2.7489\n-0.2333 0.1167 2.7489\n-0.2667 0.1333 2.7489\n-0.3000 0.1500 2.7489\nprimID: 2\nstartangle_c: 7\nendpose_c: 2 -1 7\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0111 -0.0056 2.7489\n0.0222 -0.0111 2.7489\n0.0333 -0.0167 2.7489\n0.0444 -0.0222 2.7489\n0.0556 -0.0278 2.7489\n0.0667 -0.0333 2.7489\n0.0778 -0.0389 2.7489\n0.0889 -0.0444 2.7489\n0.1000 -0.0500 2.7489\nprimID: 3\nstartangle_c: 7\nendpose_c: -5 4 6\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0298 0.0184 2.7186\n-0.0592 0.0379 2.6883\n-0.0881 0.0583 2.6580\n-0.1165 0.0796 2.6277\n-0.1444 0.1019 2.5974\n-0.1717 0.1251 2.5671\n-0.1984 0.1492 2.5368\n-0.2245 0.1742 2.5065\n-0.2500 0.2000 2.4762\nprimID: 4\nstartangle_c: 7\nendpose_c: -7 2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 2.7489\n-0.0377 0.0156 2.7489\n-0.0754 0.0312 2.7489\n-0.1131 0.0468 2.7489\n-0.1508 0.0623 2.7680\n-0.1893 0.0758 2.8427\n-0.2287 0.0863 2.9174\n-0.2687 0.0939 2.9921\n-0.3092 0.0985 3.0669\n-0.3500 0.1000 3.1416\nprimID: 5\nstartangle_c: 7\nendpose_c: 0 0 6\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7053\n0.0000 0.0000 2.6616\n0.0000 0.0000 2.6180\n0.0000 0.0000 2.5744\n0.0000 0.0000 2.5307\n0.0000 0.0000 2.4871\n0.0000 0.0000 2.4435\n0.0000 0.0000 2.3998\n0.0000 0.0000 2.3562\nprimID: 6\nstartangle_c: 7\nendpose_c: 0 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 2.7489\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.9671\n0.0000 0.0000 3.0107\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 8\nendpose_c: -1 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0056 0.0000 3.1416\n-0.0111 0.0000 3.1416\n-0.0167 0.0000 3.1416\n-0.0222 0.0000 3.1416\n-0.0278 0.0000 3.1416\n-0.0333 0.0000 3.1416\n-0.0389 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0500 0.0000 3.1416\nprimID: 1\nstartangle_c: 8\nendpose_c: -8 0 8\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0444 0.0000 3.1416\n-0.0889 0.0000 3.1416\n-0.1333 0.0000 3.1416\n-0.1778 0.0000 3.1416\n-0.2222 0.0000 3.1416\n-0.2667 0.0000 3.1416\n-0.3111 0.0000 3.1416\n-0.3556 0.0000 3.1416\n-0.4000 0.0000 3.1416\nprimID: 2\nstartangle_c: 8\nendpose_c: 1 0 8\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0056 0.0000 3.1416\n0.0111 0.0000 3.1416\n0.0167 0.0000 3.1416\n0.0222 0.0000 3.1416\n0.0278 0.0000 3.1416\n0.0333 0.0000 3.1416\n0.0389 0.0000 3.1416\n0.0444 0.0000 3.1416\n0.0500 0.0000 3.1416\nprimID: 3\nstartangle_c: 8\nendpose_c: -8 -1 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 -0.0008 3.1904\n-0.2257 -0.0045 3.2592\n-0.2703 -0.0114 3.3280\n-0.3144 -0.0213 3.3967\n-0.3577 -0.0342 3.4655\n-0.4000 -0.0500 3.5343\nprimID: 4\nstartangle_c: 8\nendpose_c: -8 1 7\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.1416\n-0.0452 0.0000 3.1416\n-0.0904 0.0000 3.1416\n-0.1355 0.0000 3.1416\n-0.1807 0.0008 3.0928\n-0.2257 0.0045 3.0240\n-0.2703 0.0114 2.9552\n-0.3144 0.0213 2.8864\n-0.3577 0.0342 2.8177\n-0.4000 0.0500 2.7489\nprimID: 5\nstartangle_c: 8\nendpose_c: 0 0 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.5343\nprimID: 6\nstartangle_c: 8\nendpose_c: 0 0 7\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.1416\n0.0000 0.0000 3.0980\n0.0000 0.0000 3.0543\n0.0000 0.0000 3.0107\n0.0000 0.0000 2.9671\n0.0000 0.0000 2.9234\n0.0000 0.0000 2.8798\n0.0000 0.0000 2.8362\n0.0000 0.0000 2.7925\n0.0000 0.0000 2.7489\nprimID: 0\nstartangle_c: 9\nendpose_c: -2 -1 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0111 -0.0056 3.5343\n-0.0222 -0.0111 3.5343\n-0.0333 -0.0167 3.5343\n-0.0444 -0.0222 3.5343\n-0.0556 -0.0278 3.5343\n-0.0667 -0.0333 3.5343\n-0.0778 -0.0389 3.5343\n-0.0889 -0.0444 3.5343\n-0.1000 -0.0500 3.5343\nprimID: 1\nstartangle_c: 9\nendpose_c: -6 -3 9\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0333 -0.0167 3.5343\n-0.0667 -0.0333 3.5343\n-0.1000 -0.0500 3.5343\n-0.1333 -0.0667 3.5343\n-0.1667 -0.0833 3.5343\n-0.2000 -0.1000 3.5343\n-0.2333 -0.1167 3.5343\n-0.2667 -0.1333 3.5343\n-0.3000 -0.1500 3.5343\nprimID: 2\nstartangle_c: 9\nendpose_c: 2 1 9\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0111 0.0056 3.5343\n0.0222 0.0111 3.5343\n0.0333 0.0167 3.5343\n0.0444 0.0222 3.5343\n0.0556 0.0278 3.5343\n0.0667 0.0333 3.5343\n0.0778 0.0389 3.5343\n0.0889 0.0444 3.5343\n0.1000 0.0500 3.5343\nprimID: 3\nstartangle_c: 9\nendpose_c: -5 -4 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0298 -0.0184 3.5646\n-0.0592 -0.0379 3.5949\n-0.0881 -0.0583 3.6252\n-0.1165 -0.0796 3.6555\n-0.1444 -0.1019 3.6858\n-0.1717 -0.1251 3.7161\n-0.1984 -0.1492 3.7464\n-0.2245 -0.1742 3.7767\n-0.2500 -0.2000 3.8070\nprimID: 4\nstartangle_c: 9\nendpose_c: -7 -2 8\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.5343\n-0.0377 -0.0156 3.5343\n-0.0754 -0.0312 3.5343\n-0.1131 -0.0468 3.5343\n-0.1508 -0.0623 3.5152\n-0.1893 -0.0758 3.4405\n-0.2287 -0.0863 3.3658\n-0.2687 -0.0939 3.2910\n-0.3092 -0.0985 3.2163\n-0.3500 -0.1000 3.1416\nprimID: 5\nstartangle_c: 9\nendpose_c: 0 0 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 9\nendpose_c: 0 0 8\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.5343\n0.0000 0.0000 3.4907\n0.0000 0.0000 3.4470\n0.0000 0.0000 3.4034\n0.0000 0.0000 3.3598\n0.0000 0.0000 3.3161\n0.0000 0.0000 3.2725\n0.0000 0.0000 3.2289\n0.0000 0.0000 3.1852\n0.0000 0.0000 3.1416\nprimID: 0\nstartangle_c: 10\nendpose_c: -1 -1 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0056 -0.0056 3.9270\n-0.0111 -0.0111 3.9270\n-0.0167 -0.0167 3.9270\n-0.0222 -0.0222 3.9270\n-0.0278 -0.0278 3.9270\n-0.0333 -0.0333 3.9270\n-0.0389 -0.0389 3.9270\n-0.0444 -0.0444 3.9270\n-0.0500 -0.0500 3.9270\nprimID: 1\nstartangle_c: 10\nendpose_c: -6 -6 10\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0333 -0.0333 3.9270\n-0.0667 -0.0667 3.9270\n-0.1000 -0.1000 3.9270\n-0.1333 -0.1333 3.9270\n-0.1667 -0.1667 3.9270\n-0.2000 -0.2000 3.9270\n-0.2333 -0.2333 3.9270\n-0.2667 -0.2667 3.9270\n-0.3000 -0.3000 3.9270\nprimID: 2\nstartangle_c: 10\nendpose_c: 1 1 10\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0056 0.0056 3.9270\n0.0111 0.0111 3.9270\n0.0167 0.0167 3.9270\n0.0222 0.0222 3.9270\n0.0278 0.0278 3.9270\n0.0333 0.0333 3.9270\n0.0389 0.0389 3.9270\n0.0444 0.0444 3.9270\n0.0500 0.0500 3.9270\nprimID: 3\nstartangle_c: 10\nendpose_c: -5 -7 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0678 -0.0684 3.9567\n-0.1000 -0.1043 4.0085\n-0.1302 -0.1418 4.0604\n-0.1584 -0.1809 4.1123\n-0.1846 -0.2213 4.1641\n-0.2086 -0.2631 4.2160\n-0.2304 -0.3060 4.2678\n-0.2500 -0.3500 4.3197\nprimID: 4\nstartangle_c: 10\nendpose_c: -7 -5 9\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 3.9270\n-0.0341 -0.0341 3.9270\n-0.0684 -0.0678 3.8973\n-0.1043 -0.1000 3.8455\n-0.1418 -0.1302 3.7936\n-0.1809 -0.1584 3.7417\n-0.2213 -0.1846 3.6899\n-0.2631 -0.2086 3.6380\n-0.3060 -0.2304 3.5862\n-0.3500 -0.2500 3.5343\nprimID: 5\nstartangle_c: 10\nendpose_c: 0 0 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.9706\n0.0000 0.0000 4.0143\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.3197\nprimID: 6\nstartangle_c: 10\nendpose_c: 0 0 9\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 3.9270\n0.0000 0.0000 3.8834\n0.0000 0.0000 3.8397\n0.0000 0.0000 3.7961\n0.0000 0.0000 3.7525\n0.0000 0.0000 3.7088\n0.0000 0.0000 3.6652\n0.0000 0.0000 3.6216\n0.0000 0.0000 3.5779\n0.0000 0.0000 3.5343\nprimID: 0\nstartangle_c: 11\nendpose_c: -1 -2 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0056 -0.0111 4.3197\n-0.0111 -0.0222 4.3197\n-0.0167 -0.0333 4.3197\n-0.0222 -0.0444 4.3197\n-0.0278 -0.0556 4.3197\n-0.0333 -0.0667 4.3197\n-0.0389 -0.0778 4.3197\n-0.0444 -0.0889 4.3197\n-0.0500 -0.1000 4.3197\nprimID: 1\nstartangle_c: 11\nendpose_c: -3 -6 11\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0167 -0.0333 4.3197\n-0.0333 -0.0667 4.3197\n-0.0500 -0.1000 4.3197\n-0.0667 -0.1333 4.3197\n-0.0833 -0.1667 4.3197\n-0.1000 -0.2000 4.3197\n-0.1167 -0.2333 4.3197\n-0.1333 -0.2667 4.3197\n-0.1500 -0.3000 4.3197\nprimID: 2\nstartangle_c: 11\nendpose_c: 1 2 11\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0056 0.0111 4.3197\n0.0111 0.0222 4.3197\n0.0167 0.0333 4.3197\n0.0222 0.0444 4.3197\n0.0278 0.0556 4.3197\n0.0333 0.0667 4.3197\n0.0389 0.0778 4.3197\n0.0444 0.0889 4.3197\n0.0500 0.1000 4.3197\nprimID: 3\nstartangle_c: 11\nendpose_c: -4 -5 10\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0184 -0.0298 4.2894\n-0.0379 -0.0592 4.2591\n-0.0583 -0.0881 4.2288\n-0.0796 -0.1165 4.1985\n-0.1019 -0.1444 4.1682\n-0.1251 -0.1717 4.1379\n-0.1492 -0.1984 4.1076\n-0.1742 -0.2245 4.0773\n-0.2000 -0.2500 4.0470\nprimID: 4\nstartangle_c: 11\nendpose_c: -2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.3197\n-0.0156 -0.0377 4.3197\n-0.0312 -0.0754 4.3197\n-0.0468 -0.1131 4.3197\n-0.0623 -0.1508 4.3388\n-0.0758 -0.1893 4.4135\n-0.0863 -0.2287 4.4882\n-0.0939 -0.2687 4.5629\n-0.0985 -0.3092 4.6377\n-0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 11\nendpose_c: 0 0 10\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.2761\n0.0000 0.0000 4.2324\n0.0000 0.0000 4.1888\n0.0000 0.0000 4.1452\n0.0000 0.0000 4.1015\n0.0000 0.0000 4.0579\n0.0000 0.0000 4.0143\n0.0000 0.0000 3.9706\n0.0000 0.0000 3.9270\nprimID: 6\nstartangle_c: 11\nendpose_c: 0 0 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.3197\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 12\nendpose_c: 0 -1 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0056 4.7124\n0.0000 -0.0111 4.7124\n0.0000 -0.0167 4.7124\n0.0000 -0.0222 4.7124\n0.0000 -0.0278 4.7124\n0.0000 -0.0333 4.7124\n0.0000 -0.0389 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0500 4.7124\nprimID: 1\nstartangle_c: 12\nendpose_c: 0 -8 12\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0444 4.7124\n0.0000 -0.0889 4.7124\n0.0000 -0.1333 4.7124\n0.0000 -0.1778 4.7124\n0.0000 -0.2222 4.7124\n0.0000 -0.2667 4.7124\n0.0000 -0.3111 4.7124\n0.0000 -0.3556 4.7124\n0.0000 -0.4000 4.7124\nprimID: 2\nstartangle_c: 12\nendpose_c: 0 1 12\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0056 4.7124\n0.0000 0.0111 4.7124\n0.0000 0.0167 4.7124\n0.0000 0.0222 4.7124\n0.0000 0.0278 4.7124\n0.0000 0.0333 4.7124\n0.0000 0.0389 4.7124\n0.0000 0.0444 4.7124\n0.0000 0.0500 4.7124\nprimID: 3\nstartangle_c: 12\nendpose_c: 1 -8 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 -0.0452 4.7124\n0.0000 -0.0904 4.7124\n0.0000 -0.1355 4.7124\n0.0008 -0.1807 4.7612\n0.0045 -0.2257 4.8300\n0.0114 -0.2703 4.8988\n0.0213 -0.3144 4.9675\n0.0342 -0.3577 5.0363\n0.0500 -0.4000 5.1051\nprimID: 4\nstartangle_c: 12\nendpose_c: -1 -8 11\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 4.7124\n-0.0000 -0.0452 4.7124\n-0.0000 -0.0904 4.7124\n-0.0000 -0.1355 4.7124\n-0.0008 -0.1807 4.6636\n-0.0045 -0.2257 4.5948\n-0.0114 -0.2703 4.5260\n-0.0213 -0.3144 4.4572\n-0.0342 -0.3577 4.3885\n-0.0500 -0.4000 4.3197\nprimID: 5\nstartangle_c: 12\nendpose_c: 0 0 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.9742\n0.0000 0.0000 5.0178\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.1051\nprimID: 6\nstartangle_c: 12\nendpose_c: 0 0 11\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 4.7124\n0.0000 0.0000 4.6688\n0.0000 0.0000 4.6251\n0.0000 0.0000 4.5815\n0.0000 0.0000 4.5379\n0.0000 0.0000 4.4942\n0.0000 0.0000 4.4506\n0.0000 0.0000 4.4070\n0.0000 0.0000 4.3633\n0.0000 0.0000 4.3197\nprimID: 0\nstartangle_c: 13\nendpose_c: 1 -2 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0056 -0.0111 5.1051\n0.0111 -0.0222 5.1051\n0.0167 -0.0333 5.1051\n0.0222 -0.0444 5.1051\n0.0278 -0.0556 5.1051\n0.0333 -0.0667 5.1051\n0.0389 -0.0778 5.1051\n0.0444 -0.0889 5.1051\n0.0500 -0.1000 5.1051\nprimID: 1\nstartangle_c: 13\nendpose_c: 3 -6 13\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0167 -0.0333 5.1051\n0.0333 -0.0667 5.1051\n0.0500 -0.1000 5.1051\n0.0667 -0.1333 5.1051\n0.0833 -0.1667 5.1051\n0.1000 -0.2000 5.1051\n0.1167 -0.2333 5.1051\n0.1333 -0.2667 5.1051\n0.1500 -0.3000 5.1051\nprimID: 2\nstartangle_c: 13\nendpose_c: -1 2 13\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 5.1051\n-0.0056 0.0111 5.1051\n-0.0111 0.0222 5.1051\n-0.0167 0.0333 5.1051\n-0.0222 0.0444 5.1051\n-0.0278 0.0556 5.1051\n-0.0333 0.0667 5.1051\n-0.0389 0.0778 5.1051\n-0.0444 0.0889 5.1051\n-0.0500 0.1000 5.1051\nprimID: 3\nstartangle_c: 13\nendpose_c: 4 -5 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0184 -0.0298 5.1354\n0.0379 -0.0592 5.1657\n0.0583 -0.0881 5.1960\n0.0796 -0.1165 5.2263\n0.1019 -0.1444 5.2566\n0.1251 -0.1717 5.2869\n0.1492 -0.1984 5.3172\n0.1742 -0.2245 5.3475\n0.2000 -0.2500 5.3778\nprimID: 4\nstartangle_c: 13\nendpose_c: 2 -7 12\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0156 -0.0377 5.1051\n0.0312 -0.0754 5.1051\n0.0468 -0.1131 5.1051\n0.0623 -0.1508 5.0860\n0.0758 -0.1893 5.0113\n0.0863 -0.2287 4.9366\n0.0939 -0.2687 4.8618\n0.0985 -0.3092 4.7871\n0.1000 -0.3500 4.7124\nprimID: 5\nstartangle_c: 13\nendpose_c: 0 0 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 13\nendpose_c: 0 0 12\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.1051\n0.0000 0.0000 5.0615\n0.0000 0.0000 5.0178\n0.0000 0.0000 4.9742\n0.0000 0.0000 4.9306\n0.0000 0.0000 4.8869\n0.0000 0.0000 4.8433\n0.0000 0.0000 4.7997\n0.0000 0.0000 4.7560\n0.0000 0.0000 4.7124\nprimID: 0\nstartangle_c: 14\nendpose_c: 1 -1 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0056 -0.0056 5.4978\n0.0111 -0.0111 5.4978\n0.0167 -0.0167 5.4978\n0.0222 -0.0222 5.4978\n0.0278 -0.0278 5.4978\n0.0333 -0.0333 5.4978\n0.0389 -0.0389 5.4978\n0.0444 -0.0444 5.4978\n0.0500 -0.0500 5.4978\nprimID: 1\nstartangle_c: 14\nendpose_c: 6 -6 14\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0333 -0.0333 5.4978\n0.0667 -0.0667 5.4978\n0.1000 -0.1000 5.4978\n0.1333 -0.1333 5.4978\n0.1667 -0.1667 5.4978\n0.2000 -0.2000 5.4978\n0.2333 -0.2333 5.4978\n0.2667 -0.2667 5.4978\n0.3000 -0.3000 5.4978\nprimID: 2\nstartangle_c: 14\nendpose_c: -1 1 14\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 5.4978\n-0.0056 0.0056 5.4978\n-0.0111 0.0111 5.4978\n-0.0167 0.0167 5.4978\n-0.0222 0.0222 5.4978\n-0.0278 0.0278 5.4978\n-0.0333 0.0333 5.4978\n-0.0389 0.0389 5.4978\n-0.0444 0.0444 5.4978\n-0.0500 0.0500 5.4978\nprimID: 3\nstartangle_c: 14\nendpose_c: 7 -5 15\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0684 -0.0678 5.5275\n0.1043 -0.1000 5.5793\n0.1418 -0.1302 5.6312\n0.1809 -0.1584 5.6830\n0.2213 -0.1846 5.7349\n0.2631 -0.2086 5.7868\n0.3060 -0.2304 5.8386\n0.3500 -0.2500 5.8905\nprimID: 4\nstartangle_c: 14\nendpose_c: 5 -7 13\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0341 -0.0341 5.4978\n0.0678 -0.0684 5.4681\n0.1000 -0.1043 5.4162\n0.1302 -0.1418 5.3644\n0.1584 -0.1809 5.3125\n0.1846 -0.2213 5.2607\n0.2086 -0.2631 5.2088\n0.2304 -0.3060 5.1569\n0.2500 -0.3500 5.1051\nprimID: 5\nstartangle_c: 14\nendpose_c: 0 0 15\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8905\nprimID: 6\nstartangle_c: 14\nendpose_c: 0 0 13\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.4978\n0.0000 0.0000 5.4542\n0.0000 0.0000 5.4105\n0.0000 0.0000 5.3669\n0.0000 0.0000 5.3233\n0.0000 0.0000 5.2796\n0.0000 0.0000 5.2360\n0.0000 0.0000 5.1924\n0.0000 0.0000 5.1487\n0.0000 0.0000 5.1051\nprimID: 0\nstartangle_c: 15\nendpose_c: 2 -1 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0111 -0.0056 5.8905\n0.0222 -0.0111 5.8905\n0.0333 -0.0167 5.8905\n0.0444 -0.0222 5.8905\n0.0556 -0.0278 5.8905\n0.0667 -0.0333 5.8905\n0.0778 -0.0389 5.8905\n0.0889 -0.0444 5.8905\n0.1000 -0.0500 5.8905\nprimID: 1\nstartangle_c: 15\nendpose_c: 6 -3 15\nadditionalactioncostmult: 1\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0333 -0.0167 5.8905\n0.0667 -0.0333 5.8905\n0.1000 -0.0500 5.8905\n0.1333 -0.0667 5.8905\n0.1667 -0.0833 5.8905\n0.2000 -0.1000 5.8905\n0.2333 -0.1167 5.8905\n0.2667 -0.1333 5.8905\n0.3000 -0.1500 5.8905\nprimID: 2\nstartangle_c: 15\nendpose_c: -2 1 15\nadditionalactioncostmult: 40\nintermediateposes: 10\n0.0000 0.0000 5.8905\n-0.0111 0.0056 5.8905\n-0.0222 0.0111 5.8905\n-0.0333 0.0167 5.8905\n-0.0444 0.0222 5.8905\n-0.0556 0.0278 5.8905\n-0.0667 0.0333 5.8905\n-0.0778 0.0389 5.8905\n-0.0889 0.0444 5.8905\n-0.1000 0.0500 5.8905\nprimID: 3\nstartangle_c: 15\nendpose_c: 5 -4 14\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0298 -0.0184 5.8602\n0.0592 -0.0379 5.8299\n0.0881 -0.0583 5.7996\n0.1165 -0.0796 5.7693\n0.1444 -0.1019 5.7390\n0.1717 -0.1251 5.7087\n0.1984 -0.1492 5.6784\n0.2245 -0.1742 5.6481\n0.2500 -0.2000 5.6178\nprimID: 4\nstartangle_c: 15\nendpose_c: 7 -2 0\nadditionalactioncostmult: 2\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0377 -0.0156 5.8905\n0.0754 -0.0312 5.8905\n0.1131 -0.0468 5.8905\n0.1508 -0.0623 5.9096\n0.1893 -0.0758 5.9843\n0.2287 -0.0863 6.0590\n0.2687 -0.0939 6.1337\n0.3092 -0.0985 6.2085\n0.3500 -0.1000 6.2832\nprimID: 5\nstartangle_c: 15\nendpose_c: 0 0 14\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.8469\n0.0000 0.0000 5.8032\n0.0000 0.0000 5.7596\n0.0000 0.0000 5.7160\n0.0000 0.0000 5.6723\n0.0000 0.0000 5.6287\n0.0000 0.0000 5.5851\n0.0000 0.0000 5.5414\n0.0000 0.0000 5.4978\nprimID: 6\nstartangle_c: 15\nendpose_c: 0 0 0\nadditionalactioncostmult: 20\nintermediateposes: 10\n0.0000 0.0000 5.8905\n0.0000 0.0000 5.9341\n0.0000 0.0000 5.9778\n0.0000 0.0000 6.0214\n0.0000 0.0000 6.0650\n0.0000 0.0000 6.1087\n0.0000 0.0000 6.1523\n0.0000 0.0000 6.1959\n0.0000 0.0000 6.2396\n0.0000 0.0000 0.0000\n"
  },
  {
    "path": "mir_navigation/nodes/acc_finder.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\n\nfrom geometry_msgs.msg import Twist\nfrom nav_msgs.msg import Odometry\n\nLIN_MAX = 1.0\nANG_MAX = 1.5  # adjust this value to the rough maximum angular velocity\n\nstate = 'stopped'\nstart = rospy.Time(0)\n\n\ndef odom_cb(msg):\n    global state\n\n    twist = msg.twist.twist\n    t = (rospy.Time.now() - start).to_sec()\n\n    if state == 'wait_for_stop':\n        if -0.05 < twist.linear.x < 0.05 and -0.1 < twist.angular.z < 0.1:\n            state = 'stopped'\n            rospy.loginfo('state transition --> %s', state)\n        return\n\n    if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX:\n        rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t)\n    elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX:\n        rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t)\n    elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX:\n        rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)\n    elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX:\n        rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t)\n    else:\n        return\n\n    state = 'wait_for_stop'\n    rospy.loginfo('state transition --> %s', state)\n\n\ndef cmd_vel_cb(msg):\n    global state, start\n\n    if state != 'stopped':\n        return\n\n    if msg.linear.x <= -LIN_MAX:\n        start = rospy.Time.now()\n        state = 'backward'\n    elif msg.linear.x >= LIN_MAX:\n        start = rospy.Time.now()\n        state = 'forward'\n    elif msg.angular.z <= -ANG_MAX:\n        start = rospy.Time.now()\n        state = 'turning_clockwise'\n    elif msg.angular.z >= ANG_MAX:\n        start = rospy.Time.now()\n        state = 'turning_counter_clockwise'\n    else:\n        return\n\n    rospy.loginfo('state transition --> %s', state)\n\n\ndef main():\n    rospy.init_node('acc_finder', anonymous=True)\n    rospy.Subscriber('odom', Odometry, odom_cb)\n    rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb)\n    rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!')\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "mir_navigation/nodes/min_max_finder.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport rospy\n\nfrom nav_msgs.msg import Odometry\n\nlin_min = 0.0\nlin_max = 0.0\nang_min = 0.0\nang_max = 0.0\n\n\ndef odom_cb(msg):\n    global lin_min, lin_max, ang_min, ang_max\n    if lin_min > msg.twist.twist.linear.x:\n        lin_min = msg.twist.twist.linear.x\n    if lin_max < msg.twist.twist.linear.x:\n        lin_max = msg.twist.twist.linear.x\n    if ang_min > msg.twist.twist.angular.z:\n        ang_min = msg.twist.twist.angular.z\n    if ang_max < msg.twist.twist.angular.z:\n        ang_max = msg.twist.twist.angular.z\n\n    rospy.loginfo('linear: [%f, %f]   angular: [%f, %f]', lin_min, lin_max, ang_min, ang_max)\n\n\ndef main():\n    rospy.init_node('min_max_finder', anonymous=True)\n    rospy.Subscriber('odom', Odometry, odom_cb)\n    rospy.loginfo('min_max_finde node ready and listening. now use teleop to move your robot to the limits!')\n    rospy.spin()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "mir_navigation/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_navigation</name>\n  <version>1.1.8</version>\n  <description>Launch and configuration files for move_base, localization etc. on the MiR robot.</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roslaunch</build_depend>\n\n  <exec_depend>amcl</exec_depend>\n  <exec_depend>base_local_planner</exec_depend>\n  <exec_depend>dwa_local_planner</exec_depend>\n  <exec_depend>dwb_critics</exec_depend>         <!-- for dwb_local_planner -->\n  <exec_depend>dwb_local_planner</exec_depend>   <!-- for dwb_local_planner -->\n  <exec_depend>dwb_plugins</exec_depend>         <!-- for dwb_local_planner -->\n  <!-- <exec_depend>eband_local_planner</exec_depend> -->\n  <exec_depend>hector_mapping</exec_depend>\n  <exec_depend>map_server</exec_depend>\n  <exec_depend>mir_driver</exec_depend>\n  <exec_depend>mir_dwb_critics</exec_depend>     <!-- for dwb_local_planner -->\n  <exec_depend>mir_gazebo</exec_depend>\n  <exec_depend>move_base</exec_depend>\n  <exec_depend>nav_core_adapter</exec_depend>    <!-- for dwb_local_planner -->\n  <exec_depend>python3-matplotlib</exec_depend>\n  <exec_depend>sbpl_lattice_planner</exec_depend>\n  <exec_depend>teb_local_planner</exec_depend>\n</package>\n"
  },
  {
    "path": "mir_navigation/rviz/navigation.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 81\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Grid1\n        - /Grid1/Offset1\n        - /TF1/Frames1\n        - /TF1/Tree1\n        - /Local Map1/DWB Markers1/Namespaces1\n      Splitter Ratio: 0.5\n    Tree Height: 575\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 25\n        Y: 25\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 50\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Class: rviz/RobotModel\n      Collision Enabled: false\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        back_laser_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_footprint:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        bl_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        bl_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        br_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        br_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fl_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fl_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fr_caster_rotation_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        fr_caster_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_frame:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        surface:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        us_1_frame:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        us_2_frame:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz/TF\n      Enabled: false\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: false\n      Tree:\n        {}\n      Update Interval: 0\n      Value: false\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: FlatColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0500000007\n      Style: Squares\n      Topic: scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/PointCloud2\n      Color: 255; 0; 0\n      Color Transformer: FlatColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: Bumper Hit\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0799999982\n      Style: Spheres\n      Topic: mobile_base/sensors/bumper_pointcloud\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Class: rviz/Group\n      Displays:\n        - Alpha: 0.699999988\n          Class: rviz/Map\n          Color Scheme: costmap\n          Draw Behind: true\n          Enabled: true\n          Name: Costmap\n          Topic: move_base_node/global_costmap/costmap\n          Unreliable: false\n          Use Timestamp: false\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz/Path\n          Color: 255; 0; 0\n          Enabled: true\n          Head Diameter: 0.300000012\n          Head Length: 0.200000003\n          Length: 0.300000012\n          Line Style: Billboards\n          Line Width: 0.0500000007\n          Name: Global Plan (DWB)\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: None\n          Radius: 0.0299999993\n          Shaft Diameter: 0.100000001\n          Shaft Length: 0.100000001\n          Topic: move_base_node/DWBLocalPlanner/transformed_global_plan\n          Unreliable: false\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz/Path\n          Color: 25; 255; 0\n          Enabled: true\n          Head Diameter: 0.300000012\n          Head Length: 0.200000003\n          Length: 0.300000012\n          Line Style: Billboards\n          Line Width: 0.0500000007\n          Name: Full Plan\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: None\n          Radius: 0.0299999993\n          Shaft Diameter: 0.100000001\n          Shaft Length: 0.100000001\n          Topic: move_base_node/SBPLLatticePlanner/plan\n          Unreliable: false\n          Value: true\n        - Alpha: 1\n          Class: rviz/Polygon\n          Color: 255; 0; 0\n          Enabled: true\n          Name: Footprint\n          Topic: move_base_node/global_costmap/footprint\n          Unreliable: false\n          Value: true\n      Enabled: true\n      Name: Global Map\n    - Class: rviz/Group\n      Displays:\n        - Alpha: 0.699999988\n          Class: rviz/Map\n          Color Scheme: costmap\n          Draw Behind: false\n          Enabled: true\n          Name: Costmap\n          Topic: move_base_node/local_costmap/costmap\n          Unreliable: false\n          Use Timestamp: false\n          Value: true\n        - Alpha: 1\n          Class: rviz/GridCells\n          Color: 25; 255; 0\n          Enabled: true\n          Name: Costmap (MiR)\n          Topic: move_base_node/local_costmap/obstacles\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz/Path\n          Color: 0; 12; 255\n          Enabled: true\n          Head Diameter: 0.300000012\n          Head Length: 0.200000003\n          Length: 0.300000012\n          Line Style: Billboards\n          Line Width: 0.0500000007\n          Name: Local Plan (DWB)\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: None\n          Radius: 0.0299999993\n          Shaft Diameter: 0.100000001\n          Shaft Length: 0.100000001\n          Topic: move_base_node/DWBLocalPlanner/local_plan\n          Unreliable: false\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz/Path\n          Color: 0; 12; 255\n          Enabled: true\n          Head Diameter: 0.300000012\n          Head Length: 0.200000003\n          Length: 0.300000012\n          Line Style: Billboards\n          Line Width: 0.0500000007\n          Name: Local Plan (MiR)\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: None\n          Radius: 0.0299999993\n          Shaft Diameter: 0.100000001\n          Shaft Length: 0.100000001\n          Topic: move_base_node/MIRPlannerROS/local_plan\n          Unreliable: false\n          Value: true\n        - Alpha: 1\n          Class: rviz/Polygon\n          Color: 25; 255; 0\n          Enabled: true\n          Name: Footprint\n          Topic: move_base_node/local_costmap/footprint\n          Unreliable: false\n          Value: true\n        - Alpha: 0.300000012\n          Autocompute Intensity Bounds: false\n          Autocompute Value Bounds:\n            Max Value: 10\n            Min Value: -10\n            Value: true\n          Axis: Z\n          Channel Name: total_cost\n          Class: rviz/PointCloud2\n          Color: 255; 255; 255\n          Color Transformer: Intensity\n          Decay Time: 0\n          Enabled: true\n          Invert Rainbow: false\n          Max Color: 255; 255; 255\n          Max Intensity: 40\n          Min Color: 0; 0; 0\n          Min Intensity: 0\n          Name: Cost Cloud\n          Position Transformer: XYZ\n          Queue Size: 10\n          Selectable: true\n          Size (Pixels): 3\n          Size (m): 0.0399999991\n          Style: Flat Squares\n          Topic: move_base_node/DWBLocalPlanner/cost_cloud\n          Unreliable: false\n          Use Fixed Frame: true\n          Use rainbow: true\n          Value: true\n        - Class: rviz/MarkerArray\n          Enabled: true\n          Marker Topic: move_base_node/DWBLocalPlanner/markers\n          Name: DWB Markers\n          Namespaces:\n            InvalidTrajectories: true\n            ValidTrajectories: true\n          Queue Size: 100\n          Value: true\n      Enabled: true\n      Name: Local Map\n    - Alpha: 1\n      Arrow Length: 0.200000003\n      Axes Length: 0.300000012\n      Axes Radius: 0.00999999978\n      Class: rviz/PoseArray\n      Color: 0; 192; 0\n      Enabled: true\n      Head Length: 0.0700000003\n      Head Radius: 0.0299999993\n      Name: Amcl Particle Swarm\n      Shaft Length: 0.230000004\n      Shaft Radius: 0.00999999978\n      Shape: Arrow (Flat)\n      Topic: particlecloud\n      Unreliable: false\n      Value: false\n    - Class: rviz/Group\n      Displays:\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz/Path\n          Color: 114; 159; 207\n          Enabled: true\n          Head Diameter: 0.30000001192092896\n          Head Length: 0.20000000298023224\n          Length: 0.30000001192092896\n          Line Style: Billboards\n          Line Width: 0.05000000074505806\n          Name: Lookahead Collision Arc (RPP)\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: None\n          Queue Size: 10\n          Radius: 0.029999999329447746\n          Shaft Diameter: 0.10000000149011612\n          Shaft Length: 0.10000000149011612\n          Topic: /move_base_node/RegulatedPurePursuitController/lookahead_collision_arc\n          Unreliable: false\n          Value: true\n        - Alpha: 1\n          Class: rviz/PointStamped\n          Color: 204; 41; 204\n          Enabled: true\n          History Length: 1\n          Name: Lookahead Point (RPP)\n          Queue Size: 10\n          Radius: 0.05000000074505806\n          Topic: /move_base_node/RegulatedPurePursuitController/lookahead_point\n          Unreliable: false\n          Value: true\n      Enabled: true\n      Name: RPP\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/MoveCamera\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/Select\n    - Class: rviz/SetInitialPose\n      Topic: initialpose\n    - Class: rviz/SetGoal\n      Topic: move_base_simple/goal\n    - Class: rviz/Measure\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: 0\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Scale: 68.8703232\n      Target Frame: <Fixed Frame>\n      Value: TopDownOrtho (rviz)\n      X: 13.2673092\n      Y: 16.1651554\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 818\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a000002d1fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006700fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000043000002d1000000e300ffffff000000010000010f000002d1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000043000002d1000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000022300fffffffb0000000800540069006d006501000000000000045000000000000000000000034b000002d100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1488\n  X: 254\n  Y: 36\n"
  },
  {
    "path": "mir_navigation/scripts/plot_mprim.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\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# Author: Martin Günther\n\nimport matplotlib.pyplot as plt\nimport numpy as np\nimport sys\n\n\ndef get_value(strline, name):\n    if strline.find(name) < 0:\n        raise Exception(\"File format not matching the parser expectation\", name)\n\n    return strline.replace(name, \"\", 1)\n\n\ndef get_pose(line):\n    ss = line.split()\n    return np.array([float(ss[0]), float(ss[1]), float(ss[2])])\n\n\nclass MPrim:\n    def __init__(self, f):\n        self.primID = int(get_value(f.readline(), \"primID:\"))\n        self.startAngle = int(get_value(f.readline(), \"startangle_c:\"))\n        self.endPose = get_pose(get_value(f.readline(), \"endpose_c:\"))\n        self.cost = float(get_value(f.readline(), \"additionalactioncostmult:\"))\n        self.nrPoses = int(get_value(f.readline(), \"intermediateposes:\"))\n        poses = []\n        for _ in range(self.nrPoses):\n            poses.append(f.readline())\n        self.poses = np.loadtxt(poses, delimiter=\" \")\n        self.cmap = plt.get_cmap(\"nipy_spectral\")\n\n    def plot(self, nr_angles):\n        plt.plot(self.poses[:, 0], self.poses[:, 1], c=self.cmap(float(self.startAngle) / nr_angles))\n\n\nclass MPrims:\n    def __init__(self, filename):\n        f = open(filename, \"r\")\n\n        self.resolution = float(get_value(f.readline(), \"resolution_m:\"))\n        self.nrAngles = int(get_value(f.readline(), \"numberofangles:\"))\n        self.nrPrims = int(get_value(f.readline(), \"totalnumberofprimitives:\"))\n\n        self.prims = []\n        for _ in range(self.nrPrims):\n            self.prims.append(MPrim(f))\n\n        f.close()\n\n    def plot(self):\n        fig = plt.figure()\n        ax = fig.add_subplot(111)\n        ax.set_xticks(np.arange(-1, 1, self.resolution))\n        ax.set_yticks(np.arange(-1, 1, self.resolution))\n        for prim in self.prims:\n            prim.plot(self.nrAngles)\n        plt.grid()\n        plt.show()\n\n\nprims = MPrims(sys.argv[1])\nprims.plot()\n"
  },
  {
    "path": "mir_robot/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_robot\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n\n1.1.6 (2022-06-02)\n------------------\n* Rename mir_100 -> mir\n  This is in preparation of mir_250 support.\n* Contributors: Martin Günther\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Set cmake_policy CMP0048 to fix warning\n* Add sdc21x0 dependency to mir_robot meta package\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n\n1.0.4 (2019-05-06)\n------------------\n\n1.0.3 (2019-03-04)\n------------------\n* Add package: mir_dwb_critics\n* Contributors: Martin Günther\n\n1.0.2 (2018-07-30)\n------------------\n* Add metapackage\n* Contributors: Martin Günther\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n"
  },
  {
    "path": "mir_robot/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_robot)\nfind_package(catkin REQUIRED)\ncatkin_metapackage()\n"
  },
  {
    "path": "mir_robot/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_robot</name>\n  <version>1.1.8</version>\n  <description>\n    URDF description, Gazebo simulation, navigation, bringup launch files, message and action descriptions for the MiR robot.\n  </description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <exec_depend>mir_actions</exec_depend>\n  <exec_depend>mir_description</exec_depend>\n  <exec_depend>mir_driver</exec_depend>\n  <exec_depend>mir_dwb_critics</exec_depend>\n  <exec_depend>mir_gazebo</exec_depend>\n  <exec_depend>mir_msgs</exec_depend>\n  <exec_depend>mir_navigation</exec_depend>\n  <exec_depend>sdc21x0</exec_depend>\n\n  <export>\n    <metapackage/>\n  </export>\n</package>\n"
  },
  {
    "path": "pyproject.toml",
    "content": "[tool.black]\nline-length = 120\ntarget-version = ['py38']\nskip-string-normalization = true\n"
  },
  {
    "path": "sdc21x0/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sdc21x0\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n------------------\n* package.xml: Use SPDX license declaration\n* Move repo to DFKI-NI\n* Contributors: Martin Günther\n\n1.1.7 (2023-01-20)\n------------------\n* Don't set cmake_policy CMP0048\n* Contributors: Martin Günther\n\n1.1.6 (2022-06-02)\n------------------\n\n1.1.5 (2022-02-11)\n------------------\n\n1.1.4 (2021-12-10)\n------------------\n\n1.1.3 (2021-06-11)\n------------------\n\n1.1.2 (2021-05-12)\n------------------\n\n1.1.1 (2021-02-11)\n------------------\n* Contributors: Martin Günther\n\n1.1.0 (2020-06-30)\n------------------\n* Initial release into noetic\n* Contributors: Martin Günther\n\n1.0.6 (2020-06-30)\n------------------\n* Set cmake_policy CMP0048 to fix warning\n* Contributors: Martin Günther\n\n1.0.5 (2020-05-01)\n------------------\n* Add sdc21x0 package, MC/currents topic\n* Contributors: Martin Günther\n\n* Add sdc21x0 package, MC/currents topic\n* Contributors: Martin Günther\n\n1.0.4 (2019-05-06)\n------------------\n\n1.0.3 (2019-03-04)\n------------------\n\n1.0.2 (2018-07-30)\n------------------\n\n1.0.1 (2018-07-17)\n------------------\n\n1.0.0 (2018-07-12)\n------------------\n"
  },
  {
    "path": "sdc21x0/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.5.1)\nproject(sdc21x0)\n\nfind_package(catkin REQUIRED COMPONENTS\n  message_generation\n  std_msgs\n)\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n# Generate messages in the 'msg' folder\nadd_message_files(\n  FILES\n  Encoders.msg\n  MotorCurrents.msg\n  StampedEncoders.msg\n)\n\n# Generate services in the 'srv' folder\nadd_service_files(\n  FILES\n  Flags.srv\n)\n\n# Generate added messages and services with any dependencies listed here\ngenerate_messages(\n  DEPENDENCIES\n    std_msgs\n)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package(\n  CATKIN_DEPENDS\n    message_runtime\n    std_msgs\n)\n"
  },
  {
    "path": "sdc21x0/msg/Encoders.msg",
    "content": "float32 time_delta # Time since last encoder update.\nint32 left_wheel  # Encoder counts (absolute or relative)\nint32 right_wheel # Encoder counts (absolute or relative)\n"
  },
  {
    "path": "sdc21x0/msg/MotorCurrents.msg",
    "content": "float32 left_motor\nfloat32 right_motor\n"
  },
  {
    "path": "sdc21x0/msg/StampedEncoders.msg",
    "content": "Header header\nEncoders encoders\n"
  },
  {
    "path": "sdc21x0/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sdc21x0</name>\n  <version>1.1.8</version>\n  <description>Message definitions for the sdc21x0 motor controller</description>\n\n  <maintainer email=\"martin.guenther@dfki.de\">Martin Günther</maintainer>\n  <author email=\"martin.guenther@dfki.de\">Martin Günther</author>\n\n  <license>BSD-3-Clause</license>\n\n  <url type=\"website\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"repository\">https://github.com/DFKI-NI/mir_robot</url>\n  <url type=\"bugtracker\">https://github.com/DFKI-NI/mir_robot/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>std_msgs</depend>\n\n  <build_depend>message_generation</build_depend>\n  <exec_depend>message_runtime</exec_depend>\n</package>\n"
  },
  {
    "path": "sdc21x0/srv/Flags.srv",
    "content": "int32 digitalPort\n---\nbool response\n"
  }
]