Repository: dfki-ric/mir_robot Branch: noetic Commit: c08dfad93be5 Files: 187 Total size: 677.4 KB Directory structure: gitextract_w5fzwrag/ ├── .clang-format ├── .dockerfilelintrc ├── .flake8 ├── .github/ │ └── workflows/ │ └── github-actions.yml ├── .gitignore ├── .markdownlint.yaml ├── .pre-commit-config.yaml ├── Dockerfile-noetic ├── LICENSE ├── README.md ├── mir_actions/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── action/ │ │ └── MirMoveBase.action │ └── package.xml ├── mir_description/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config/ │ │ ├── diffdrive_controller.yaml │ │ └── joint_state_controller.yaml │ ├── launch/ │ │ ├── mir_debug_urdf.launch │ │ └── upload_mir_urdf.launch │ ├── meshes/ │ │ ├── collision/ │ │ │ ├── caster_wheel_base.stl │ │ │ ├── mir_100_base.stl │ │ │ └── mir_250_base.stl │ │ └── visual/ │ │ ├── caster_wheel_base.stl │ │ ├── mir_100_base.stl │ │ ├── mir_250_base.stl │ │ ├── sick_lms-100.stl │ │ └── wheel.stl │ ├── package.xml │ ├── rviz/ │ │ └── mir_description.rviz │ └── urdf/ │ ├── include/ │ │ ├── common.gazebo.xacro │ │ ├── common_properties.urdf.xacro │ │ ├── imu.gazebo.urdf.xacro │ │ ├── mir.gazebo.xacro │ │ ├── mir.transmission.xacro │ │ ├── mir_100_v1.urdf.xacro │ │ ├── mir_v1.urdf.xacro │ │ └── sick_s300.urdf.xacro │ └── mir.urdf.xacro ├── mir_driver/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── launch/ │ │ └── mir.launch │ ├── nodes/ │ │ ├── fake_mir_joint_publisher.py │ │ ├── mir_bridge.py │ │ ├── rep117_filter.py │ │ └── tf_remove_child_frames.py │ ├── package.xml │ ├── setup.py │ └── src/ │ └── mir_driver/ │ ├── __init__.py │ └── rosbridge.py ├── mir_dwb_critics/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── default_critics.xml │ ├── include/ │ │ └── mir_dwb_critics/ │ │ ├── path_angle.h │ │ ├── path_dist_pruned.h │ │ └── path_progress.h │ ├── nodes/ │ │ ├── plot_dwb_scores.py │ │ └── print_dwb_scores.py │ ├── package.xml │ └── src/ │ ├── path_angle.cpp │ ├── path_dist_pruned.cpp │ └── path_progress.cpp ├── mir_gazebo/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config/ │ │ └── ekf.yaml │ ├── launch/ │ │ ├── fake_localization.launch │ │ ├── includes/ │ │ │ ├── ekf.launch.xml │ │ │ └── spawn_maze.launch.xml │ │ ├── mir_empty_world.launch │ │ ├── mir_gazebo_common.launch │ │ └── mir_maze_world.launch │ ├── maps/ │ │ ├── maze.yaml │ │ └── maze_virtual_walls.yaml │ ├── package.xml │ └── sdf/ │ └── maze/ │ ├── model.config │ └── model.sdf ├── mir_msgs/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── msg/ │ │ ├── AngleMeasurment.msg │ │ ├── BMSData.msg │ │ ├── BatteryCurrents.msg │ │ ├── BrakeState.msg │ │ ├── ChargingState.msg │ │ ├── Device.msg │ │ ├── Devices.msg │ │ ├── EncoderTestEntry.msg │ │ ├── Encoders.msg │ │ ├── Error.msg │ │ ├── Event.msg │ │ ├── Events.msg │ │ ├── ExternalRobot.msg │ │ ├── ExternalRobots.msg │ │ ├── Gpio.msg │ │ ├── GripperState.msg │ │ ├── HeightState.msg │ │ ├── HookData.msg │ │ ├── HookExtendedStatus.msg │ │ ├── HookStatus.msg │ │ ├── IOs.msg │ │ ├── JoystickVel.msg │ │ ├── LocalMapStat.msg │ │ ├── MirExtra.msg │ │ ├── MirLocalPlannerPathTypes.msg │ │ ├── MissionCtrlCommand.msg │ │ ├── MissionCtrlState.msg │ │ ├── MovingState.msg │ │ ├── PalletLifterStatus.msg │ │ ├── Path.msg │ │ ├── Pendant.msg │ │ ├── PlanSegment.msg │ │ ├── PlanSegments.msg │ │ ├── Pose2D.msg │ │ ├── PowerBoardMotorStatus.msg │ │ ├── PrecisionDockingStatus.msg │ │ ├── Proximity.msg │ │ ├── ResourceState.msg │ │ ├── ResourcesAcquisition.msg │ │ ├── ResourcesState.msg │ │ ├── RobotMode.msg │ │ ├── RobotState.msg │ │ ├── RobotStatus.msg │ │ ├── SafetyStatus.msg │ │ ├── Serial.msg │ │ ├── ServiceResponseHeader.msg │ │ ├── SkidDetectionDiff.msg │ │ ├── SkidDetectionStampedFloat.msg │ │ ├── SoundEvent.msg │ │ ├── StampedEncoders.msg │ │ ├── TimeDebug.msg │ │ ├── Trolley.msg │ │ ├── Twist2D.msg │ │ ├── UserPrompt.msg │ │ ├── WebPath.msg │ │ ├── WorldMap.msg │ │ └── WorldModel.msg │ └── package.xml ├── mir_navigation/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config/ │ │ ├── base_local_planner_params.yaml │ │ ├── costmap_common_params.yaml │ │ ├── costmap_global_params.yaml │ │ ├── costmap_global_params_plugins_no_virtual_walls.yaml │ │ ├── costmap_global_params_plugins_virtual_walls.yaml │ │ ├── costmap_local_params.yaml │ │ ├── costmap_local_params_plugins_no_virtual_walls.yaml │ │ ├── costmap_local_params_plugins_virtual_walls.yaml │ │ ├── dwa_local_planner_params.yaml │ │ ├── dwb_local_planner_params.yaml │ │ ├── eband_local_planner_params.yaml │ │ ├── mir_local_planner_params.yaml │ │ ├── move_base_common_params.yaml │ │ ├── pose_local_planner_params.yaml │ │ ├── rpp_local_planner_params.yaml │ │ ├── sbpl_global_params.yaml │ │ └── teb_local_planner_params.yaml │ ├── launch/ │ │ ├── amcl.launch │ │ ├── hector_mapping.launch │ │ ├── move_base.xml │ │ ├── start_maps.launch │ │ └── start_planner.launch │ ├── mprim/ │ │ ├── genmprim_unicycle_highcost_5cm.m │ │ ├── genmprim_unicycle_highcost_5cm.py │ │ ├── unicycle_5cm.mprim │ │ ├── unicycle_5cm_expensive_turn_in_place.mprim │ │ ├── unicycle_5cm_expensive_turn_in_place_highcost.mprim │ │ ├── unicycle_5cm_noreverse_trolley.mprim │ │ ├── unicycle_highcost_10cm.mprim │ │ ├── unicycle_highcost_1cm.mprim │ │ ├── unicycle_highcost_2_5cm.mprim │ │ ├── unicycle_highcost_2cm.mprim │ │ └── unicycle_highcost_5cm.mprim │ ├── nodes/ │ │ ├── acc_finder.py │ │ └── min_max_finder.py │ ├── package.xml │ ├── rviz/ │ │ └── navigation.rviz │ └── scripts/ │ └── plot_mprim.py ├── mir_robot/ │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ └── package.xml ├── pyproject.toml └── sdc21x0/ ├── CHANGELOG.rst ├── CMakeLists.txt ├── msg/ │ ├── Encoders.msg │ ├── MotorCurrents.msg │ └── StampedEncoders.msg ├── package.xml └── srv/ └── Flags.srv ================================================ FILE CONTENTS ================================================ ================================================ FILE: .clang-format ================================================ --- BasedOnStyle: Google ColumnLimit: 120 MaxEmptyLinesToKeep: 1 SortIncludes: false Standard: Auto IndentWidth: 2 TabWidth: 2 UseTab: Never AccessModifierOffset: -2 ConstructorInitializerIndentWidth: 2 NamespaceIndentation: None ContinuationIndentWidth: 4 IndentCaseLabels: true IndentFunctionDeclarationAfterType: false AlignEscapedNewlinesLeft: false AlignTrailingComments: true AllowAllParametersOfDeclarationOnNextLine: false ExperimentalAutoDetectBinPacking: false ObjCSpaceBeforeProtocolList: true Cpp11BracedListStyle: false AllowShortBlocksOnASingleLine: true AllowShortIfStatementsOnASingleLine: false AllowShortLoopsOnASingleLine: false AllowShortFunctionsOnASingleLine: None AllowShortCaseLabelsOnASingleLine: false AlwaysBreakTemplateDeclarations: true AlwaysBreakBeforeMultilineStrings: false BreakBeforeBinaryOperators: false BreakBeforeTernaryOperators: false BreakConstructorInitializersBeforeComma: true BinPackParameters: true ConstructorInitializerAllOnOneLineOrOnePerLine: true DerivePointerBinding: false PointerBindsToType: true PenaltyExcessCharacter: 50 PenaltyBreakBeforeFirstCallParameter: 30 PenaltyBreakComment: 1000 PenaltyBreakFirstLessLess: 10 PenaltyBreakString: 100 PenaltyReturnTypeOnItsOwnLine: 50 SpacesBeforeTrailingComments: 2 SpacesInParentheses: false SpacesInAngles: false SpaceInEmptyParentheses: false SpacesInCStyleCastParentheses: false SpaceAfterCStyleCast: false SpaceAfterControlStatementKeyword: true SpaceBeforeAssignmentOperators: true # Configure each individual brace in BraceWrapping BreakBeforeBraces: Custom # Control of individual brace wrapping cases BraceWrapping: AfterCaseLabel: true AfterClass: true AfterControlStatement: true AfterEnum: true AfterFunction: true AfterNamespace: true AfterStruct: true AfterUnion: true BeforeCatch: true BeforeElse: true IndentBraces: false ... ================================================ FILE: .dockerfilelintrc ================================================ rules: apt-get-update_require_install: off ================================================ FILE: .flake8 ================================================ [flake8] # The line length here has to match the black config in pyproject.toml max-line-length = 120 exclude = .git, __pycache__ extend-ignore = # See https://github.com/PyCQA/pycodestyle/issues/373 E203, E741, ================================================ FILE: .github/workflows/github-actions.yml ================================================ name: Build and run ROS tests on: push: pull_request: workflow_dispatch: inputs: debug_enabled: type: boolean description: 'Run the build with tmate debugging enabled (https://github.com/marketplace/actions/debugging-with-tmate)' required: false default: false jobs: build: strategy: matrix: rosdistro: [noetic] runs-on: ubuntu-latest container: image: ros:${{ matrix.rosdistro }}-ros-core steps: # Enable tmate debugging of manually-triggered workflows if the input option was provided - name: Setup tmate session uses: mxschmitt/action-tmate@v3 if: ${{ github.event_name == 'workflow_dispatch' && inputs.debug_enabled }} with: detached: true - name: Install apt dependencies run: | sudo apt-get update sudo apt-get install -y build-essential clang-format-10 file git python3-catkin-lint python3-catkin-tools python3-pip python3-rosdep - name: Install pip dependencies run: pip install pre-commit - name: Checkout repository uses: actions/checkout@v5 with: path: src/mir_robot - name: Use rosdep to install remaining dependencies run: | sudo rosdep init rosdep update --include-eol-distros rosdep install --from-paths src -i -y --rosdistro ${{ matrix.rosdistro }} - name: Build run: | . /opt/ros/${{ matrix.rosdistro }}/setup.sh catkin init catkin config -j 1 -p 1 catkin build --limit-status-rate 0.1 --no-notify catkin build --limit-status-rate 0.1 --no-notify --make-args tests - name: Run tests run: | . devel/setup.sh catkin run_tests catkin_test_results - name: Run pre-commit hooks run: | cd src/mir_robot pre-commit run -a ================================================ FILE: .gitignore ================================================ *.pyc ================================================ FILE: .markdownlint.yaml ================================================ ## Default state for all rules #default: true ## Path to configuration file to extend #extends: null ## 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 #MD001: true ## MD003/heading-style : Heading style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md003.md MD003: false #MD003: # # Heading style # style: "consistent" ## MD004/ul-style : Unordered list style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md004.md MD004: # List style style: "sublist" ## MD005/list-indent : Inconsistent indentation for list items at the same level : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md005.md #MD005: true ## MD007/ul-indent : Unordered list indentation : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md007.md #MD007: # # Spaces for indent # indent: 2 # # Whether to indent the first level of the list # start_indented: false # # Spaces for first level indent (when start_indented is set) # start_indent: 2 ## MD009/no-trailing-spaces : Trailing spaces : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md009.md #MD009: # # Spaces for line break # br_spaces: 2 # # Allow spaces for empty lines in list items # list_item_empty_lines: false # # Include unnecessary breaks # strict: false ## MD010/no-hard-tabs : Hard tabs : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md010.md #MD010: # # Include code blocks # code_blocks: true # # Fenced code languages to ignore # ignore_code_languages: [] # # Number of spaces for each hard tab # spaces_per_tab: 1 ## MD011/no-reversed-links : Reversed link syntax : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md011.md #MD011: true ## MD012/no-multiple-blanks : Multiple consecutive blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md012.md MD012: # Consecutive blank lines maximum: 2 ## MD013/line-length : Line length : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md013.md MD013: # Number of characters line_length: 120 # Number of characters for headings heading_line_length: 80 # Number of characters for code blocks code_block_line_length: 80 # Include code blocks code_blocks: false # Include tables tables: false # Include headings headings: true # Strict length checking strict: false # Stern length checking stern: false ## MD014/commands-show-output : Dollar signs used before commands without showing output : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md014.md #MD014: true ## 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 #MD018: true ## 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 #MD019: true ## 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 #MD020: true ## 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 #MD021: true ## MD022/blanks-around-headings : Headings should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md022.md #MD022: # # Blank lines above heading # lines_above: 1 # # Blank lines below heading # lines_below: 1 ## 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 #MD023: true ## MD024/no-duplicate-heading : Multiple headings with the same content : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md024.md MD024: # Only check sibling headings siblings_only: true ## 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 #MD025: # # RegExp for matching title in front matter # front_matter_title: "^\\s*title\\s*[:=]" # # Heading level # level: 1 ## MD026/no-trailing-punctuation : Trailing punctuation in heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md026.md #MD026: # # Punctuation characters # punctuation: ".,;:!。,;:!" ## MD027/no-multiple-space-blockquote : Multiple spaces after blockquote symbol : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md027.md #MD027: # # Include list items # list_items: true ## MD028/no-blanks-blockquote : Blank line inside blockquote : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md028.md #MD028: true ## MD029/ol-prefix : Ordered list item prefix : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md029.md MD029: # List style style: "ordered" ## MD030/list-marker-space : Spaces after list markers : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md030.md #MD030: # # Spaces for single-line unordered list items # ul_single: 1 # # Spaces for single-line ordered list items # ol_single: 1 # # Spaces for multi-line unordered list items # ul_multi: 1 # # Spaces for multi-line ordered list items # ol_multi: 1 ## 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 #MD031: # # Include list items # list_items: true ## MD032/blanks-around-lists : Lists should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md032.md #MD032: true ## MD033/no-inline-html : Inline HTML : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md033.md #MD033: # # Allowed elements # allowed_elements: [] ## MD034/no-bare-urls : Bare URL used : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md034.md MD034: false ## MD035/hr-style : Horizontal rule style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md035.md #MD035: # # Horizontal rule style # style: "consistent" ## MD036/no-emphasis-as-heading : Emphasis used instead of a heading : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md036.md #MD036: # # Punctuation characters # punctuation: ".,;:!?。,;:!?" ## MD037/no-space-in-emphasis : Spaces inside emphasis markers : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md037.md #MD037: true ## MD038/no-space-in-code : Spaces inside code span elements : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md038.md #MD038: true ## MD039/no-space-in-links : Spaces inside link text : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md039.md #MD039: true ## MD040/fenced-code-language : Fenced code blocks should have a language specified : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md040.md #MD040: # # List of languages # allowed_languages: [] # # Require language only # language_only: false ## 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 #MD041: # # Allow content before first heading # allow_preamble: false # # RegExp for matching title in front matter # front_matter_title: "^\\s*title\\s*[:=]" # # Heading level # level: 1 ## MD042/no-empty-links : No empty links : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md042.md #MD042: true ## MD043/required-headings : Required heading structure : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md043.md #MD043: # # List of headings # headings: [] # # Match case of headings # match_case: false ## MD044/proper-names : Proper names should have the correct capitalization : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md044.md #MD044: # # List of proper names # names: [] # # Include code blocks # code_blocks: true # # Include HTML elements # html_elements: true ## MD045/no-alt-text : Images should have alternate text (alt text) : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md045.md MD045: true ## MD046/code-block-style : Code block style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md046.md #MD046: # # Block style # style: "consistent" ## MD047/single-trailing-newline : Files should end with a single newline character : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md047.md #MD047: true ## MD048/code-fence-style : Code fence style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md048.md #MD048: # # Code fence style # style: "consistent" ## MD049/emphasis-style : Emphasis style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md049.md #MD049: # # Emphasis style # style: "consistent" ## MD050/strong-style : Strong style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md050.md #MD050: # # Strong style # style: "consistent" ## MD051/link-fragments : Link fragments should be valid : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md051.md #MD051: # # Ignore case of fragments # ignore_case: false # # Pattern for ignoring additional fragments # ignored_pattern: "" ## 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 #MD052: # # Ignored link labels # ignored_labels: # - "x" # # Include shortcut syntax # shortcut_syntax: false ## 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 #MD053: # # Ignored definitions # ignored_definitions: # - "//" ## MD054/link-image-style : Link and image style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md054.md #MD054: # # Allow autolinks # autolink: true # # Allow inline links and images # inline: true # # Allow full reference links and images # full: true # # Allow collapsed reference links and images # collapsed: true # # Allow shortcut reference links and images # shortcut: true # # Allow URLs as inline links # url_inline: true ## MD055/table-pipe-style : Table pipe style : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md055.md #MD055: # # Table pipe style # style: "consistent" ## MD056/table-column-count : Table column count : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md056.md #MD056: true ## MD058/blanks-around-tables : Tables should be surrounded by blank lines : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md058.md #MD058: true ## MD059/descriptive-link-text : Link text should be descriptive : https://github.com/DavidAnson/markdownlint/blob/v0.38.0/doc/md059.md #MD059: # # Prohibited link texts # prohibited_texts: # - "click here" # - "here" # - "link" # - "more" ================================================ FILE: .pre-commit-config.yaml ================================================ # To use: # # pre-commit run -a # # Or: # # pre-commit install # (runs every time you commit in git) # # To update this file: # # pre-commit autoupdate # # See https://github.com/pre-commit/pre-commit repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks rev: v4.6.0 hooks: - id: check-added-large-files - id: check-case-conflict - id: check-executables-have-shebangs - id: check-docstring-first - id: check-merge-conflict - id: check-shebang-scripts-are-executable - id: check-symlinks - id: check-vcs-permalinks - id: check-xml - id: check-yaml - id: debug-statements - id: end-of-file-fixer exclude: &excludes | (?x)^( .*\.blend| .*\.dae| .*\.mtl| .*\.obj| .*\.pgm| .*\.step| .*\.stl )$ - id: fix-byte-order-marker - id: mixed-line-ending exclude: *excludes - id: trailing-whitespace exclude: *excludes - repo: https://github.com/psf/black rev: 24.3.0 hooks: - id: black - repo: https://github.com/PyCQA/flake8.git rev: 7.0.0 hooks: - id: flake8 - repo: https://github.com/detailyang/pre-commit-shell.git rev: v1.0.6 hooks: - id: shell-lint args: [--external-sources] - repo: https://github.com/igorshubovych/markdownlint-cli rev: v0.45.0 hooks: - id: markdownlint language_version: 24.2.0 - repo: https://github.com/pryorda/dockerfilelint-precommit-hooks rev: v0.1.0 hooks: - id: dockerfilelint - repo: https://github.com/Lucas-C/pre-commit-hooks rev: v1.5.1 hooks: - id: insert-license files: \.py$ exclude: | (?x)^( .*setup\.py| .*__init__\.py| .*test_copyright\.py| .*test_pep257\.py| mir_driver/nodes/tf_remove_child_frames\.py| mir_navigation/mprim/genmprim_unicycle_highcost_5cm\.py )$ args: - --license-filepath - LICENSE - repo: https://github.com/pycqa/pydocstyle rev: 6.3.0 hooks: - id: pydocstyle args: - --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 - repo: local hooks: - id: clang-format name: clang-format description: Format files with ClangFormat. entry: clang-format-10 language: system files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|proto|vert)$ args: [ "-fallback-style=none", "-i" ] - id: catkin_lint name: catkin_lint description: Check package.xml and cmake files entry: catkin_lint . language: system always_run: true pass_filenames: false args: [ "--strict" ] ================================================ FILE: Dockerfile-noetic ================================================ FROM ros:noetic-ros-core RUN apt-get update \ && apt-get install -y --no-install-recommends build-essential python3-rosdep python3-catkin-lint python3-catkin-tools \ && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* # Install pre-commit hooks to /root/.cache/pre-commit/ RUN apt-get update -qq \ && apt-get install -y -qq --no-install-recommends git python3-pip ruby shellcheck clang-format-10 python3-catkin-lint \ && rm -rf /var/lib/apt/lists/* RUN pip3 install pre-commit RUN mkdir -p /tmp/pre-commit COPY .pre-commit-config.yaml /tmp/pre-commit/ RUN cd /tmp/pre-commit \ && git init \ && pre-commit install-hooks \ && rm -rf /tmp/pre-commit # Create ROS workspace COPY . /ws/src/mir_robot WORKDIR /ws # Use rosdep to install all dependencies (including ROS itself) RUN rosdep init \ && rosdep update --include-eol-distros \ && apt-get update \ && DEBIAN_FRONTEND=noninteractive rosdep install --from-paths src -i -y --rosdistro noetic \ && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && \ catkin init && \ catkin config --install -j 1 -p 1 && \ catkin build --limit-status-rate 0.1 --no-notify && \ catkin build --limit-status-rate 0.1 --no-notify --make-args tests" ================================================ FILE: LICENSE ================================================ Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ================================================ FILE: README.md ================================================ mir_robot ========= This repo contains a ROS driver and ROS configuration files (URDF description, Gazebo launch files, move_base config, bringup launch files, message and action descriptions) for the [MiR robots](http://www.mobile-industrial-robots.com/). This is a community project created by us ([DFKI](https://www.dfki.de/), the German Research Center for Artificial Intelligence) to use the MiR Robots with ROS. We are not affiliated with Mobile Industrial Robots. If you find a bug or missing feature in this software, please report it on the [issue tracker](https://github.com/DFKI-NI/mir_robot/issues). Supported MiR robots and software versions ------------------------------------------ This repo has been confirmed to work with the following robots: * MiR 100 * MiR 200 * MiR 250 * MiR 500 It probably also works with the MiR1000. If you can test it on one of those, please let us know if it works. This repo has been tested with the following MiR software versions: * 2.8.3.1 * 2.13.4.1 * 2.13.5.3 You can try if it works with other versions, but these are the ones that are known to work. :warning: **Do NOT update to the upcoming version 3.0; it is very well possible that this repo will no longer work with this version!** Package overview ---------------- * `mir_actions`: Action definitions for the MiR robot * `mir_description`: URDF description of the MiR robot * `mir_dwb_critics`: Plugins for the dwb_local_planner used in Gazebo * `mir_driver`: A reverse ROS bridge for the MiR robot * `mir_gazebo`: Simulation specific launch and configuration files for the MiR robot * `mir_msgs`: Message definitions for the MiR robot * `mir_navigation`: move_base launch and configuration files Installation ------------ You can chose between binary and source install below. If you don't want to modify the source, the binary install is preferred (if `mir_robot` binary packages are available for your ROS distro). The instructions below use the ROS distro `noetic` as an example; if you use a different distro (e.g. `melodic`), replace all occurrences of the string `noetic` by your distro name in the instructions. ### Preliminaries If you haven't already installed ROS on your PC, you need to add the ROS apt repository. This step is necessary for either binary or source install. ```bash sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' wget http://packages.ros.org/ros.key -O - | sudo apt-key add - sudo apt-get update -qq ``` ### Binary install For a binary install, it suffices to run this command: ```bash sudo apt install ros-noetic-mir-robot ``` See the tables at the end of this README for a list of ROS distros for which binary packages are available. ### Source install For a source install, run the commands below instead of the command from the "binary install" section. ```bash # create a catkin workspace mkdir -p ~/catkin_ws/src cd ~/catkin_ws/src/ # clone mir_robot into the catkin workspace git clone -b noetic https://github.com/DFKI-NI/mir_robot.git # use rosdep to install all dependencies (including ROS itself) sudo apt-get update -qq sudo apt-get install -qq -y python-rosdep sudo rosdep init rosdep update --include-eol-distros rosdep install --from-paths ./ -i -y --rosdistro noetic # build all packages in the catkin workspace source /opt/ros/noetic/setup.bash catkin_init_workspace cd ~/catkin_ws catkin_make -DCMAKE_BUILD_TYPE=RelWithDebugInfo ``` In case you encounter problems, please compare the commands above to the build step in [`.github/workflows/github-actions.yml`](.github/workflows/github-actions.yml); that should always have the most recent list of commands. You should add the following line to the end of your `~/.bashrc`, and then close and reopen all terminals: ```bash source ~/catkin_ws/devel/setup.bash ``` Gazebo demo (existing map) -------------------------- https://user-images.githubusercontent.com/320188/145610491-2afeb46c-3729-4106-ab9c-6681b5dd9d2e.mp4 ```bash ### gazebo: roslaunch mir_gazebo mir_maze_world.launch rosservice call /gazebo/unpause_physics # or click the "start" button in the Gazebo GUI ### localization: roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 # or alternatively: roslaunch mir_gazebo fake_localization.launch delta_x:=-10.0 delta_y:=-10.0 # navigation: roslaunch mir_navigation start_planner.launch \ map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz ``` Now, you can use the "2D Nav Goal" tool in RViz to set a navigation goal for move_base. Gazebo demo (mapping) --------------------- ```bash ### gazebo: roslaunch mir_gazebo mir_maze_world.launch rosservice call /gazebo/unpause_physics # or click the "start" button in the Gazebo GUI ### mapping: roslaunch mir_navigation hector_mapping.launch # navigation: roslaunch mir_navigation move_base.xml with_virtual_walls:=false rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz ``` Gazebo demo (MiR 250 in warehouse Gazebo world) ----------------------------------------------- https://user-images.githubusercontent.com/320188/171613044-639f3ab2-fe84-4839-acfc-d0642f8869b3.mp4 This repo contains URDF descriptions for the MiR 100 (default) and the MiR 250. You can switch to the MiR 250 by adding **`mir_type:=mir_250`** to the gazebo roslaunch command. You can also select another Gazebo world using the **`world_name`** argument. For example, the video above was generated using the following commands: ```bash cd git clone -b ros1 https://github.com/aws-robotics/aws-robomaker-small-warehouse-world.git catkin build roslaunch mir_gazebo mir_empty_world.launch \ world_name:=$(rospack find aws_robomaker_small_warehouse_world)/worlds/no_roof_small_warehouse.world \ mir_type:=mir_250 ``` ... and then running the remaining commands from the "mapping" section above. Gazebo demo (multiple robots) ----------------------------- If you want to spawn multiple robots into Gazebo, you unfortunately have to hard-code the name of the second robot into the `mir_empty_world.launch` file, like this: ```diff diff --git i/mir_gazebo/launch/mir_empty_world.launch w/mir_gazebo/launch/mir_empty_world.launch index 27b9159..7773fae 100644 --- i/mir_gazebo/launch/mir_empty_world.launch +++ w/mir_gazebo/launch/mir_empty_world.launch @@ -17,6 +17,10 @@ + + + + ``` Then you can run the simulation like this: ```bash # start Gazebo + first MiR roslaunch mir_gazebo mir_maze_world.launch tf_prefix:=mir # first MiR: start localization, navigation + rviz roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 tf_prefix:=mir roslaunch mir_navigation start_planner.launch \ map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir/ ROS_NAMESPACE=mir rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz # spawn second MiR into Gazebo roslaunch mir_gazebo mir_gazebo_common.launch robot_x:=-2 robot_y:=-2 tf_prefix:=mir2 model_name:=mir2 __ns:=mir2 # second MiR: start localization, navigation + rviz roslaunch mir_navigation amcl.launch initial_pose_x:=8.0 initial_pose_y:=8.0 tf_prefix:=mir2 roslaunch mir_navigation start_planner.launch \ map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir2/ ROS_NAMESPACE=mir2 rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz ``` Running the driver on the real robot ------------------------------------ ### Start up the robot * switch on MiR base ### Connect to the MiR web interface * connect to MiR_R??? wifi (password "mirex4you"), for example from your Android phone/tablet * disable other network connections (mobile data / LAN / etc.) * open mir.com (192.168.12.20) in Chrome (!) * log in (admin/mir4you) ### Synchronize system time The internal robot PC's is not synchronized (for example via NTP), so it tends to get out of sync quickly (about 1 second per day!). This causes TF transforms timing out etc. and can be seen using `tf_monitor` (the "Max Delay" is about 3.3 seconds, but should be less than 0.1 seconds): ```text $ rosrun tf tf_monitor Frames: Frame: /back_laser_link published by unknown_publisher Average Delay: 3.22686 Max Delay: 3.34766 Frame: /base_footprint published by unknown_publisher Average Delay: 3.34273 Max Delay: 3.38062 Frame: /base_link published by unknown_publisher Average Delay: 3.22751 Max Delay: 3.34844 Frame: /front_laser_link published by unknown_publisher Average Delay: 3.22661 Max Delay: 3.34159 Frame: /imu_link published by unknown_publisher Average Delay: 3.22739 Max Delay: 3.34738 Frame: /odom published by unknown_publisher Average Delay: 3.16493 Max Delay: 3.28667 [...] All Broadcasters: Node: unknown_publisher 418.344 Hz, Average Delay: 0.827575 Max Delay: 3.35237 Node: unknown_publisher(static) 465.362 Hz, Average Delay: 0 Max Delay: 0 ``` To fix this: * go to "Service" -> "Configuration" -> "System settings" -> "Time settings" -> "Set device time on robot" Afterwards, the ROS software on the robot will restart, so you'll have to start `move_base` again (see below). If you have an external PC on the MiR platform, you can use `chrony` to automatically synchronize system time (see below). ### Start `move_base` on the robot * go to "Service" -> "Configuration" -> "Launch menu", start "Planner"; this starts `move_base` and `amcl` on the robot ### Teleoperate the robot (optional) * go to "Manual", press yellow button (LEDs change from yellow to blue); now the robot can be teleoperated ### Relocalize robot (optional) If the robot's localization is lost: * go to "Service" -> "Command view" -> "Set start position" and click + drag to current position of robot in the map * click "Adjust" ### Start the ROS driver ```bash roslaunch mir_driver mir.launch ``` Advanced -------- ### Installing chrony to synchronize system time automatically If you have an external PC integrated into your robot that is on the same wired network as the MiR PC, you can use `chrony` to automatically synchronize the MiR's system time. Unfortunately, this method is not easy to install. Let's call the external PC `external-pc`. That PC's clock is our reference clock. It is synced to an NTP clock whenever the `external-pc` has access to the internet. To implement this synchronization solution, install `chrony` on both the `external-pc` and the internal PC of the MiR, and set up the `external-pc` as the chrony server and the internal MiR PC as the chrony client. This way, the clocks on these systems always stay in sync without any manual interaction. To install things on the internal MiR PC: * Connect a monitor, keyboard and USB stick with a live Linux system to the ports that are exposed on one corner of the MiR. * Boot into the live USB Linux system. * `chroot` into the MiR PC: 1. Mount MiR partition and bind /dev, /run etc. You can use fdisk -l to figure out which partition to mount. (Here it's `sda3`): ```bash sudo mkdir -p /media/mir sudo mount /dev/sda3 /media/mir for dir in /dev /dev/pts /proc /sys /run; do sudo mount --bind $dir /media/mir/@$dir; done ``` 2. `chroot` into the MiR PC: ```bash sudo chroot /media/mir/@/ ``` * Create user: ```bash adduser newuser usermod -aG sudo newuser ``` * Reboot and log into MiR PC via SSH and the newly created user name. * Install Chrony: ```bash sudo apt update sudo apt install chrony # if not installable (to fix broken dependencies): sudo apt -f install sudo apt install chrony ``` * Set up `/etc/chrony/chrony.conf`. * Make sure all old ntp configs are configured in chrony. For this, add the following to your chrony.conf (the old ntp.conf part is commented out): ```bash # Clients from this subnet have unlimited access, but only if # cryptographically authenticated. #restrict 192.168.12.255 mask 255.255.255.0 nomodify notrap nopeer allow 192.168.12.0/24 nomodify notrap nopeer ``` * Restart chrony service. Troubleshooting --------------- ### Got a result when we were already in the DONE state Sometimes the move_base action will print the warning "Got a result when we were already in the DONE state". This is caused by a race condition between the `/move_base/result` and `/move_base/status` topics. When a status message with status `SUCCEEDED` arrives before the corresponding result message, this warning will be printed. It can be safely ignored. ### Gazebo prints errors: "No p gain specified for pid." These errors are expected and can be ignored. Unfortunately, we cannot set the PID gains (to silence the error) due to the following behavior of Gazebo: 1. When using the `PositionJointInterface`, you *must* set the PID values for the joints using that interface, otherwise you will run into [this bug](https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612). 2. When using the `VelocityJointInterface`, if you omit the PID values, Gazebo just perfectly follows the commanded velocities. If you specify PID values, Gazebo will use a PID controller to approximate following the commanded velocities, so you have to tune the PID controllers. Since we just want Gazebo to follow our commanded velocities, we cannot set the PID values for joints using the VelocityJointInterface, so the errors get printed (but can be ignored). pre-commit Formatting Checks ---------------------------- This repo has a [pre-commit](https://pre-commit.com/) check that runs in CI. You can use this locally and set it up to run automatically before you commit something. To install, use pip: ```bash pip3 install --user pre-commit ``` To run over all the files in the repo manually: ```bash pre-commit run -a ``` To run pre-commit automatically before committing in the local repo, install the git hooks: ```bash pre-commit install ``` GitHub Actions - Continuous Integration --------------------------------------- | Noetic | |--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| | [![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/) | ROS Buildfarm ------------- | | Noetic source deb | Noetic binary deb | |--------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| | [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/) | | [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/) | | [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/) | | [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/) | | [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/) | | [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/) | | [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/) | | [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/) | | [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/) | | | Noetic devel | Noetic doc | |--------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------| | [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) | ================================================ FILE: mir_actions/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_actions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Update MirMoveBase action to 2.10.3.1 * Don't set cmake_policy CMP0048 * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ * Rename mir_100 -> mir This is in preparation of mir_250 support. * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Remove RelativeMove action It was removed in MiR software 2.4.0. * Update mir_actions to MiR 2.8.3 * Adjust to changed MirMoveBase action (MiR >= 2.4.0) See `#45 `_. * Contributors: Martin Günther 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ 1.0.4 (2019-05-06) ------------------ * Update mir_msgs and mir_actions to MiR 2.3.1 * Contributors: Martin Günther 1.0.3 (2019-03-04) ------------------ 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_actions/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_actions) find_package(catkin REQUIRED COMPONENTS actionlib geometry_msgs message_generation mir_msgs nav_msgs ) ################################################ ## Declare ROS messages, services and actions ## ################################################ # Generate actions in the 'action' folder add_action_files( FILES MirMoveBase.action ) # Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES geometry_msgs mir_msgs nav_msgs ) ################################### ## catkin specific configuration ## ################################### catkin_package( CATKIN_DEPENDS actionlib geometry_msgs message_runtime mir_msgs nav_msgs ) ================================================ FILE: mir_actions/action/MirMoveBase.action ================================================ #goal definition #move type int16 BASE_MOVE = 0 int16 GLOBAL_MOVE = 1 int16 RELATIVE_MOVE = 2 int16 RELATIVE_MARKER_MOVE = 3 int16 DOCKING_MOVE = 4 int16 DOCKING_GLOBAL_MOVE = 5 int16 PATH_TYPE = 6 int16 move_task #shared parameters geometry_msgs/PoseStamped target_pose string target_guid #global move parameters float64 goal_dist_threshold float64 goal_orientation_threshold nav_msgs/Path path float32 max_plan_time bool clear_costmaps bool pause_command bool continue_command #relative move parameters float64 yaw bool collision_detection bool collision_avoidance float64 disable_collision_check_dist float64 max_linear_speed float64 max_rotational_speed float64 pid_dist_offset float64 target_offset bool only_collision_detection float64 timeout #docking move parameters int32 pattern_type int32 pattern_value bool only_track bool same_goal string pose_frame geometry_msgs/Pose2D pose geometry_msgs/Pose2D offset float64 bar_length float64 bar_distance float64 shelf_leg_asymmetry_x float64 tolerance #Path type mir_msgs/MirLocalPlannerPathTypes path_type geometry_msgs/PoseStamped start_pose # float64 timeout --- #result definition #shared states int16 UNDEFINED = 0 int16 GOAL_REACHED = 1 int16 FAILED = -1 #global move states int16 MARKER_VISIBLE = 2 int16 FAILED_NO_PATH = -2 int16 FAILED_GOAL_IN_STATIC_OBSTACLE = -3 int16 FAILED_GOAL_IN_FORBIDDEN_AREA = -4 int16 FAILED_GOAL_IN_DYNAMIC_OBSTACLE = -5 int16 FAILED_ROBOT_IN_COLLISION = -6 int16 FAILED_ROBOT_IN_FORBIDDEN_AREA = -7 int16 FAILED_UNKNOWN_TRAILER = -8 int16 FAILED_TO_PASS_GLOBAL_PLAN = -9 int16 FAILED_NO_VALID_RECOVERY_CONTROL = -10 int16 FAILED_UNKNOWN_PLANNER_ERROR = -11 int16 FAILED_ROBOT_OSCILLATING = -12 int16 FAILED_SOFTWARE_ERROR = -13 #relative move states int16 FAILED_TIMEOUT = -14 int16 FAILED_COLLISION = -15 int16 INVALID_GOAL = -16 #docking move states int16 FAILED_MARKER_TRACKING_ERROR = -17 #shared results int16 end_state geometry_msgs/PoseStamped end_pose #docking results geometry_msgs/Pose2D pose #feedback for UI string message --- #feedback #shared int8 NOT_READY = -1 int8 UNKNOWN = -2 int8 WAITING_FOR_FLEET = -3 int8 COLLISION = -4 #global move states int8 PLANNING = 0 int8 CONTROLLING = 1 int8 CLEARING = 2 #relative move states int8 DOCKING = 3 #shared feedback int8 state #global move feedback geometry_msgs/PoseStamped base_position #relative move feedback geometry_msgs/PoseStamped current_goal geometry_msgs/PoseStamped dist_to_goal #docking move feedback geometry_msgs/Pose2D pose bool marker_inversion #path_types #reverse_trolly int8 MOVING_FORWARD = 10 int8 MOVING_BACKWARD = 11 ================================================ FILE: mir_actions/package.xml ================================================ mir_actions 1.1.8 Action definitions for the MiR robot Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin actionlib geometry_msgs mir_msgs nav_msgs message_generation message_runtime ================================================ FILE: mir_description/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ * URDF: Downsize inertia box, move to lower back * URDF: Pull out inertia properties * URDF: Update masses according to data sheet * URDF: Add mir_250 * Add arg mir_type to launch files and urdfs * Add mir_250 meshes * URDF: Make wheels black * Add mir_100_v1.urdf.xacro for backwards compatibility * Rename mir_100 -> mir * Refactor URDF to prepare for MiR250 support * Gazebo: Don't manually specify wheel params for diffdrive controller * Simplify mir_100 collision mesh further * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ * Remove xacro comment to work around xacro bug Since xacro 1.14.11, xacro now also evaluates expressions in comments and throws an error if the substition argument is undefined. In xacro 1.14.12, this error was changed to a warning. This commit removes that warning. Workaround for https://github.com/ros/xacro/issues/309 . * xacro: drop --inorder option In-order processing became default in ROS Melodic. * Add gazebo_plugins to dependency list (`#103 `_) This is needed for the ground truth pose via p3d plugin. * Contributors: Martin Günther, moooeeeep 1.1.4 (2021-12-10) ------------------ * Replace gazebo_plugins IMU with hector_gazebo_plugins * Use cylinders instead of STLs for wheel collision geometries Fixes `#99 `_. * mir_debug_urdf.launch: Fix GUI display * Contributors: Martin Günther 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Rename tf frame and topic 'odom_comb' -> 'odom' This is how they are called on the real MiR since MiR software 2.0. * Contributors: Martin Günther 1.1.2 (2021-05-12) ------------------ * Fix laser scan frame_id with gazebo_plugins 2.9.2 * Contributors: Martin Günther 1.1.1 (2021-02-11) ------------------ * Add prepend_prefix_to_laser_frame to URDF and launch files Fixes `#65 `_. * Add tf_prefix to URDF and launch files * Fix typo in robot_namespace * Add missing 'xacro:' xml namespace prefixes Macro calls without 'xacro:' prefix are deprecated in Melodic and will be forbidden in Noetic. * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Update to non-deprecated robot_state_publisher node * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ * Switch from Gazebo GPU laser to normal laser plugin The GPU laser plugin has caused multiple people problems before, because it is not compatible with all GPUS: `#1 `_ `#32 `_ `#46 `_ `#52 `_ The normal laser plugin directly uses the physics engine, so it doesn't depend on any specific GPU. Also, it doesn't slow down the simulation noticeably (maybe 1-2%). * Contributors: Martin Günther 1.0.4 (2019-05-06) ------------------ * Add legacyModeNS param to gazebo_ros_control plugin This enables the new behavior of the plugin (pid_gains parameter are now in the proper namespace). * re-added gazebo friction parameters for the wheels (`#19 `_) * Contributors: Martin Günther, niniemann 1.0.3 (2019-03-04) ------------------ * Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs Add prefix argument to configs * removed prefix from plugin frameName in sick urdf The gazebo plugins automatically use tf_prefix, even if none is set (in that case it defaults to the robot namespace). That's why we can remove the prefix from the plugins configuration, assuming that the robot namespace will be equal to the prefix. * adds $(arg prefix) to a lot of configs This is an important step to be able to re-parameterize move base, the diffdrive controller, ekf, amcl and the costmaps for adding a tf prefix to the robots links * workaround eval in xacro for indigo support * adds tf_prefix argument to imu.gazebo.urdf.xacro * Add TFs for ultrasound sensors * Contributors: Martin Günther, Nils Niemann 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ * gazebo: Remove leading slashes in TF frames TF2 doesn't like it (e.g., robot_localization). * Contributors: Martin Günther 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_description/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_description) find_package(catkin REQUIRED COMPONENTS roslaunch ) ################################### ## catkin specific configuration ## ################################### catkin_package() ############# ## Install ## ############# # Mark other files for installation (e.g. launch and bag files, etc.) install(DIRECTORY config launch meshes rviz urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ############# ## Testing ## ############# roslaunch_add_file_check(launch) ================================================ FILE: mir_description/config/diffdrive_controller.yaml ================================================ # ----------------------------------- mobile_base_controller: type : "diff_drive_controller/DiffDriveController" left_wheel : '$(arg prefix)left_wheel_joint' right_wheel : '$(arg prefix)right_wheel_joint' publish_rate: 41.2 # this is what the real MiR platform publishes (default: 50) # These covariances are exactly what the real MiR platform publishes pose_covariance_diagonal : [0.00001, 0.00001, 1000000.0, 1000000.0, 1000000.0, 1000.0] twist_covariance_diagonal: [0.1, 0.1, 1000000.0, 1000000.0, 1000000.0, 1000.0] enable_odom_tf: false # Wheel separation and diameter. These are both optional. # diff_drive_controller will attempt to read either one or both from the # URDF if not specified as a parameter. # We don't set the value here because it's different for each MiR type (100, 250, ...), and # the plugin figures out the correct values. #wheel_separation : 0.445208 #wheel_radius : 0.0625 # Wheel separation and radius multipliers wheel_separation_multiplier: 1.0 # default: 1.0 wheel_radius_multiplier : 1.0 # default: 1.0 # Velocity commands timeout [s], default 0.5 cmd_vel_timeout: 0.5 # frame_ids (same as real MiR platform) base_frame_id: $(arg prefix)base_footprint # default: base_link odom_frame_id: $(arg prefix)odom # default: odom # Velocity and acceleration limits # Whenever a min_* is unspecified, default to -max_* linear: x: has_velocity_limits : true max_velocity : 1.0 # m/s; move_base max_vel_x: 0.8 has_acceleration_limits: true max_acceleration : 2.0 # m/s^2; move_base acc_lim_x: 1.5 angular: z: has_velocity_limits : true max_velocity : 1.5 # rad/s; move_base max_rot_vel: 1.0 has_acceleration_limits: true max_acceleration : 2.5 # rad/s^2; move_base acc_lim_th: 2.0 ================================================ FILE: mir_description/config/joint_state_controller.yaml ================================================ # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 ================================================ FILE: mir_description/launch/mir_debug_urdf.launch ================================================ ================================================ FILE: mir_description/launch/upload_mir_urdf.launch ================================================ ================================================ FILE: mir_description/package.xml ================================================ mir_description 1.1.8 URDF description of the MiR robot Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin roslaunch diff_drive_controller gazebo_plugins gazebo_ros_control hector_gazebo_plugins joint_state_controller joint_state_publisher joint_state_publisher_gui position_controllers robot_state_publisher rviz urdf xacro ================================================ FILE: mir_description/rviz/mir_description.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 81 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 Splitter Ratio: 0.5 Tree Height: 535 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: "" Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: Value: true - Alpha: 1 Class: rviz/RobotModel Collision Enabled: false Enabled: true Links: All Links Enabled: true Expand Joint Details: false Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order back_laser_link: Alpha: 1 Show Axes: false Show Trail: false Value: true base_footprint: Alpha: 1 Show Axes: false Show Trail: false base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true bl_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true bl_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true br_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true br_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fl_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fl_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fr_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fr_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true front_laser_link: Alpha: 1 Show Axes: false Show Trail: false Value: true imu_frame: Alpha: 1 Show Axes: false Show Trail: false imu_link: Alpha: 1 Show Axes: false Show Trail: false left_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true right_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true surface: Alpha: 1 Show Axes: false Show Trail: false Name: RobotModel Robot Description: robot_description TF Prefix: "" Update Interval: 0 Value: true Visual Enabled: true Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: base_footprint Frame Rate: 30 Name: root Tools: - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/MoveCamera - Class: rviz/Select - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose Topic: /initialpose - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint Single click: true Topic: /clicked_point Value: true Views: Current: Class: rviz/Orbit Distance: 2.20704937 Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0.023150593 Y: -0.0341755934 Z: -2.6775524e-09 Focal Shape Fixed Size: false Focal Shape Size: 0.0500000007 Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Pitch: 0.515398085 Target Frame: Value: Orbit (rviz) Yaw: 0.490397513 Saved: ~ Window Geometry: Displays: collapsed: false Height: 846 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000016a000002a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006700fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000043000002a9000000e300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002a9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000043000002a9000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000022300fffffffb0000000800540069006d006501000000000000045000000000000000000000022b000002a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1200 X: 59 Y: 29 ================================================ FILE: mir_description/urdf/include/common.gazebo.xacro ================================================ ${robot_namespace} 0.001 false ================================================ FILE: mir_description/urdf/include/common_properties.urdf.xacro ================================================ ================================================ FILE: mir_description/urdf/include/imu.gazebo.urdf.xacro ================================================ ${update_rate} ${link} ${imu_frame} ${imu_topic} 0.0 0.0 0.0 ${sqrt(5e-05)} ${sqrt(0.0001)} ${sqrt(0.00013)} 0.0 0.0 0.0 ${sqrt(8e-06)} ${sqrt(8e-06)} ${sqrt(3e-07)} 0.0 ${sqrt(0.1)} ================================================ FILE: mir_description/urdf/include/mir.gazebo.xacro ================================================ false true 1000.0 ${left_wheel_joint} ${right_wheel_joint} ${wheel_separation} ${2*wheel_radius} 10 1 map mobile_base_controller/cmd_vel mobile_base_controller/odom base_footprint 2.8 true false world Debug 0.01 true 50.0 ${prefix}base_footprint base_pose_ground_truth 0.01 map 0 0 0 0 0 0 ================================================ FILE: mir_description/urdf/include/mir.transmission.xacro ================================================ transmission_interface/SimpleTransmission hardware_interface/VelocityJointInterface hardware_interface/VelocityJointInterface 1 ================================================ FILE: mir_description/urdf/include/mir_100_v1.urdf.xacro ================================================ ================================================ FILE: mir_description/urdf/include/mir_v1.urdf.xacro ================================================ Gazebo/FlatBlack Gazebo/Grey Gazebo/FlatBlack Gazebo/FlatBlack Gazebo/White Gazebo/DarkGrey ================================================ FILE: mir_description/urdf/include/sick_s300.urdf.xacro ================================================ 0 0 0 0 0 0 false 12.5 541 1 -2.35619449615 2.35619449615 0.05 29.0 0.01 gaussian 0.0 0.01 ${prefix}${link} ${topic} ================================================ FILE: mir_description/urdf/mir.urdf.xacro ================================================ ================================================ FILE: mir_driver/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_driver ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Fix typo in license * pre-commit: Update hook versions * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Fix pydocstyle errors * Add license headers * Fix flake8 warnings * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ * Add arg mir_type to launch files and urdfs * Rename mir_100 -> mir This is in preparation of mir_250 support. * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Subscribe to move_base_simple/goal in relative namespace * Use absolute topics for /tf, /tf_static, /map etc. * Rename tf frame and topic 'odom_comb' -> 'odom' This is how they are called on the real MiR since MiR software 2.0. * Fix handling of tf_static topic This does two things: 1. Make the tf_static topic latched. 2. Cache all transforms, publish as one message. * Increase queue_size for publishers + subscribers to 10 One case where this was a problem was the tf_static topic: Since multiple messages are being published at once, the subscriber often missed one. The tf_static topic will be fixed anyway in the next commit, but let's increase the queue_size anyway to avoid such bugs in the future. * Update topic list to 2.8.3.1 * Reformat python code using black * Remove outdated topics These topics don't exist on MiR software 2.8.3 any more (most of them have been removed a long time ago). Fixes `#37 `_. * Remove MirStatus This message was removed in MiR software 2.0 (Renamed to RobotStatus). * Use same MirMoveBase params as real MiR (2.8.3) This shouldn't make a difference (it used to work before). Just removing one more potential source of error. * Fix: Converts move_base_simple/goal into a move_base action. (`#62 `_) At least MIR software version 2.8 does not react properly to move_base_simple/goal messages. This implements a workaround. Closes `#60 `_. * Fix: Adds subscription to "tf_static". (`#58 `_) Some transformations are published on this topic and are needed to obtain a full tf tree. E.g. "base_footprint" to "base_link" * Minor: Removes /particlecloud from the list of published topics. (`#57 `_) * Fix: Add missing dict_filter keyword argument for cmd_vel msgs (`#56 `_) * Remove relative_move_action (MiR => 2.4.0) This action was merged into the generic MirMoveBaseAction in MiR software 2.4.0. * Adjust to changed MirMoveBase action (MiR >= 2.4.0) See `#45 `_. * Adjust cmd_vel topic to TwistStamped (MiR >= 2.7) See `#45 `_. * Contributors: Martin Günther, matthias-mayr 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Fix subscribing twice to same topic (TF etc) There was a flaw in the subscriber logic that caused the mir_bridge to subscribe multiple times to the same topic from the MiR, especially for latched topics. This can be seen by repeated lines in the output: starting to stream messages on topic 'tf' starting to stream messages on topic 'tf' starting to stream messages on topic 'tf' Probably related to `#64 `_. * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Adapt to changes in websocket-client >= 0.49 Ubuntu 16.04 has python-websocket 0.18 Ubuntu 20.04 has python3-websocket 0.53 * Update scripts to Python3 (Noetic) * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ * Add optional prefix parameter to fake_mir_joint_publisher (`#47 `_) * tf_remove_child_frames: Don't publish empty TFs * Add sdc21x0 package, MC/currents topic * Contributors: Martin Günther, Nils Niemann 1.0.4 (2019-05-06) ------------------ * Remove garbage file * Contributors: Martin Günther 1.0.3 (2019-03-04) ------------------ * Make disable_map work with MiR software 2.0 See `#5 `_. * mir_driver: Optionally disable the map topic + TF frame (`#6 `_) This is useful when running one's own SLAM / localization nodes. Fixes `#5 `_. * Split scan_rep117 topic into two separate topics This fixes the problem that the back laser scanner was ignored in the navigation costmap in Gazebo (probably because in Gazebo, both laser scanners have the exact same timestamp). * Contributors: Martin Günther 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ * mir_driver: Remove leading slashes in TF frames * mir_driver: Install launch directory * Contributors: Martin Günther 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_driver/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_driver) find_package(catkin REQUIRED COMPONENTS actionlib actionlib_msgs diagnostic_msgs dynamic_reconfigure geometry_msgs mir_actions mir_msgs move_base_msgs nav_msgs rosgraph_msgs roslaunch rospy rospy_message_converter sdc21x0 sensor_msgs std_msgs tf tf2_msgs visualization_msgs ) catkin_python_setup() ################################### ## catkin specific configuration ## ################################### catkin_package( CATKIN_DEPENDS actionlib actionlib_msgs diagnostic_msgs dynamic_reconfigure geometry_msgs mir_actions mir_msgs move_base_msgs nav_msgs rosgraph_msgs rospy_message_converter sdc21x0 sensor_msgs std_msgs tf tf2_msgs visualization_msgs ) ############# ## Install ## ############# catkin_install_python(PROGRAMS nodes/fake_mir_joint_publisher.py nodes/mir_bridge.py nodes/rep117_filter.py nodes/tf_remove_child_frames.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) # Mark other files for installation (e.g. launch and bag files, etc.) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ############# ## Testing ## ############# roslaunch_add_file_check(launch) ================================================ FILE: mir_driver/launch/mir.launch ================================================ - base_link - front_laser_link - back_laser_link - camera_top_link - camera_top_depth_optical_frame - camera_floor_link - camera_floor_depth_optical_frame - imu_link - odom ================================================ FILE: mir_driver/nodes/fake_mir_joint_publisher.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy from sensor_msgs.msg import JointState def fake_mir_joint_publisher(): rospy.init_node('fake_mir_joint_publisher') prefix = rospy.get_param('~prefix', '') pub = rospy.Publisher('joint_states', JointState, queue_size=10) r = rospy.Rate(50.0) while not rospy.is_shutdown(): js = JointState() js.header.stamp = rospy.Time.now() js.name = [ prefix + 'left_wheel_joint', prefix + 'right_wheel_joint', prefix + 'fl_caster_rotation_joint', prefix + 'fl_caster_wheel_joint', prefix + 'fr_caster_rotation_joint', prefix + 'fr_caster_wheel_joint', prefix + 'bl_caster_rotation_joint', prefix + 'bl_caster_wheel_joint', prefix + 'br_caster_rotation_joint', prefix + 'br_caster_wheel_joint', ] js.position = [0.0 for _ in js.name] js.velocity = [0.0 for _ in js.name] js.effort = [0.0 for _ in js.name] pub.publish(js) r.sleep() if __name__ == '__main__': try: fake_mir_joint_publisher() except rospy.ROSInterruptException: pass ================================================ FILE: mir_driver/nodes/mir_bridge.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy import copy import sys from collections.abc import Iterable from mir_driver import rosbridge from rospy_message_converter import message_converter from actionlib import SimpleActionClient import actionlib_msgs.msg import diagnostic_msgs.msg import dynamic_reconfigure.msg import geometry_msgs.msg import mir_actions.msg import mir_msgs.msg import move_base_msgs.msg import nav_msgs.msg import rosgraph_msgs.msg import sdc21x0.msg import sensor_msgs.msg import std_msgs.msg import tf2_msgs.msg import visualization_msgs.msg from collections import OrderedDict tf_prefix = '' static_transforms = OrderedDict() class TopicConfig(object): def __init__(self, topic, topic_type, latch=False, dict_filter=None): self.topic = topic self.topic_type = topic_type self.latch = latch self.dict_filter = dict_filter # remap mir_actions/MirMoveBaseAction => move_base_msgs/MoveBaseAction def _move_base_goal_dict_filter(msg_dict): filtered_msg_dict = copy.deepcopy(msg_dict) filtered_msg_dict['goal']['move_task'] = mir_actions.msg.MirMoveBaseGoal.GLOBAL_MOVE filtered_msg_dict['goal']['goal_dist_threshold'] = 0.25 filtered_msg_dict['goal']['clear_costmaps'] = True return filtered_msg_dict def _move_base_feedback_dict_filter(msg_dict): # filter out slots from the dict that are not in our message definition # e.g., MiRMoveBaseFeedback has the field "state", which MoveBaseFeedback doesn't filtered_msg_dict = copy.deepcopy(msg_dict) filtered_msg_dict['feedback'] = { key: msg_dict['feedback'][key] for key in move_base_msgs.msg.MoveBaseFeedback.__slots__ } return filtered_msg_dict def _move_base_result_dict_filter(msg_dict): filtered_msg_dict = copy.deepcopy(msg_dict) filtered_msg_dict['result'] = {key: msg_dict['result'][key] for key in move_base_msgs.msg.MoveBaseResult.__slots__} return filtered_msg_dict def _cmd_vel_dict_filter(msg_dict): """ Convert Twist to TwistStamped. Convert a geometry_msgs/Twist message dict (as sent from the ROS side) to a geometry_msgs/TwistStamped message dict (as expected by the MiR on software version >=2.7). """ header = std_msgs.msg.Header(frame_id='', stamp=rospy.Time.now()) filtered_msg_dict = { 'header': message_converter.convert_ros_message_to_dictionary(header), 'twist': copy.deepcopy(msg_dict), } return filtered_msg_dict def _tf_dict_filter(msg_dict): filtered_msg_dict = copy.deepcopy(msg_dict) for transform in filtered_msg_dict['transforms']: transform['child_frame_id'] = tf_prefix + '/' + transform['child_frame_id'].strip('/') return filtered_msg_dict def _tf_static_dict_filter(msg_dict): """ Cache tf_static messages (simulate latching). The tf_static topic needs special handling. Publishers on tf_static are *latched*, which means that the ROS master caches the last message that was sent by each publisher on that topic, and will forward it to new subscribers. However, since the mir_driver node appears to the ROS master as a single node with a single publisher on tf_static, and there are multiple actual publishers hiding behind it on the MiR side, only one of those messages will be cached. Therefore, we need to implement the caching ourselves and make sure that we always publish the full set of transforms as a single message. """ global static_transforms # prepend tf_prefix filtered_msg_dict = _tf_dict_filter(msg_dict) # The following code was copied + modified from https://github.com/tradr-project/static_transform_mux . # Process the incoming transforms, merge them with our cache. for transform in filtered_msg_dict['transforms']: key = transform['child_frame_id'] rospy.loginfo( "[%s] tf_static: updated transform %s->%s.", rospy.get_name(), transform['header']['frame_id'], transform['child_frame_id'], ) static_transforms[key] = transform # Return the cached messages. filtered_msg_dict['transforms'] = static_transforms.values() rospy.loginfo( "[%s] tf_static: sent %i transforms: %s", rospy.get_name(), len(static_transforms), str(static_transforms.keys()), ) return filtered_msg_dict def _prepend_tf_prefix_dict_filter(msg_dict): # filtered_msg_dict = copy.deepcopy(msg_dict) if not isinstance(msg_dict, dict): # can happen during recursion return for key, value in msg_dict.items(): if key == 'header': try: # prepend frame_id frame_id = value['frame_id'].strip('/') if frame_id != 'map': # prepend tf_prefix, then remove leading '/' (e.g., when tf_prefix is empty) value['frame_id'] = (tf_prefix + '/' + frame_id).strip('/') else: value['frame_id'] = frame_id except TypeError: pass # value is not a dict except KeyError: pass # value doesn't have key 'frame_id' elif isinstance(value, dict): _prepend_tf_prefix_dict_filter(value) elif isinstance(value, Iterable): # an Iterable other than dict (e.g., a list) for item in value: _prepend_tf_prefix_dict_filter(item) return msg_dict def _remove_tf_prefix_dict_filter(msg_dict): # filtered_msg_dict = copy.deepcopy(msg_dict) if not isinstance(msg_dict, dict): # can happen during recursion return for key, value in msg_dict.items(): if key == 'header': try: # remove frame_id s = value['frame_id'].strip('/') if s.find(tf_prefix) == 0: value['frame_id'] = (s[len(tf_prefix) :]).strip('/') # strip off tf_prefix, then strip leading '/' except TypeError: pass # value is not a dict except KeyError: pass # value doesn't have key 'frame_id' elif isinstance(value, dict): _remove_tf_prefix_dict_filter(value) elif isinstance(value, Iterable): # an Iterable other than dict (e.g., a list) for item in value: _remove_tf_prefix_dict_filter(item) return msg_dict # topics we want to publish to ROS (and subscribe to from the MiR) PUB_TOPICS = [ # TopicConfig('LightCtrl/bms_data', mir_msgs.msg.BMSData), # TopicConfig('LightCtrl/charging_state', mir_msgs.msg.ChargingState), TopicConfig('LightCtrl/us_list', sensor_msgs.msg.Range), # TopicConfig('MC/battery_currents', mir_msgs.msg.BatteryCurrents), # TopicConfig('MC/battery_voltage', std_msgs.msg.Float64), TopicConfig('MC/currents', sdc21x0.msg.MotorCurrents), # TopicConfig('MC/encoders', sdc21x0.msg.StampedEncoders), TopicConfig('MissionController/CheckArea/visualization_marker', visualization_msgs.msg.Marker), # TopicConfig('MissionController/goal_position_guid', std_msgs.msg.String), # TopicConfig('MissionController/prompt_user', mir_msgs.msg.UserPrompt), TopicConfig('SickPLC/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('SickPLC/parameter_updates', dynamic_reconfigure.msg.Config), # TopicConfig('active_mapping_guid', std_msgs.msg.String), TopicConfig('amcl_pose', geometry_msgs.msg.PoseWithCovarianceStamped), TopicConfig('b_raw_scan', sensor_msgs.msg.LaserScan), TopicConfig('b_scan', sensor_msgs.msg.LaserScan), TopicConfig('camera_floor/background', sensor_msgs.msg.PointCloud2), TopicConfig('camera_floor/depth/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('camera_floor/depth/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('camera_floor/depth/points', sensor_msgs.msg.PointCloud2), TopicConfig('camera_floor/filter/visualization_marker', visualization_msgs.msg.Marker), TopicConfig('camera_floor/floor', sensor_msgs.msg.PointCloud2), TopicConfig('camera_floor/obstacles', sensor_msgs.msg.PointCloud2), TopicConfig('check_area/polygon', geometry_msgs.msg.PolygonStamped), # TopicConfig('check_pose_area/polygon', geometry_msgs.msg.PolygonStamped), # TopicConfig('data_events/area_events', mir_data_msgs.msg.AreaEventEvent), # TopicConfig('data_events/maps', mir_data_msgs.msg.MapEvent), # TopicConfig('data_events/positions', mir_data_msgs.msg.PositionEvent), # TopicConfig('data_events/registers', mir_data_msgs.msg.PLCRegisterEvent), # TopicConfig('data_events/sounds', mir_data_msgs.msg.SoundEvent), TopicConfig('diagnostics', diagnostic_msgs.msg.DiagnosticArray), TopicConfig('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray), TopicConfig('diagnostics_toplevel_state', diagnostic_msgs.msg.DiagnosticStatus), TopicConfig('f_raw_scan', sensor_msgs.msg.LaserScan), TopicConfig('f_scan', sensor_msgs.msg.LaserScan), TopicConfig('imu_data', sensor_msgs.msg.Imu), TopicConfig('laser_back/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('laser_back/driver/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('laser_front/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('laser_front/driver/parameter_updates', dynamic_reconfigure.msg.Config), # TopicConfig('localization_score', std_msgs.msg.Float64), TopicConfig('/map', nav_msgs.msg.OccupancyGrid, latch=True), TopicConfig('/map_metadata', nav_msgs.msg.MapMetaData), # TopicConfig('marker_tracking_node/feedback', mir_marker_tracking.msg.MarkerTrackingActionFeedback), # TopicConfig( # 'marker_tracking_node/laser_line_extract/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription # ), # TopicConfig('marker_tracking_node/laser_line_extract/parameter_updates', dynamic_reconfigure.msg.Config), # TopicConfig('marker_tracking_node/laser_line_extract/visualization_marker', visualization_msgs.msg.Marker), # TopicConfig('marker_tracking_node/result', mir_marker_tracking.msg.MarkerTrackingActionResult), # TopicConfig('marker_tracking_node/status', actionlib_msgs.msg.GoalStatusArray), # TopicConfig('mirEventTrigger/events', mir_msgs.msg.Events), TopicConfig('mir_amcl/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('mir_amcl/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('mir_amcl/selected_points', sensor_msgs.msg.PointCloud2), TopicConfig('mir_log', rosgraph_msgs.msg.Log), # TopicConfig('mir_sound/sound_event', mir_msgs.msg.SoundEvent), TopicConfig('mir_status_msg', std_msgs.msg.String), # TopicConfig('mirspawn/node_events', mirSpawn.msg.LaunchItem), TopicConfig('mirwebapp/grid_map_metadata', mir_msgs.msg.LocalMapStat), TopicConfig('mirwebapp/laser_map_metadata', mir_msgs.msg.LocalMapStat), # TopicConfig('mirwebapp/web_path', mir_msgs.msg.WebPath), # really mir_actions/MirMoveBaseActionFeedback: TopicConfig( 'move_base/feedback', move_base_msgs.msg.MoveBaseActionFeedback, dict_filter=_move_base_feedback_dict_filter ), # really mir_actions/MirMoveBaseActionResult: TopicConfig('move_base/result', move_base_msgs.msg.MoveBaseActionResult, dict_filter=_move_base_result_dict_filter), TopicConfig('move_base/status', actionlib_msgs.msg.GoalStatusArray), # TopicConfig('move_base_node/MIRPlannerROS/cost_cloud', sensor_msgs.msg.PointCloud2), # TopicConfig('move_base_node/MIRPlannerROS/global_plan', nav_msgs.msg.Path), # TopicConfig('move_base_node/MIRPlannerROS/len_to_goal', std_msgs.msg.Float64), TopicConfig('move_base_node/MIRPlannerROS/local_plan', nav_msgs.msg.Path), # TopicConfig('move_base_node/MIRPlannerROS/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), # TopicConfig('move_base_node/MIRPlannerROS/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('move_base_node/MIRPlannerROS/updated_global_plan', mir_msgs.msg.PlanSegments), # TopicConfig('move_base_node/MIRPlannerROS/visualization_marker', visualization_msgs.msg.MarkerArray), TopicConfig('move_base_node/SBPLLatticePlanner/plan', nav_msgs.msg.Path), # TopicConfig( # 'move_base_node/SBPLLatticePlanner/sbpl_lattice_planner_stats', sbpl_lattice_planner.msg.SBPLLatticePlannerStats # ), # TopicConfig('move_base_node/SBPLLatticePlanner/visualization_marker', visualization_msgs.msg.MarkerArray), TopicConfig('move_base_node/current_goal', geometry_msgs.msg.PoseStamped), # TopicConfig('move_base_node/global_costmap/inflated_obstacles', nav_msgs.msg.GridCells), # TopicConfig('move_base_node/global_costmap/obstacles', nav_msgs.msg.GridCells), # TopicConfig('move_base_node/global_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), # TopicConfig('move_base_node/global_costmap/parameter_updates', dynamic_reconfigure.msg.Config), # TopicConfig('move_base_node/global_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), # TopicConfig('move_base_node/global_costmap/unknown_space', nav_msgs.msg.GridCells), # TopicConfig('move_base_node/global_plan', nav_msgs.msg.Path), TopicConfig('move_base_node/local_costmap/inflated_obstacles', nav_msgs.msg.GridCells), TopicConfig('move_base_node/local_costmap/obstacles', nav_msgs.msg.GridCells), # TopicConfig('move_base_node/local_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), # TopicConfig('move_base_node/local_costmap/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('move_base_node/local_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), # TopicConfig('move_base_node/local_costmap/safety_zone', geometry_msgs.msg.PolygonStamped), # TopicConfig('move_base_node/local_costmap/unknown_space', nav_msgs.msg.GridCells), # TopicConfig('move_base_node/mir_escape_recovery/visualization_marker', visualization_msgs.msg.Marker), # TopicConfig('move_base_node/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), # TopicConfig('move_base_node/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('move_base_node/time_to_coll', std_msgs.msg.Float64), TopicConfig('move_base_node/traffic_costmap/inflated_obstacles', nav_msgs.msg.GridCells), TopicConfig('move_base_node/traffic_costmap/obstacles', nav_msgs.msg.GridCells), TopicConfig('move_base_node/traffic_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), TopicConfig('move_base_node/traffic_costmap/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('move_base_node/traffic_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), TopicConfig('move_base_node/traffic_costmap/unknown_space', nav_msgs.msg.GridCells), TopicConfig('move_base_node/visualization_marker', visualization_msgs.msg.Marker), TopicConfig('move_base_simple/visualization_marker', visualization_msgs.msg.Marker), TopicConfig('odom', nav_msgs.msg.Odometry), TopicConfig('odom_enc', nav_msgs.msg.Odometry), # TopicConfig('one_way_map', nav_msgs.msg.OccupancyGrid), # TopicConfig('param_update', std_msgs.msg.String), # TopicConfig('particlevizmarker', visualization_msgs.msg.MarkerArray), # TopicConfig('resource_tracker/needed_resources', mir_msgs.msg.ResourcesState), TopicConfig('robot_mode', mir_msgs.msg.RobotMode), TopicConfig('robot_pose', geometry_msgs.msg.Pose), TopicConfig('robot_state', mir_msgs.msg.RobotState), # TopicConfig('robot_status', mir_msgs.msg.RobotStatus), TopicConfig('/rosout', rosgraph_msgs.msg.Log), TopicConfig('/rosout_agg', rosgraph_msgs.msg.Log), TopicConfig('scan', sensor_msgs.msg.LaserScan), # TopicConfig('scan_filter/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), # TopicConfig('scan_filter/parameter_updates', dynamic_reconfigure.msg.Config), TopicConfig('scan_filter/visualization_marker', visualization_msgs.msg.Marker), # TopicConfig('session_importer_node/info', mirSessionImporter.msg.SessionImportInfo), # TopicConfig('set_mc_PID', std_msgs.msg.Float64MultiArray), TopicConfig('/tf', tf2_msgs.msg.TFMessage, dict_filter=_tf_dict_filter), TopicConfig('/tf_static', tf2_msgs.msg.TFMessage, dict_filter=_tf_static_dict_filter, latch=True), # TopicConfig('traffic_map', nav_msgs.msg.OccupancyGrid), # TopicConfig('wifi_diagnostics', diagnostic_msgs.msg.DiagnosticArray), # TopicConfig('wifi_diagnostics/cur_ap', mir_wifi_msgs.msg.APInfo), # TopicConfig('wifi_diagnostics/roam_events', mir_wifi_msgs.msg.WifiRoamEvent), # TopicConfig('wifi_diagnostics/wifi_ap_interface_stats', mir_wifi_msgs.msg.WifiInterfaceStats), # TopicConfig('wifi_diagnostics/wifi_ap_rssi', mir_wifi_msgs.msg.APRssiStats), # TopicConfig('wifi_diagnostics/wifi_ap_time_stats', mir_wifi_msgs.msg.APTimeStats), # TopicConfig('wifi_watchdog/ping', mir_wifi_msgs.msg.APPingStats), ] # topics we want to subscribe to from ROS (and publish to the MiR) SUB_TOPICS = [ # really geometry_msgs.msg.TwistStamped: TopicConfig('cmd_vel', geometry_msgs.msg.Twist, dict_filter=_cmd_vel_dict_filter), TopicConfig('initialpose', geometry_msgs.msg.PoseWithCovarianceStamped), TopicConfig('light_cmd', std_msgs.msg.String), TopicConfig('mir_cmd', std_msgs.msg.String), TopicConfig('move_base/cancel', actionlib_msgs.msg.GoalID), # really mir_actions/MirMoveBaseActionGoal: TopicConfig('move_base/goal', move_base_msgs.msg.MoveBaseActionGoal, dict_filter=_move_base_goal_dict_filter), ] class PublisherWrapper(rospy.SubscribeListener): def __init__(self, topic_config, robot): self.topic_config = topic_config self.robot = robot self.connected = False # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace. self.pub = rospy.Publisher( name=topic_config.topic, data_class=topic_config.topic_type, subscriber_listener=self, latch=topic_config.latch, queue_size=10, ) rospy.loginfo( "[%s] publishing topic '%s' [%s]", rospy.get_name(), topic_config.topic, topic_config.topic_type._type ) # latched topics must be subscribed immediately if topic_config.latch: self.peer_subscribe("", None, None) def peer_subscribe(self, topic_name, topic_publish, peer_publish): if not self.connected: self.connected = True rospy.loginfo("[%s] starting to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm self.robot.subscribe(topic=absolute_topic, callback=self.callback) def peer_unsubscribe(self, topic_name, num_peers): pass # doesn't work: once ubsubscribed, robot doesn't let us subscribe again # if self.connected and self.pub.get_num_connections() == 0 and not self.topic_config.latch: # self.connected = False # rospy.loginfo("[%s] stopping to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) # absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm # self.robot.unsubscribe(topic=absolute_topic) def callback(self, msg_dict): msg_dict = _prepend_tf_prefix_dict_filter(msg_dict) if self.topic_config.dict_filter is not None: msg_dict = self.topic_config.dict_filter(msg_dict) msg = message_converter.convert_dictionary_to_ros_message(self.topic_config.topic_type._type, msg_dict) self.pub.publish(msg) class SubscriberWrapper(object): def __init__(self, topic_config, robot): self.topic_config = topic_config self.robot = robot # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace. self.sub = rospy.Subscriber( name=topic_config.topic, data_class=topic_config.topic_type, callback=self.callback, queue_size=10 ) rospy.loginfo( "[%s] subscribing to topic '%s' [%s]", rospy.get_name(), topic_config.topic, topic_config.topic_type._type ) def callback(self, msg): msg_dict = message_converter.convert_ros_message_to_dictionary(msg) msg_dict = _remove_tf_prefix_dict_filter(msg_dict) if self.topic_config.dict_filter is not None: msg_dict = self.topic_config.dict_filter(msg_dict) absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm self.robot.publish(absolute_topic, msg_dict) class MiRBridge(object): def __init__(self): try: hostname = rospy.get_param('~hostname') except KeyError: rospy.logfatal('[%s] parameter "hostname" is not set!', rospy.get_name()) sys.exit(-1) port = rospy.get_param('~port', 9090) global tf_prefix tf_prefix = rospy.get_param('~tf_prefix', '').strip('/') rospy.loginfo('[%s] trying to connect to %s:%i...', rospy.get_name(), hostname, port) self.robot = rosbridge.RosbridgeSetup(hostname, port) r = rospy.Rate(10) i = 1 while not self.robot.is_connected(): if rospy.is_shutdown(): sys.exit(0) if self.robot.is_errored(): rospy.logfatal('[%s] connection error to %s:%i, giving up!', rospy.get_name(), hostname, port) sys.exit(-1) if i % 10 == 0: rospy.logwarn('[%s] still waiting for connection to %s:%i...', rospy.get_name(), hostname, port) i += 1 r.sleep() rospy.loginfo('[%s] ... connected.', rospy.get_name()) topics = self.get_topics() published_topics = [topic_name for (topic_name, _, has_publishers, _) in topics if has_publishers] subscribed_topics = [topic_name for (topic_name, _, _, has_subscribers) in topics if has_subscribers] for pub_topic in PUB_TOPICS: PublisherWrapper(pub_topic, self.robot) absolute_topic = '/' + pub_topic.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm if absolute_topic not in published_topics: rospy.logwarn("[%s] topic '%s' is not published by the MiR!", rospy.get_name(), pub_topic.topic) for sub_topic in SUB_TOPICS: SubscriberWrapper(sub_topic, self.robot) absolute_topic = '/' + sub_topic.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm if absolute_topic not in subscribed_topics: rospy.logwarn("[%s] topic '%s' is not yet subscribed to by the MiR!", rospy.get_name(), sub_topic.topic) # At least with software version 2.8 there were issues when forwarding a simple goal to the robot # This workaround converts it into an action. Check https://github.com/DFKI-NI/mir_robot/issues/60 for details. self._move_base_client = SimpleActionClient('move_base', move_base_msgs.msg.MoveBaseAction) rospy.Subscriber("move_base_simple/goal", geometry_msgs.msg.PoseStamped, self._move_base_simple_goal_callback) def get_topics(self): srv_response = self.robot.callService('/rosapi/topics', msg={}) topic_names = sorted(srv_response['topics']) topics = [] for topic_name in topic_names: srv_response = self.robot.callService("/rosapi/topic_type", msg={'topic': topic_name}) topic_type = srv_response['type'] srv_response = self.robot.callService("/rosapi/publishers", msg={'topic': topic_name}) has_publishers = True if len(srv_response['publishers']) > 0 else False srv_response = self.robot.callService("/rosapi/subscribers", msg={'topic': topic_name}) has_subscribers = True if len(srv_response['subscribers']) > 0 else False topics.append([topic_name, topic_type, has_publishers, has_subscribers]) print('Publishers:') for topic_name, topic_type, has_publishers, has_subscribers in topics: if has_publishers: print((' * %s [%s]' % (topic_name, topic_type))) print('\nSubscribers:') for topic_name, topic_type, has_publishers, has_subscribers in topics: if has_subscribers: print((' * %s [%s]' % (topic_name, topic_type))) return topics def _move_base_simple_goal_callback(self, msg): if not self._move_base_client.wait_for_server(rospy.Duration(2)): rospy.logwarn("Could not connect to 'move_base' server after two seconds. Dropping goal.") rospy.logwarn("Did you activate 'planner' in the MIR web interface?") return goal = move_base_msgs.msg.MoveBaseGoal() goal.target_pose.header = copy.deepcopy(msg.header) goal.target_pose.pose = copy.deepcopy(msg.pose) self._move_base_client.send_goal(goal) def main(): rospy.init_node('mir_bridge') MiRBridge() rospy.spin() if __name__ == '__main__': try: main() except rospy.ROSInterruptException: pass ================================================ FILE: mir_driver/nodes/rep117_filter.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy from sensor_msgs.msg import LaserScan pub = None def callback(msg): """ Convert laser scans to REP 117 standard. See http://www.ros.org/reps/rep-0117.html """ ranges_out = [] for dist in msg.ranges: if dist < msg.range_min: # assume "reading too close to measure", # although it could also be "reading invalid" (nan) ranges_out.append(float("-inf")) elif dist > msg.range_max: # assume "reading of no return (outside sensor range)", # although it could also be "reading invalid" (nan) ranges_out.append(float("inf")) else: ranges_out.append(dist) msg.ranges = ranges_out pub.publish(msg) def main(): global pub rospy.init_node('rep117_filter') pub = rospy.Publisher('scan_filtered', LaserScan, queue_size=10) rospy.Subscriber('scan', LaserScan, callback) rospy.spin() if __name__ == '__main__': try: main() except rospy.ROSInterruptException: pass ================================================ FILE: mir_driver/nodes/tf_remove_child_frames.py ================================================ #!/usr/bin/env python3 # -*- coding: utf-8 -*- # Copyright 2016 The Cartographer Authors # Copyright 2018 DFKI GmbH # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 # # Unless required by applicable law or agreed to in writing, software # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. import rospy from tf.msg import tfMessage def main(): rospy.init_node('tf_remove_child_frames') remove_frames = rospy.get_param('~remove_frames', []) # filter tf_in topic tf_pub = rospy.Publisher('tf_out', tfMessage, queue_size=1) def tf_cb(msg): msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames] if len(msg.transforms) > 0: tf_pub.publish(msg) rospy.Subscriber('tf_in', tfMessage, tf_cb) # filter tf_static_in topic tf_static_pub = rospy.Publisher('tf_static_out', tfMessage, queue_size=1, latch=True) def tf_static_cb(msg): msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames] if len(msg.transforms) > 0: tf_static_pub.publish(msg) rospy.Subscriber('tf_static_in', tfMessage, tf_static_cb) rospy.spin() if __name__ == '__main__': main() ================================================ FILE: mir_driver/package.xml ================================================ mir_driver 1.1.8 A reverse ROS bridge for the MiR robot Martin Günther Martin Günther BSD-3-Clause Apache-2.0 https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin roslaunch actionlib actionlib_msgs diagnostic_msgs dynamic_reconfigure geometry_msgs mir_actions mir_msgs move_base_msgs nav_msgs python3-websocket rosgraph_msgs rospy rospy_message_converter sdc21x0 sensor_msgs std_msgs tf2_msgs tf visualization_msgs mir_description robot_state_publisher ================================================ FILE: mir_driver/setup.py ================================================ # ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup # fetch values from package.xml setup_args = generate_distutils_setup(packages=['mir_driver'], package_dir={'': 'src'}) setup(**setup_args) ================================================ FILE: mir_driver/src/mir_driver/__init__.py ================================================ ================================================ FILE: mir_driver/src/mir_driver/rosbridge.py ================================================ # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import websocket import threading import json import traceback import time import string import random class RosbridgeSetup: def __init__(self, host, port): self.callbacks = {} self.service_callbacks = {} self.resp = None self.connection = RosbridgeWSConnection(host, port) self.connection.registerCallback(self.onMessageReceived) def publish(self, topic, obj): pub = {"op": "publish", "topic": topic, "msg": obj} self.send(pub) def subscribe(self, topic, callback, throttle_rate=-1): if self.addCallback(topic, callback): sub = {"op": "subscribe", "topic": topic} if throttle_rate > 0: sub['throttle_rate'] = throttle_rate self.send(sub) def unhook(self, callback): keys_for_deletion = [] for key, values in self.callbacks.items(): for value in values: if callback == value: print("Found!") values.remove(value) if len(values) == 0: keys_for_deletion.append(key) for key in keys_for_deletion: self.unsubscribe(key) self.callbacks.pop(key) def unsubscribe(self, topic): unsub = {"op": "unsubscribe", "topic": topic} self.send(unsub) def callService(self, serviceName, callback=None, msg=None): id = self.generate_id() call = {"op": "call_service", "id": id, "service": serviceName} if msg is not None: call['args'] = msg if callback is None: self.resp = None def internalCB(msg): self.resp = msg return None self.addServiceCallback(id, internalCB) self.send(call) while self.resp is None: time.sleep(0.01) return self.resp self.addServiceCallback(id, callback) self.send(call) return None def send(self, obj): try: self.connection.sendString(json.dumps(obj)) except Exception: traceback.print_exc() raise def generate_id(self, chars=16): return ''.join(random.SystemRandom().choice(string.ascii_letters + string.digits) for _ in range(chars)) def addServiceCallback(self, id, callback): self.service_callbacks[id] = callback def addCallback(self, topic, callback): if topic in self.callbacks: self.callbacks[topic].append(callback) return False self.callbacks[topic] = [callback] return True def is_connected(self): return self.connection.connected def is_errored(self): return self.connection.errored def onMessageReceived(self, message): try: # Load the string into a JSON object obj = json.loads(message) # print "Received: ", obj if 'op' in obj: option = obj['op'] if option == "publish": # A message from a topic we have subscribed to.. topic = obj["topic"] msg = obj["msg"] if topic in self.callbacks: for callback in self.callbacks[topic]: try: callback(msg) except Exception: print("exception on callback", callback, "from", topic) traceback.print_exc() raise elif option == "service_response": if "id" in obj: id = obj["id"] values = obj["values"] if id in self.service_callbacks: try: # print 'id:', id, 'func:', self.service_callbacks[id] self.service_callbacks[id](values) except Exception: print("exception on callback ID:", id) traceback.print_exc() raise else: print("Missing ID!") else: print("Recieved unknown option - it was: ", option) else: print("No OP key!") except Exception: print("exception in onMessageReceived") print("message", message) traceback.print_exc() raise class RosbridgeWSConnection: def __init__(self, host, port): self.ws = websocket.WebSocketApp( ("ws://%s:%d/" % (host, port)), on_message=self.on_message, on_error=self.on_error, on_close=self.on_close ) self.ws.on_open = self.on_open self.run_thread = threading.Thread(target=self.run) self.run_thread.start() self.connected = False self.errored = False self.callbacks = [] def on_open(self): print("### ROS bridge connected ###") self.connected = True def sendString(self, message): if not self.connected: print("Error: not connected, could not send message") # TODO: throw exception else: self.ws.send(message) def on_error(self, error): self.errored = True print("Error: %s" % error) def on_close(self): self.connected = False print("### ROS bridge closed ###") def run(self, *args): self.ws.run_forever() def on_message(self, message): # Call the handlers for callback in self.callbacks: callback(message) def registerCallback(self, callback): self.callbacks.append(callback) ================================================ FILE: mir_dwb_critics/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_dwb_critics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Fix typo in license * mir_dwb_critics: Fill in description * Re-format C++ files using clang-format * mir_dwb_critics: Fix URLs in package.xml * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Drop old C++ compiler flags * Add license headers * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Reformat python code using black * Contributors: Martin Günther 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Fix bug in path_dist_pruned With some paths, the previous code crashed with "terminate called after throwing an instance of 'std::bad_alloc'". * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Update scripts to Python3 (Noetic) * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Add missing matplotlib dependency * Fix some catkin_lint warnings * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ * mir_dwb_critics: Add plot_dwb_scores.py * mir_dwb_critics: Improve print_dwb_scores output * added PathDistPrunedCritic for dwb (`#42 `_) which works exactly like the original PathDistCritic, except that it searches for a local minimum in the distance from the global path to the robots current position. It then prunes the global_path from the start up to this point, therefore approximately cutting of a segment of the path that the robot already followed. * Contributors: Martin Günther, Nils Niemann 1.0.4 (2019-05-06) ------------------ 1.0.3 (2019-03-04) ------------------ * PathProgressCritic: Add heading score * Add package: mir_dwb_critics * Contributors: Martin Günther 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ ================================================ FILE: mir_dwb_critics/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_dwb_critics) set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Werror") find_package(catkin REQUIRED COMPONENTS 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 ) catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} 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 ) include_directories( include ${catkin_INCLUDE_DIRS} ) add_library(${PROJECT_NAME} src/path_angle.cpp src/path_progress.cpp src/path_dist_pruned.cpp ) add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) install(PROGRAMS nodes/print_dwb_scores.py nodes/plot_dwb_scores.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} ) install(FILES default_critics.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ================================================ FILE: mir_dwb_critics/default_critics.xml ================================================ Scores trajectories based on how far along the global path they end up. Scores trajectories based on the difference between the path's current angle and the trajectory's angle Scores trajectories based on the distance to the global path, only taking the parts into account that are still ahead of the robot. ================================================ FILE: mir_dwb_critics/include/mir_dwb_critics/path_angle.h ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef MIR_DWB_CRITICS_PATH_ANGLE_H_ #define MIR_DWB_CRITICS_PATH_ANGLE_H_ #include #include namespace mir_dwb_critics { /** * @class PathAngleCritic * @brief Scores trajectories based on the difference between the path's current angle and the trajectory's angle * * This trajectory critic helps to ensure that the robot is roughly aligned with the path (i.e., * if the path specifies a forward motion, the robot should point forward along the path and vice versa). * This critic is not a replacement for the PathAlignCritic: The PathAlignCritic tries to point the robot * towards a point on the path that is in front of the trajectory's end point, so it helps guiding the * robot back towards the path. The PathAngleCritic on the other hand uses the path point that is closest * to the robot's current position (not the trajectory end point, or even a point in front of that) as a * reference, so it always lags behind. Also, it tries to keep the robot parallel to the path, not towards * it. For these reasons, the error is squared, so that the PathAngleCritic really only affects the final * score if the error is large. The PathAlignCritic doesn't take the path orientation into account though, * so that's why the PathAngleCritic is a useful addition. */ class PathAngleCritic : public dwb_local_planner::TrajectoryCritic { public: virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; protected: double desired_angle_; }; } // namespace mir_dwb_critics #endif // MIR_DWB_CRITICS_PATH_ANGLE_H_ ================================================ FILE: mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_ #define MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_ #include #include namespace mir_dwb_critics { /** * @class PathDistPrunedCritic * @brief Scores trajectories based on how far from the global path they end up, * where the global path is pruned to only include waypoints ahead of the * robot. */ class PathDistPrunedCritic : public dwb_critics::PathDistCritic { public: virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; }; } // namespace mir_dwb_critics #endif // MIR_DWB_CRITICS_DISTANCE_PRUNED_H_ ================================================ FILE: mir_dwb_critics/include/mir_dwb_critics/path_progress.h ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef MIR_DWB_CRITICS_PATH_PROGRESS_H_ #define MIR_DWB_CRITICS_PATH_PROGRESS_H_ #include #include namespace mir_dwb_critics { /** * @class PathProgressCritic * @brief Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal. * * This trajectory critic helps ensure progress along the global path. It * calculates an intermediate goal that is as far as possible along the global * path as long as the path continues to move in one direction (+/- * angle_threshold). */ class PathProgressCritic : public dwb_critics::MapGridCritic { public: bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; void onInit() override; void reset() override; double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; protected: bool getGoalPose(const geometry_msgs::Pose2D& robot_pose, const nav_2d_msgs::Path2D& global_plan, unsigned int& x, unsigned int& y, double& desired_angle); unsigned int getGoalIndex(const std::vector& plan, unsigned int start_index, unsigned int last_valid_index) const; double xy_local_goal_tolerance_; double angle_threshold_; double heading_scale_; std::vector reached_intermediate_goals_; double desired_angle_; }; } // namespace mir_dwb_critics #endif // MIR_DWB_CRITICS_PATH_PROGRESS_H_ ================================================ FILE: mir_dwb_critics/nodes/plot_dwb_scores.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import os import tkinter import matplotlib.pyplot as plt import numpy as np import rospy from dwb_msgs.msg import LocalPlanEvaluation fig = None rects = None max_score = 0.0 def eval_cb(msg): global fig, rects, max_score labels = [s.name for s in msg.twists[msg.best_index].scores] scaled_scores = [s.scale * s.raw_score for s in msg.twists[msg.best_index].scores] # reverse labels + scaled_scores to show the critics in the correct order top to bottom labels.reverse() scaled_scores.reverse() if not fig: # init y = np.arange(len(labels)) # the label locations height = 0.35 # the height of the bars fig, ax = plt.subplots() rects = ax.barh(y - height / 2, scaled_scores, height, label='scaled score') ax.set_ylabel('DWB Critics') ax.set_title('Scaled scores') ax.set_yticks(y) ax.set_yticklabels(labels) fig.tight_layout() fig.canvas.set_window_title('DWB Scores') # update axis limit if max_score < max(scaled_scores): max_score = max(scaled_scores) plt.xlim(0.0, max_score) for rect, h in zip(rects, scaled_scores): rect.set_width(h) try: fig.canvas.draw() fig.canvas.flush_events() except tkinter.TclError: rospy.loginfo('Window was closed, exiting.') os._exit(0) def main(): rospy.init_node('plot_dwb_scores') rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb) rospy.loginfo('plot_dwb_scores ready.') plt.ion() rospy.spin() if __name__ == '__main__': main() ================================================ FILE: mir_dwb_critics/nodes/print_dwb_scores.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy from dwb_msgs.msg import LocalPlanEvaluation def eval_cb(msg): print('\n\n=========================================================\n\n') for heading, i in zip(['best trajectory', 'worst trajectory'], [msg.best_index, msg.worst_index]): print('### {}\n'.format(heading)) print('Name | Raw | Scale | Scaled Score') print('---------------------|-----------|---------|-------------') for s in msg.twists[i].scores: print('{:20} | {:9.4f} | {:7.4f} | {:12.4f}'.format(s.name, s.raw_score, s.scale, s.raw_score * s.scale)) print('---------------------------------------- total: {:9.4f}'.format(msg.twists[i].total)) print() def main(): rospy.init_node('print_dwb_scores', anonymous=True) rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb) rospy.loginfo('print_dwb_scores ready.') rospy.spin() if __name__ == '__main__': main() ================================================ FILE: mir_dwb_critics/package.xml ================================================ mir_dwb_critics 1.1.8 Trajectory critics for the dwb_local_planner that work well together with the SBPL global planner on the MiR robot Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin 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 python3-matplotlib ================================================ FILE: mir_dwb_critics/src/path_angle.cpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include #include #include namespace mir_dwb_critics { bool PathAngleCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) { const nav_core2::Costmap& costmap = *costmap_; const nav_grid::NavGridInfo& info = costmap.getInfo(); nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution); if (global_plan.poses.empty()) { ROS_ERROR_NAMED("PathAngleCritic", "The global plan was empty."); return false; } // find the angle of the plan at the pose on the plan closest to the robot double distance_min = std::numeric_limits::infinity(); bool started_path = false; for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); i++) { double g_x = adjusted_global_plan.poses[i].x; double g_y = adjusted_global_plan.poses[i].y; unsigned int map_x, map_y; if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION) { double distance = nav_2d_utils::poseDistance(adjusted_global_plan.poses[i], pose); if (distance_min > distance) { // still getting closer desired_angle_ = adjusted_global_plan.poses[i].theta; distance_min = distance; started_path = true; } else { // plan is going away from the robot again break; } } else if (started_path) { // Off the costmap after being on the costmap. break; } // else, we have not yet found a point on the costmap, so we just continue } if (!started_path) { ROS_ERROR_NAMED("PathAngleCritic", "None of the points of the global plan were in the local costmap."); return false; } return true; } double PathAngleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) { double diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI)); return diff * diff; } } // namespace mir_dwb_critics PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathAngleCritic, dwb_local_planner::TrajectoryCritic) ================================================ FILE: mir_dwb_critics/src/path_dist_pruned.cpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include "mir_dwb_critics/path_dist_pruned.h" namespace mir_dwb_critics { bool PathDistPrunedCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) { const nav_core2::Costmap& costmap = *costmap_; const nav_grid::NavGridInfo& info = costmap.getInfo(); auto plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; // --- stolen from PathProgressCritic::getGoalPose --- // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map unsigned int start_index = 0; double distance_to_start = std::numeric_limits::infinity(); bool started_path = false; for (unsigned int i = 0; i < plan.size(); i++) { double g_x = plan[i].x; double g_y = plan[i].y; unsigned int map_x, map_y; if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { // Still on the costmap. Continue. double distance = nav_2d_utils::poseDistance(plan[i], pose); if (distance_to_start > distance) { start_index = i; distance_to_start = distance; started_path = true; } else { // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's // even closer to the robot, but then we would skip over parts of the plan. break; } } else if (started_path) { // Off the costmap after being on the costmap. break; } // else, we have not yet found a point on the costmap, so we just continue } if (!started_path) { ROS_ERROR_NAMED("PathDistPrunedCritic", "None of the points of the global plan were in the local costmap."); return false; } // --------------------------------------------------- // remove the first part of the path, everything before start_index, to // disregard that part in the PathDistCritic implementation. nav_2d_msgs::Path2D global_plan_pruned; global_plan_pruned.header = global_plan.header; global_plan_pruned.poses = std::vector(plan.begin() + start_index, plan.end()); return dwb_critics::PathDistCritic::prepare(pose, vel, goal, global_plan_pruned); } } // namespace mir_dwb_critics PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathDistPrunedCritic, dwb_local_planner::TrajectoryCritic) ================================================ FILE: mir_dwb_critics/src/path_progress.cpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2019, DFKI GmbH * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include #include #include #include namespace mir_dwb_critics { bool PathProgressCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) { dwb_critics::MapGridCritic::reset(); unsigned int local_goal_x, local_goal_y; if (!getGoalPose(pose, global_plan, local_goal_x, local_goal_y, desired_angle_)) { return false; } // Enqueue just the last pose cell_values_.setValue(local_goal_x, local_goal_y, 0.0); queue_->enqueueCell(local_goal_x, local_goal_y); propogateManhattanDistances(); return true; } void PathProgressCritic::onInit() { dwb_critics::MapGridCritic::onInit(); critic_nh_.param("xy_local_goal_tolerance", xy_local_goal_tolerance_, 0.20); critic_nh_.param("angle_threshold", angle_threshold_, M_PI_4); critic_nh_.param("heading_scale", heading_scale_, 1.0); // divide heading scale by position scale because the sum will be multiplied by scale again heading_scale_ /= getScale(); } void PathProgressCritic::reset() { reached_intermediate_goals_.clear(); } double PathProgressCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) { double position_score = MapGridCritic::scoreTrajectory(traj); double heading_diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI)); double heading_score = heading_diff * heading_diff; return position_score + heading_scale_ * heading_score; } bool PathProgressCritic::getGoalPose(const geometry_msgs::Pose2D& robot_pose, const nav_2d_msgs::Path2D& global_plan, unsigned int& x, unsigned int& y, double& desired_angle) { const nav_core2::Costmap& costmap = *costmap_; const nav_grid::NavGridInfo& info = costmap.getInfo(); if (global_plan.poses.empty()) { ROS_ERROR_NAMED("PathProgressCritic", "The global plan was empty."); return false; } std::vector plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map unsigned int start_index = 0; double distance_to_start = std::numeric_limits::infinity(); bool started_path = false; for (unsigned int i = 0; i < plan.size(); i++) { double g_x = plan[i].x; double g_y = plan[i].y; unsigned int map_x, map_y; if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { // Still on the costmap. Continue. double distance = nav_2d_utils::poseDistance(plan[i], robot_pose); if (distance_to_start > distance) { start_index = i; distance_to_start = distance; started_path = true; } else { // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's // even closer to the robot, but then we would skip over parts of the plan. break; } } else if (started_path) { // Off the costmap after being on the costmap. break; } // else, we have not yet found a point on the costmap, so we just continue } if (!started_path) { ROS_ERROR_NAMED("PathProgressCritic", "None of the points of the global plan were in the local costmap."); return false; } // find the "last valid pose", i.e. the last pose on the plan after the start pose that is still on the local map unsigned int last_valid_index = start_index; for (unsigned int i = start_index + 1; i < plan.size(); i++) { double g_x = plan[i].x; double g_y = plan[i].y; unsigned int map_x, map_y; if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { // Still on the costmap. Continue. last_valid_index = i; } else { // Off the costmap after being on the costmap. break; } } // find the "goal pose" by walking along the plan as long as each step leads far enough away from the starting point, // i.e. is within angle_threshold_ of the starting direction. unsigned int goal_index = start_index; while (goal_index < last_valid_index) { goal_index = getGoalIndex(plan, start_index, last_valid_index); // check if goal already reached bool goal_already_reached = false; for (auto& reached_intermediate_goal : reached_intermediate_goals_) { double distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[goal_index]); if (distance < xy_local_goal_tolerance_) { goal_already_reached = true; // choose a new start_index by walking along the plan until we're outside xy_local_goal_tolerance_ and try again // (start_index is now > goal_index) for (start_index = goal_index; start_index <= last_valid_index; ++start_index) { distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[start_index]); if (distance >= xy_local_goal_tolerance_) { break; } } break; } } if (!goal_already_reached) { // new goal not in reached_intermediate_goals_ double distance = nav_2d_utils::poseDistance(plan[goal_index], robot_pose); if (distance < xy_local_goal_tolerance_) { // the robot has currently reached the goal reached_intermediate_goals_.push_back(plan[goal_index]); ROS_DEBUG_NAMED("PathProgressCritic", "Number of reached_intermediate goals: %zu", reached_intermediate_goals_.size()); } else { // we've found a new goal! break; } } } if (start_index > goal_index) start_index = goal_index; ROS_ASSERT(goal_index <= last_valid_index); // save goal in x, y worldToGridBounded(info, plan[goal_index].x, plan[goal_index].y, x, y); desired_angle = plan[start_index].theta; return true; } unsigned int PathProgressCritic::getGoalIndex(const std::vector& plan, unsigned int start_index, unsigned int last_valid_index) const { if (start_index >= last_valid_index) return last_valid_index; unsigned int goal_index = start_index; const double start_direction_x = plan[start_index + 1].x - plan[start_index].x; const double start_direction_y = plan[start_index + 1].y - plan[start_index].y; if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) { // make sure that atan2 is defined double start_angle = atan2(start_direction_y, start_direction_x); for (unsigned int i = start_index + 1; i <= last_valid_index; ++i) { const double current_direction_x = plan[i].x - plan[i - 1].x; const double current_direction_y = plan[i].y - plan[i - 1].y; if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) { double current_angle = atan2(current_direction_y, current_direction_x); // goal pose is found if plan doesn't point far enough away from the starting point if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) > angle_threshold_) break; goal_index = i; } } } return goal_index; } } // namespace mir_dwb_critics PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathProgressCritic, dwb_local_planner::TrajectoryCritic) ================================================ FILE: mir_gazebo/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_gazebo ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ * Add arg mir_type to launch files and urdfs * Rename mir_100 -> mir This is in preparation of mir_250 support. * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ * Remove outdated comment * Contributors: Martin Günther 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Rename tf frame and topic 'odom_comb' -> 'odom' This is how they are called on the real MiR since MiR software 2.0. * Contributors: Martin Günther 1.1.2 (2021-05-12) ------------------ * Fix laser scan frame_id with gazebo_plugins 2.9.2 * Contributors: Martin Günther 1.1.1 (2021-02-11) ------------------ * mir_gazebo: Add model_name arg * Move joint_state_publisher to mir_gazebo_common.launch * Add optional namespace to launch files * Add prepend_prefix_to_laser_frame to URDF and launch files Fixes `#65 `_. * Add tf_prefix to URDF and launch files * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ 1.0.4 (2019-05-06) ------------------ * Fix gazebo launch file Before this commit, the mobile base plugin couldn't initialize, because subst_value didn't work. * Contributors: Martin Günther 1.0.3 (2019-03-04) ------------------ * Add hector_mapping * fake_localization.launch: Add frame id args * Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs Add prefix argument to configs * adds $(arg prefix) to a lot of configs This is an important step to be able to re-parameterize move base, the diffdrive controller, ekf, amcl and the costmaps for adding a tf prefix to the robots links * Fix translation error in odom_comb (`#12 `_) 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). This PR changes the ekf configuration to not use any position information from the odometry, but to integrate the velocities, which fixes this problem. * Split scan_rep117 topic into two separate topics This fixes the problem that the back laser scanner was ignored in the navigation costmap in Gazebo (probably because in Gazebo, both laser scanners have the exact same timestamp). * Contributors: Martin Günther, Nils Niemann 1.0.2 (2018-07-30) ------------------ * mir_gazebo: Install config directory * Contributors: Martin Günther 1.0.1 (2018-07-17) ------------------ * gazebo: Replace robot_pose_ekf with robot_localization robot_pose_ekf is deprecated, and has been removed from the navigation stack starting in melodic. * gazebo: Adjust ekf.yaml * gazebo: Copy robot_localization/ekf_template.yaml ... for modification. * Contributors: Martin Günther 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_gazebo/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_gazebo) find_package(catkin REQUIRED COMPONENTS roslaunch ) ################################### ## catkin specific configuration ## ################################### catkin_package() ############# ## Install ## ############# # Mark other files for installation (e.g. launch and bag files, etc.) install(DIRECTORY config launch maps sdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ############# ## Testing ## ############# roslaunch_add_file_check(launch) ================================================ FILE: mir_gazebo/config/ekf.yaml ================================================ # The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin # computation until it receives at least one message from one of the inputs. It will then run continuously at the # frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. frequency: 40 # The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict # cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the # filter will generate new output. Defaults to 1 / frequency if not specified. sensor_timeout: 0.1 # ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is # set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar # environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected # by, for example, an IMU. Defaults to false if unspecified. two_d_mode: true # Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for # future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if # unspecified. transform_time_offset: 0.0 # Use this parameter to specify how long the tf listener should wait for a transform to become available. # Defaults to 0.0 if unspecified. transform_timeout: 0.0 # If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is # unhappy with any settings or data. print_diagnostics: true # Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by # debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious # effects on the performance of the node. Defaults to false if unspecified. debug: false # Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. debug_out_file: /path/to/debug/file.txt # Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. publish_tf: true # Whether to publish the acceleration state. Defaults to false if unspecified. publish_acceleration: false # REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and # earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. # The robot's position in the odom frame will drift over time, but is accurate in the short term and should be # continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom # frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your # robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based # localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. # ekf_localization_node and ukf_localization_node are not concerned with the earth frame. # Here is how to use the following settings: # 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. # 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of # odom_frame. # 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set # "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. # 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates # from landmark observations) then: # 3a. Set your "world_frame" to your map_frame value # 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state # estimation node from robot_localization! However, that instance should *not* fuse the global data. map_frame: map # Defaults to "map" if unspecified odom_frame: $(arg tf_prefix)odom # Defaults to "odom" if unspecified base_link_frame: $(arg tf_prefix)base_footprint # Defaults to "base_link" if unspecified world_frame: $(arg tf_prefix)odom # Defaults to the value of odom_frame if unspecified # The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, # geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, # sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, # odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no # default values, and must be specified. odom0: odom # Each sensor reading updates some or all of the filter's state. These options give you greater control over which # values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only # want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the # values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types # do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message # has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false # if unspecified, effectively making this parameter required for each sensor. # see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html odom0_config: [false, false, false, # x y z false, false, false, # roll pitch yaw true, true, false, # vx vy vz false, false, true, # vroll vpitch vyaw false, false, false] # ax ay az # If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase # the size of the subscription queue so that more measurements are fused. odom0_queue_size: 10 # [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result # of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's # algorithm. odom0_nodelay: false # [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- # report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they # arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also # measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't # always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose # data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then # integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true # for twist measurements has no effect. odom0_differential: false # [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" # for all future measurements. While you can achieve the same effect with the differential paremeter, the key # difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before # integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. odom0_relative: false # [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to # control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to # numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not # required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. # For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying # the thresholds. #odom0_pose_rejection_threshold: 5 #odom0_twist_rejection_threshold: 1 # Further input parameter examples # see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html imu0: imu_data imu0_config: [false, false, false, # x y z false, false, true, # roll pitch yaw false, false, false, # vx vy vz false, false, true, # vroll vpitch vyaw true, false, false] # ax ay az imu0_nodelay: false imu0_differential: false imu0_relative: true imu0_queue_size: 10 #imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names #imu0_twist_rejection_threshold: 0.8 # #imu0_linear_acceleration_rejection_threshold: 0.8 # # [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set # this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. imu0_remove_gravitational_acceleration: false # [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no # acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During # correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be # problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When # this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially # noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance # for the velocity variable in question, or decrease the variance of the variable in question in the measurement # itself. In addition, users can also take advantage of the control command being issued to the robot at the time we # make the prediction. If control is used, it will get converted into an acceleration term, which will be used during # predicition. Note that if an acceleration measurement for the variable in question is available from one of the # inputs, the control term will be ignored. # Whether or not we use the control input during predicition. Defaults to false. use_control: false # Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to # false. stamped_control: false # The last issued control command will be used in prediction for this period. Defaults to 0.2. control_timeout: 0.2 # Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. control_config: [true, false, false, false, false, true] # Places limits on how large the acceleration term will be. Should match your robot's kinematics. acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] # Acceleration and deceleration limits are not always the same for robots. deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] # If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these # gains acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] # If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these # gains deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] # [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is # exposed as a configuration parameter. This matrix represents the noise we add to the total error after each # prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. # However, if users find that a given variable is slow to converge, one approach is to increase the # process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error # to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are # ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if # unspecified. process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] # [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal # value (variance) to a large value will result in rapid convergence for initial measurements of the variable in # question. Users should take care not to use large values for variables that will not be measured directly. The values # are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below #if unspecified. initial_estimate_covariance: [100.0,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 100.0,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] ================================================ FILE: mir_gazebo/launch/fake_localization.launch ================================================ ================================================ FILE: mir_gazebo/launch/includes/ekf.launch.xml ================================================ ================================================ FILE: mir_gazebo/launch/includes/spawn_maze.launch.xml ================================================ ================================================ FILE: mir_gazebo/launch/mir_empty_world.launch ================================================ ================================================ FILE: mir_gazebo/launch/mir_gazebo_common.launch ================================================ [mir/joint_states] ================================================ FILE: mir_gazebo/launch/mir_maze_world.launch ================================================ ================================================ FILE: mir_gazebo/maps/maze.yaml ================================================ image: maze.png resolution: 0.05 origin: [0.0, 0.0, 0.0] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ================================================ FILE: mir_gazebo/maps/maze_virtual_walls.yaml ================================================ image: maze_virtual_walls.png resolution: 0.05 origin: [0.0, 0.0, 0.0] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ================================================ FILE: mir_gazebo/package.xml ================================================ mir_gazebo 1.1.8 Simulation specific launch and configuration files for the MiR robot. Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin roslaunch controller_manager fake_localization gazebo_ros joint_state_publisher mir_description mir_driver robot_localization robot_state_publisher rostopic rqt_robot_steering topic_tools ================================================ FILE: mir_gazebo/sdf/maze/model.config ================================================ maze 1.0 model.sdf Martin Günther martin.guenther@dfki.de ================================================ FILE: mir_gazebo/sdf/maze/model.sdf ================================================ -0.078283 0.098984 0 0 -0 0 20 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 20 0.15 2.5 1 1 1 1 0.030536 9.925 0 0 -0 0 20 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 20 0.15 2.5 1 1 1 1 9.95554 0 0 0 0 -1.5708 20 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 20 0.15 2.5 1 1 1 1 0.030536 -9.925 0 0 -0 3.14159 1.5 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 1.5 0.15 2.5 1 1 1 1 5.35089 3.21906 0 0 -0 3.14159 5.25 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 5.25 0.15 2.5 1 1 1 1 4.67589 5.76906 0 0 -0 1.5708 5.5 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 5.5 0.15 2.5 1 1 1 1 7.10914 4.73454 0 0 0 -1.5708 3 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 3 0.15 2.5 1 1 1 1 8.53414 2.05954 0 0 -0 0 20 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 20 0.15 2.5 1 1 1 1 -9.89446 0 0 0 -0 1.5708 5.5 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 5.5 0.15 2.5 1 1 1 1 -4.35914 -2.82889 0 0 0 -1.5708 5.75 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 5.75 0.15 2.5 1 1 1 1 -7.15914 -5.50389 0 0 -0 3.14159 16 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 16 0.15 2.5 1 1 1 1 -1.89911 1.86906 0 0 -0 0 1.5 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 1.5 0.15 2.5 1 1 1 1 6.02589 2.54406 0 0 -0 1.5708 0.15 0.15 2.5 0 0 1.25 0 -0 0 0 0 1.25 0 -0 0 0.15 0.15 2.5 1 1 1 1 6.02589 3.21906 0 0 -0 0 1 ================================================ FILE: mir_msgs/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Build new msgs (`#117 `_) Need to build new msg files. The files were added in a previous commit, but not added here for build and installation. * Update MirMoveBase action to 2.10.3.1 * Update BMSData.msg to MiR software 2.13.2 This is an "unsafe" change (it breaks compatibility with MiR versions <= 2.13.2), but since BMSData is not published by the mir_driver currently, it should be ok. * Add new messages added in MiR software 2.13.4.1 This does not break compatibility with earlier versions (like 2.8.3.1), because these messages did not exist before. Actually, these messages were added in 2.10.3.1 (all other messages) and 2.13.0.4 (ServiceResponseHeader.msg). * Update Brake, Gripper + Height State msg to 2.13.4.1 These are "unsafe" message changes (fields have been removed), but it should be ok because these are only used in HookExtendedStatus, and that message isn't forwarded by the mir_driver. * Partially update messages to MiR software 2.13.4.1 This only contains the "safe" changes, where fields were added. Also, it doesn't include the move of some messages to mir_hook_shared_interface, but keeps them here. * Don't set cmake_policy CMP0048 * Contributors: Martin Günther, moooeeeep 1.1.6 (2022-06-02) ------------------ * Rename mir_100 -> mir This is in preparation of mir_250 support. * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ * mir_msgs: Build all messages (`#98 `_) * Contributors: Martin Günther 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Update BMSData msg to MiR software 2.8.3.1 * Remove MirStatus This message was removed in MiR software 2.0 (Renamed to RobotStatus). * Update mir_msgs to 2.8.2.2 * Contributors: Felix, Martin Günther 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Fix some catkin_lint warnings * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ 1.0.4 (2019-05-06) ------------------ * Update mir_msgs and mir_actions to MiR 2.3.1 The following changes were made to the actual mir_msgs: * rename mirMsgs -> mir_msgs * rename proximity -> Proximity * rename serial -> Serial * keep MirStatus msg (was replaced by RobotStatus in MiR software 2.0) * Contributors: Martin Günther 1.0.3 (2019-03-04) ------------------ * mir_msgs: Compile new msgs + rename mirMsgs -> mir_msgs * mir_msgs: Add geometry_msgs dependency Now that we have an actual msg package dependency, we don't need the std_msgs placeholder any more. * mir_msgs: Add new messages on kinetic * Contributors: Martin Günther 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_msgs/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation ) ################################################ ## Declare ROS messages, services and actions ## ################################################ # Generate messages in the 'msg' folder add_message_files( FILES AngleMeasurment.msg BMSData.msg BatteryCurrents.msg BrakeState.msg ChargingState.msg Device.msg Devices.msg EncoderTestEntry.msg Encoders.msg Error.msg Event.msg Events.msg ExternalRobot.msg ExternalRobots.msg Gpio.msg GripperState.msg HeightState.msg HookData.msg HookExtendedStatus.msg HookStatus.msg IOs.msg JoystickVel.msg LocalMapStat.msg MirExtra.msg MirLocalPlannerPathTypes.msg MissionCtrlCommand.msg MissionCtrlState.msg MovingState.msg PalletLifterStatus.msg Path.msg Pendant.msg PlanSegment.msg PlanSegments.msg Pose2D.msg PowerBoardMotorStatus.msg PrecisionDockingStatus.msg Proximity.msg ResourceState.msg ResourcesAcquisition.msg ResourcesState.msg RobotMode.msg RobotState.msg RobotStatus.msg SafetyStatus.msg Serial.msg ServiceResponseHeader.msg SkidDetectionDiff.msg SkidDetectionStampedFloat.msg SoundEvent.msg StampedEncoders.msg TimeDebug.msg Trolley.msg Twist2D.msg UserPrompt.msg WebPath.msg WorldMap.msg WorldModel.msg ) # Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES geometry_msgs ) ################################### ## catkin specific configuration ## ################################### catkin_package( CATKIN_DEPENDS geometry_msgs message_runtime ) ================================================ FILE: mir_msgs/msg/AngleMeasurment.msg ================================================ float64 angle #radians time timestamp ================================================ FILE: mir_msgs/msg/BMSData.msg ================================================ float64 pack_voltage float64 charge_current float64 discharge_current float64 state_of_charge float64 remaining_time_to_full_charge int32 remaining_capacity int32 state_of_health int32 DISCHARGING=1 #bit 0 int32 CHARGING=2 #bit 1 int32 OV=4 #bit 2 Over voltage int32 UV=8 #bit 3 Under voltage int32 COC=16 #bit 4 Charge over current int32 DOC=32 #bit 5 Discharge over current int32 DOT=64 #bit 6 Discharge over temperature int32 DUT=128 #bit 7 Discharge under temperature int32 SC=512 #bit 9 int32 COT=1024 #bit 10 Charge over temperature int32 CUT=2048 #bit 11 Charge under temperature int32 FW_STATUS_MSK=2031616 # to get Battery_Firmware_Status do the following: int32 FW_STATUS_SHIFT=16 # batt_fw_stat=(status_flags & FW_STATUS_MSK)>>FW_STATUS_SHIFT int32 FW_UPD_OK=0 #Battery firmware update finished OK. int32 FW_UPD_RUNNING=1 #Battery firmware update running. int32 FW_UPD_FAILED_BOOT=2 #Battery firmware update failed in Bootloader (Robot must not drive) int32 FW_UPD_FAILED_APP=3 #Battery firmware update failed updating the application (Robot can drive with old FW) int32 FW_UPD_FAILED_PARAM=4 #Battery firmware update failed uploading parameters (Robot can drive with old fw and parameters.) int32 FW_STATUS_LOW_BATT=5 #Battery firmware update skipped battery too low or high (Robot can drive with old parameters.) int32 FW_STATUS_FILE_CORRUPTED=6 #Battery firmware file corrupted (Robot can drive with old parameters.) int32 FW_STATUS_CURRENT_TO_HIGH=7 #Battery firmware file corrupted (Robot can drive with old parameters.) int32 FW_STATUS_NO_CAN=8 #Battery firmware update skipped no CAN communication (Robot can drive with old fw and parameters.) int32 FW_BATTERY_IMBALANCE_HIGH=9 #Battery firmware update is enforced and the battery will be shut off by the new firmware int32 status_flags int32 temperature uint32[] cell_voltage # In Mk2 robots and above the BMS provides data for 8 battery cells. 2Gen robots have BMS for 13 battery cells uint32 cell_voltage_diff string WST_serial # Exteded diagnosticts for BMZ battery uint32 bmz_flag # Flag for enabling extended diagnosticts uint32 battery_type uint32 BATT_TYPE_UNKNOWN=0 #type is unknown / no communucation uint32 BATT_TYPE_BMZ=1 #BMZ battery uint32 BATT_TYPE_WST=2 #WST battery uint32 BATT_TYPE_SBS=3 #SBS battery uint32 BATT_TYPE_SBS_SLIDE=4 #SBS SLIDE battery uint32 BATT_TYPE_NO_BMS=255 #WST No BMS battery float64 full_voltage int32 full_capacity int32 temperature2 int32 temperature_pcb int32 cycle_count int32 dsg_overcurrent_counter int32 chg_overcurrent_counter int32 hw_major int32 hw_minor int32 fw_major int32 fw_minor int32 fw_patch int32 fw_parameters_ok int32 rec_fw_major int32 rec_fw_minor int32 rec_fw_patch int32 bl_major int32 bl_minor uint32 status_enabled uint32 status_current_limitation uint32 status_switch_off_warn1 uint32 status_switch_off_warn2 uint32 status_fully_discharged uint32 status_nearly_discharged uint32 status_chargefet_on uint32 status_dischargefet_on uint32 status_discharging uint32 status_fully_charged uint32 status_charging uint32 status_temp_charging_err uint32 status_cell_over_voltage uint32 status_cell_under_voltage uint32 status_charge_over_current uint32 status_shortcircuit uint32 status_discharge_over_current float64 status_chargefet_voltage float64 status_dischargefet_voltage uint32 status_temp_discharging_err uint32 status_charger_detected uint32 mnfct_bms_revision uint32 mnfct_asn_revision uint32 mnfct_year uint32 mnfct_week uint32 mnfct_model uint32 mnfct_serial uint32 afe_i2c_error_count uint32 app_error_count uint32 fet_disable_state float64 last_battery_msg_time # SBS battery states uint32 SBS_battery_status uint32 SBS_battery_status_raw uint32 SBS_InitState1=1 uint32 SBS_InitState2=2 uint32 SBS_InitState3=3 uint32 SBS_InitState4=4 uint32 SBS_Idle=5 uint32 SBS_Discharge=6 uint32 SBS_Charge=7 uint32 SBS_Fault=10 uint32 SBS_CriticalError=11 uint32 SBS_PrepareDeepsleep=99 uint32 SBS_Deepsleep=100 string SBS_serial_1 string SBS_serial_2 uint32 SBS_arti_nr_1 uint32 SBS_arti_nr_2 uint32 SBS_arti_nr_3 uint32 SBS_curr_flow_passive_state # Overcurrent counters uint8 CHG_OC1_Count uint8 CHG_OC2_Count uint8 DSG_OC1_Count uint8 DSG_OC2_Count uint8 DSG_OC3_Count uint8 AFE_OC1_Count uint8 AFE_OC2_Count uint8 CHG_LatchClear_Count uint8 DSG_LatchClear_Count uint8 chg_oc_warning uint8 dsg_oc_warning ================================================ FILE: mir_msgs/msg/BatteryCurrents.msg ================================================ float64 battery1_current float64 battery2_current ================================================ FILE: mir_msgs/msg/BrakeState.msg ================================================ uint8 UNKNOWN = 0 uint8 INITIALIZING = 1 uint8 HOMING = 2 uint8 ACTIVE = 3 uint8 INACTIVE = 4 uint8 ACTIVATING = 5 uint8 DEACTIVATING = 6 uint8 ERROR = 7 uint8 state ================================================ FILE: mir_msgs/msg/ChargingState.msg ================================================ bool charging_relay float64 charging_current uint32 charging_current_raw float64 last_time_current float64 charging_voltage uint32 charging_voltage_raw bool is_voltage_low float64 last_time_voltage ================================================ FILE: mir_msgs/msg/Device.msg ================================================ string name string serial ================================================ FILE: mir_msgs/msg/Devices.msg ================================================ mir_msgs/Device[] devices ================================================ FILE: mir_msgs/msg/EncoderTestEntry.msg ================================================ float64 command_velocity float64 command_distance float64 left_dist float64 right_dist string suggested_direction string user_direction ================================================ FILE: mir_msgs/msg/Encoders.msg ================================================ float32 time_delta # Time since last encoder update. int32 left_wheel # Encoder counts (absolute or relative) int32 right_wheel # Encoder counts (absolute or relative) ================================================ FILE: mir_msgs/msg/Error.msg ================================================ # Definition of offsets indicating what type an error is int32 HARDWARE_ERROR = 0 int32 CPU_LOAD_ERROR = 100 int32 MEMORY_ERROR = 200 int32 ETHERNET_ERROR = 300 int32 HDD_ERROR = 400 int32 BATTERY_ERROR = 500 int32 IMU_ERROR = 600 int32 MOTOR_ERROR = 700 int32 LASER_ERROR = 800 int32 CAMERA_ERROR = 900 int32 SAFETY_SYSTEM_ERROR = 1000 int32 POWERBOARD_ERROR = 2000 int32 POWERSUPPLY_ERROR = 2100 int32 CANBUS_ERROR = 2200 int32 HOOK_ERROR = 5000 int32 HOOK_CAMERA_ERROR = 5100 int32 HOOK_ACTUATOR_ERROR = 5200 int32 HOOK_BRAKE_ERROR = 5300 int32 HOOK_ENCODER_ERROR = 5400 int32 MISSING_ERROR = 9000 int32 SOFTWARE_ERROR = 10000 int32 MISSION_ERROR = 10100 int32 LOCALIZATION_ERROR = 10200 int32 MAPPING_ERROR = 10300 int32 ODOM_FUSION_ERROR = 10400 int32 EVACUATION_ERROR = 12000 time timestamp # Timestamp for when the error occurred int32 code # Error code string description # Error description string module # Module in which the error occurred bool nolog # Do not trigger an error log if set to true ================================================ FILE: mir_msgs/msg/Event.msg ================================================ uint32 EV_SPEED=1 uint32 EV_BLINK=2 uint32 EV_SOUND=3 uint32 EV_DOOR=4 uint32 EV_AMCLOFF=5 uint32 EV_FWDDIST=6 uint32 EV_IO=7 uint32 EV_FLEETLCK=8 # Fleet uint32 EV_EMERGENCY=9 # Fleet uint32 eventType # The area event type string area_guid # The area unique identifier string area_name # The name of the area geometry_msgs/Point[] polygon # An array of corner points that define the edges of the area ================================================ FILE: mir_msgs/msg/Events.msg ================================================ Header header Event[] events ================================================ FILE: mir_msgs/msg/ExternalRobot.msg ================================================ Header header uint32 id uint32 MIR100=1 uint32 MIR500=3 uint32 type_id string name float64 robot_length float64 robot_width string footprint string ip uint32 map_id int32 priority geometry_msgs/Pose pose geometry_msgs/Pose extrapolated_pose geometry_msgs/Twist twist ================================================ FILE: mir_msgs/msg/ExternalRobots.msg ================================================ Header header mir_msgs/ExternalRobot[] robots ================================================ FILE: mir_msgs/msg/Gpio.msg ================================================ uint8 POWERBOARD_GPIO = 0 uint8 POWERBOARD_RESET_SWITCH_LED = 1 uint8 PENDANT_INPUT = 5 uint8 AUTO_MODE_SWITCH = 10 uint8 MANUAL_MODE_SWITCH = 11 uint8 STOP_BUTTON = 12 uint8 ioport uint8 dat ================================================ FILE: mir_msgs/msg/GripperState.msg ================================================ uint8 LOCK_UNKNOWN = 0 uint8 LOCK_HOMING = 1 uint8 LOCK_OPEN = 2 uint8 LOCK_OPENING = 3 uint8 LOCK_CLOSED = 4 uint8 LOCK_CLOSING = 6 uint8 LOCK_ERROR = 9 uint8 state ================================================ FILE: mir_msgs/msg/HeightState.msg ================================================ uint8 HEIGHT_UNKNOWN = 0 uint8 HEIGHT_HOMING = 1 uint8 HEIGHT_IDLE = 2 uint8 HEIGHT_CHANGING = 3 uint8 HEIGHT_ERROR = 4 uint8 state ================================================ FILE: mir_msgs/msg/HookData.msg ================================================ AngleMeasurment angle float64 height float64 length uint8 brake_state uint8 gripper_state uint8 height_state ================================================ FILE: mir_msgs/msg/HookExtendedStatus.msg ================================================ bool available BrakeState brake GripperState gripper HeightState height float32 angle string qr_marker_name ================================================ FILE: mir_msgs/msg/HookStatus.msg ================================================ bool available float32 length float32 height float32 angle bool braked bool trolley_attached Trolley trolley ================================================ FILE: mir_msgs/msg/IOs.msg ================================================ string module_guid bool connected uint8 DONE=0 uint8 STARTED=1 uint8 ERROR=3 uint8 status int8 num_inputs bool[] input_state int8 num_outputs bool[] output_state string ip string error ================================================ FILE: mir_msgs/msg/JoystickVel.msg ================================================ string joystick_token geometry_msgs/Twist speed_command ================================================ FILE: mir_msgs/msg/LocalMapStat.msg ================================================ int32 idx int32 x int32 y ================================================ FILE: mir_msgs/msg/MirExtra.msg ================================================ # MirExtra - to publish data on a topic Header header float32 time_delta # Time since last encoder update. float32 r_rpm # rmp speed from right encoder float32 l_rpm # rmp speed from left encoder float32 vel # calc velocity float32 ang # calculated angle speed ================================================ FILE: mir_msgs/msg/MirLocalPlannerPathTypes.msg ================================================ uint8 REVERSE_TROLLEY_STANDARD=1 uint8 REVERSE_TROLLEY_FAST=2 uint8 REVERSE_TROLLEY_COMPACT=3 uint8 path_type ================================================ FILE: mir_msgs/msg/MissionCtrlCommand.msg ================================================ uint8 CMD_GET_STATUS = 0 uint8 CMD_WAIT_POS_LOCK = 1 uint8 CMD_WAIT_AREA_LOCK = 2 uint8 CMD_CONTINUE = 3 uint8 CMD_LOAD_MISSION = 4 string description int32 cmd int32 mission_id ================================================ FILE: mir_msgs/msg/MissionCtrlState.msg ================================================ uint8 STATE_IDLE = 0 uint8 STATE_WAIT_POS_LOCK = 1 uint8 STATE_WAIT_AREA_LOCK = 2 uint8 STATE_WAIT_MAP_TRANSITION = 10 uint8 STATE_WAIT_LIFT_START_FLOOR = 11 uint8 STATE_WAIT_LIFT_END_FLOOR = 12 uint8 STATE_WAIT_LIFT_END_FLOOR_CONTINUE = 13 int32 state int32 pos_id ================================================ FILE: mir_msgs/msg/MovingState.msg ================================================ uint8 UNKNOWN=0 uint8 MOVING=1 uint8 STOPPED=2 uint8 STANDING_STILL=3 uint8 moving_state # Current robot moving state ================================================ FILE: mir_msgs/msg/PalletLifterStatus.msg ================================================ uint8 PALLET_LIFT_STATE_DISABLED = 0 uint8 PALLET_LIFT_STATE_MOVING = 1 uint8 PALLET_LIFT_STATE_DOWN = 2 uint8 PALLET_LIFT_STATE_UP = 3 bool is_enabled uint8 state ================================================ FILE: mir_msgs/msg/Path.msg ================================================ Header header mir_msgs/Pose2D[] poses ================================================ FILE: mir_msgs/msg/Pendant.msg ================================================ float32 x float32 y uint8 gpio_bits ================================================ FILE: mir_msgs/msg/PlanSegment.msg ================================================ bool forward_motion int32 start_idx float64 length float64 remaining_length geometry_msgs/PoseStamped[] path ================================================ FILE: mir_msgs/msg/PlanSegments.msg ================================================ mir_msgs/PlanSegment[] p_segments ================================================ FILE: mir_msgs/msg/Pose2D.msg ================================================ float32 x float32 y float32 orientation ================================================ FILE: mir_msgs/msg/PowerBoardMotorStatus.msg ================================================ uint16 LeftMotor_CtrlWord int32 LeftMotor_Speed int32 LeftMotor_Encoder uint16 LeftMotor_Status uint8 LeftMotor_Error uint32 LeftMotor_ErrorHist1 uint32 LeftMotor_ErrorHist2 int32 LeftMotor_Current uint16 LeftMotor_I2t_Motor uint16 LeftMotor_I2t_Controller int16 LeftMotor_Temperature uint16 RightMotor_CtrlWord int32 RightMotor_Speed int32 RightMotor_Encoder uint16 RightMotor_Status uint8 RightMotor_Error uint32 RightMotor_ErrorHist1 uint32 RightMotor_ErrorHist2 int32 RightMotor_Current uint16 RightMotor_I2t_Motor uint16 RightMotor_I2t_Controller int16 RightMotor_Temperature #Status bits for brake feedback. uint8 BRAKE_STATUS_BRAKED_BIT=1 # is "1" if brake is supposed to be braked uint8 BRAKE_STATUS_FB_BIT=4 # is "1" if brake feedback sensor is activated (brake is released) uint8 BRAKE_STATUS_TRANSITION_BIT=128 # So error combinations are - (Any combination with the TRANSITION bit set are valid) # BRAKED FB TRANSITION STATUSWORD # 0 0 0 0x00 Brake is suppused to be released, but FB indicate braked. We are not in transition. # 1 1 0 0x05 Brake is suppused to be braked, but FB indicate released. We are not in transition. uint8 Brake_LeftStatus uint8 Brake_RightStatus ================================================ FILE: mir_msgs/msg/PrecisionDockingStatus.msg ================================================ bool connected bool motor_forward bool motor_back bool left_docking bool right_docking ================================================ FILE: mir_msgs/msg/Proximity.msg ================================================ Header header uint16[] ranges ================================================ FILE: mir_msgs/msg/ResourceState.msg ================================================ string[] assigned # A list of IPs of all assigned robots (Areas can have more than one robot assigned at a time) uint32 ROBOT_POSITION=0 uint32 STAGING_POSITION=1 uint32 CHARGING_STATION=2 uint32 AREA=3 uint32 ELEVATOR_ENTRY_POSITION=26 uint32 ELEVATOR_POSITION=25 uint32 type # The resource type uint32 path_idx # The index from the global path in which the robot gets into the position float32 distance # The distance from the robot to the resource geometry_msgs/Point collision_point # The collision point with the resource geometry_msgs/Point[] resource_geometry # The resource_geometry string[] queue # The queue for a resource. It's a list of robots ips. string name # The name of the resource string guid # The guid of the resource ================================================ FILE: mir_msgs/msg/ResourcesAcquisition.msg ================================================ Header header geometry_msgs/PoseStamped[] path string position_guid string token ================================================ FILE: mir_msgs/msg/ResourcesState.msg ================================================ Header header ResourceState[] resources string token ================================================ FILE: mir_msgs/msg/RobotMode.msg ================================================ # The robot operates in different mode uint8 ROBOT_MODE_NONE = 0 # start mode uint8 ROBOT_MODE_MAPPING = 3 # in mapping a new map is made uint8 ROBOT_MODE_MAPPING_FINALIZING = 4 # in mapping the recorded map is being finalised uint8 ROBOT_MODE_MISSION = 7 # primary mode when executing a mission (action list) uint8 ROBOT_MODE_CHANGING = 255 # a transition mode - to say that a transition is in progress uint8 robotMode string robotModeString ================================================ FILE: mir_msgs/msg/RobotState.msg ================================================ # The robot has to be in a predefined state uint8 ROBOT_STATE_NONE = 0 uint8 ROBOT_STATE_STARTING = 1 uint8 ROBOT_STATE_SHUTTINGDOWN = 2 uint8 ROBOT_STATE_READY = 3 # ready to execute uint8 ROBOT_STATE_PAUSE = 4 # pause from executing uint8 ROBOT_STATE_EXECUTING = 5 # when running in mission/taxa/bus uint8 ROBOT_STATE_ABORTED = 6 uint8 ROBOT_STATE_COMPLETED = 7 # done executing uint8 ROBOT_STATE_DOCKED = 8 # in the dock and charging the batteries uint8 ROBOT_STATE_DOCKING = 9 uint8 ROBOT_STATE_EMERGENCYSTOP = 10 # the robot has emg-stop activated uint8 ROBOT_STATE_MANUALCONTROL = 11 # a pause state, where the robot can move uint8 ROBOT_STATE_ERROR = 12 # a general error state, requires a error handle uint8 robotState string robotStateString ================================================ FILE: mir_msgs/msg/RobotStatus.msg ================================================ Header header float32 battery_percentage int32 battery_time_remaining float32 battery_voltage float32 distance_to_next_target Error[] errors string footprint HookStatus hook_status HookData hook_data string map_id bool unloaded_map_changes int32 mission_queue_id string mission_text int32 mode_id string mode_text float64 moved Pose2D position string robot_name string session_id string software_version uint8 state_id string state_text int32 uptime Twist2D velocity mir_msgs/UserPrompt user_prompt bool safety_system_muted bool joystick_low_speed_mode_enabled string joystick_web_session_id string mode_key_state ================================================ FILE: mir_msgs/msg/SafetyStatus.msg ================================================ bool is_connected bool is_firmware_ok int32 firmware_version bool in_protective_stop bool in_emergency_stop bool sto_feedback bool is_restart_required bool is_safety_muted float64 max_lin_speed float64 max_rot_speed # Defines for filling out the mute_mask uint8 MUTE_FRONT_RIGHT = 1 uint8 MUTE_FRONT_CENTER = 2 uint8 MUTE_FRONT_LEFT = 4 uint8 MUTE_LEFT_CENTER = 8 uint8 MUTE_REAR_LEFT = 16 uint8 MUTE_REAR_CENTER = 32 uint8 MUTE_REAR_RIGHT = 64 uint8 MUTE_RIGHT_CENTER = 128 uint8 MUTE_FRONT = 7 uint8 MUTE_LEFT = 28 uint8 MUTE_REAR = 112 uint8 MUTE_RIGHT = 193 uint8 MUTE_SIDES = 221 uint8 MUTE_ALL = 255 uint8 mute_mask uint8 partial_mute_mask bool is_limited_speed_active bool is_lifter_down bool in_sleep_mode bool in_manual_mode bool is_manual_mode_restart_required ================================================ FILE: mir_msgs/msg/Serial.msg ================================================ Header header string data ================================================ FILE: mir_msgs/msg/ServiceResponseHeader.msg ================================================ bool success string error ================================================ FILE: mir_msgs/msg/SkidDetectionDiff.msg ================================================ time time_stamp float64 enc_acc_x float64 enc_acc_y float64 enc_rot_th float64 imu_acc_x float64 imu_acc_y float64 imu_rot_th float64 diff_acc_x float64 diff_acc_y float64 diff_rot_th ================================================ FILE: mir_msgs/msg/SkidDetectionStampedFloat.msg ================================================ time time_stamp float64 value ================================================ FILE: mir_msgs/msg/SoundEvent.msg ================================================ time time_stamp string sound_guid string message uint8 START=0 uint8 STOP =1 uint8 MUTE=2 uint8 UNMUTE=3 uint8 PAUSE=4 uint8 UNPAUSE=5 uint8 FINISH=6 uint8 MUTEABLE=7 uint8 REQ_PLAY=10 uint8 event ================================================ FILE: mir_msgs/msg/StampedEncoders.msg ================================================ Header header Encoders encoders ================================================ FILE: mir_msgs/msg/TimeDebug.msg ================================================ string[] description float64[] time_elapsed ================================================ FILE: mir_msgs/msg/Trolley.msg ================================================ int32 id float32 length float32 width float32 height float32 offset_locked_wheels ================================================ FILE: mir_msgs/msg/Twist2D.msg ================================================ float32 linear float32 angular ================================================ FILE: mir_msgs/msg/UserPrompt.msg ================================================ bool has_request string guid string user_group string question string[] options duration timeout ================================================ FILE: mir_msgs/msg/WebPath.msg ================================================ int32 seq float32[] x float32[] y ================================================ FILE: mir_msgs/msg/WorldMap.msg ================================================ mir_msgs/ResourcesState positions mir_msgs/ResourcesState areas mir_msgs/ExternalRobots robots int32 map_id ================================================ FILE: mir_msgs/msg/WorldModel.msg ================================================ Header header mir_msgs/WorldMap[] world_map # world model for a particular map bool enable_resource_tracking ================================================ FILE: mir_msgs/package.xml ================================================ mir_msgs 1.1.8 Message definitions for the MiR robot Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin geometry_msgs message_generation message_runtime ================================================ FILE: mir_navigation/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_navigation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Fix typo in license * Add Regulated Pure Pursuit local planner (experimental) requires https://github.com/JohnTGZ/regulated_pure_pursuit_controller known bugs: - ignores local costmap (will collide with dynamic obstacles) - oscillates near goal (https://github.com/JohnTGZ/regulated_pure_pursuit_controller/issues/8) * Move repo to DFKI-NI * Fix start_planner documentation * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Add license headers * Fix flake8 warnings * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ * navigation: Reduce footprint to actual size This reduces the footprint: * 18 mm in front * 42 mm in the back * 27 mm at the sides Now the footprint exactly matches the bounding box of the mesh, with no padding. This should make navigation in tight spaces easier; let's hope it doesn't lead to collisions. * navigation: Move footprint_padding to proper namespace The footprint_padding parameter in the upper namespace was ignored, needed to be moved into local_costmap/global_costmap to take effect. * genmprim: Remove obsolete plt.hold() This fixes the following error: AttributeError: module 'matplotlib.pyplot' has no attribute 'hold' * mir_navigation: Remove static_map parameter This fixes the following warning: [ WARN] local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ * Merge branch 'melodic-2.8' into noetic * Rename tf frame and topic 'odom_comb' -> 'odom' This is how they are called on the real MiR since MiR software 2.0. * Reformat python code using black * Contributors: Martin Günther 1.1.2 (2021-05-12) ------------------ * Uncomment available dependencies in noetic (`#79 `_) * Contributors: Oscar Lima 1.1.1 (2021-02-11) ------------------ * Add optional namespace to launch files * Add prefix to start_planner.launch (`#67 `_) * Update scripts to Python3 (Noetic) * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Remove hector_mapping dependency (not released in noetic) * Update scripts to Python3 (Noetic) * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Add missing matplotlib dependency * plot_mprim: Fix color display * Fix bug in genmprim_unicycle_highcost_5cm In Python3, np.arange doesn't accept floats. * Fix some catkin_lint warnings * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ * Rename hector_mapping.launch, add dependency * genmprim.py: Improve plotting * genmprim.py: Make executable * SBPL: Reduce allocated_time + initial_epsilon params This leads to shorter planning times, but will perhaps fail on larger maps. * Update mprim file to mir-software 2.0.17 This was updated in 2.0.17 and hasn't changed through 2.6 at least. * Add genmprim_unicycle matlab + python script, fix mprim file * Adjust dwb params: split_path, finer trajectories (`#43 `_) - use split_path option to enforce following complex paths - more trajectory samples over a smaller simulated time. This fixes a problem where the robot would stop too far away from the goal, as all possible trajectories either overshot the goal, or were too short to reach into the next gridcell of the critics. - remove Oscillation critic (never helped) * added PathDistPrunedCritic for dwb (`#42 `_) which works exactly like the original PathDistCritic, except that it searches for a local minimum in the distance from the global path to the robots current position. It then prunes the global_path from the start up to this point, therefore approximately cutting of a segment of the path that the robot already followed. * Add default local_planner to move_base launch file This makes the hector_mapping Gazebo demo work with the instructions from the README (see `#32 `_). * Contributors: Martin Günther, Nils Niemann 1.0.4 (2019-05-06) ------------------ * Rviz config: Add planned paths + costmap from real MiR * Contributors: Martin Günther 1.0.3 (2019-03-04) ------------------ * fix frame_id for melodic (`#18 `_) * Tune dwb parameters * PathProgressCritic: Add heading score * Use dwb_local_planner in move_base config * Move footprint param to move_base root namespace This allows other move_base plugins, such as dwb_local_planner, to access this parameter. * Add hector_mapping * amcl.launch: Change default, remap service This is required if amcl.launch is started within a namespace. * teb_local_planner: Fix odom topic name * Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs Add prefix argument to configs * adds $(arg prefix) to a lot of configs This is an important step to be able to re-parameterize move base, the diffdrive controller, ekf, amcl and the costmaps for adding a tf prefix to the robots links * mir_navigation: Adjust helper node topics * Add amcl launchfile (`#11 `_) * added amcl.launch * changed amcl params to default mir amcl parameters * Merge pull request `#13 `_ from niniemann/fix-virtual-walls 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. Also, I added a `with_virtual_walls` parameter to `start_maps.launch` and `start_planner.launch`. * added with_virtual_walls parameter to start_maps and start_planner * reorder local costmap plugins * Revert "mir_navigation: Disable virtual walls if no map file set" This reverts commit 0cfda301b2bb1e8b3458e698efd24a7901e5d132. The reason is that the `eval` keyword was introduced in kinetic, so it doesn't work in indigo. * mir_navigation: Update rviz config * mir_navigation: Disable virtual walls if no map file set * mir_navigation: Rename virtual_walls args + files * mir_navigation: Remove parameter first_map_only This parameter must be set to false (the default) when running SLAM (otherwise the map updates won't be received), and when running a static map_server it doesn't matter; even then, it should be false to allow restarting the map_server with a different map. Therefore this commit removes it altogether and leaves it at the default of "false". * split parameter files between mapping/planning (`#10 `_) The differences are simple: When mapping, first_map_only must be set to false, and the virtual walls plugin must not be loaded (else move_base will wait for a topic that is not going to be published). * Document move_base params, add max_planning_retries Setting max_planning_retries to 10 makes the planner fail faster if the planning problem is infeasible. By default, there's an infinite number of retries, so we had to wait until the planner_patience ran out (5 s). * Update rviz config Make topics relative, so that ROS_NAMESPACE=... works. * Switch to binary sbpl_lattice_planner dependency ... instead of compiling from source. * Split scan_rep117 topic into two separate topics This fixes the problem that the back laser scanner was ignored in the navigation costmap in Gazebo (probably because in Gazebo, both laser scanners have the exact same timestamp). * mir_navigation: Add clear_params to move_base launch * mir_navigation: marking + clearing were switched Other than misleading names, this had no effect. * Contributors: Martin Günther, Nils Niemann, Noël Martignoni 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ * Initial release * Contributors: Martin Günther ================================================ FILE: mir_navigation/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_navigation) find_package(catkin REQUIRED COMPONENTS roslaunch ) ################################### ## catkin specific configuration ## ################################### catkin_package() ############# ## Install ## ############# # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html # Mark executable scripts (Python etc.) for installation # in contrast to setup.py, you can choose the destination install(PROGRAMS mprim/genmprim_unicycle_highcost_5cm.py nodes/acc_finder.py nodes/min_max_finder.py scripts/plot_mprim.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) ## Mark executables and/or libraries for installation # install(TARGETS mir_navigation mir_navigation_node # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} # FILES_MATCHING PATTERN "*.h" # PATTERN ".svn" EXCLUDE # ) # Mark other files for installation (e.g. launch and bag files, etc.) install(DIRECTORY config launch mprim rviz DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) ############# ## Testing ## ############# ## Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_mir_navigation.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() ## Add folders to be run by python nosetests # catkin_add_nosetests(test) roslaunch_add_file_check(launch) ================================================ FILE: mir_navigation/config/base_local_planner_params.yaml ================================================ base_local_planner: base_local_planner/TrajectoryPlannerROS TrajectoryPlannerROS: # Robot configuration acc_lim_x: 1.5 acc_lim_y: 0 acc_lim_theta: 2.0 max_vel_x: 0.8 min_vel_x: 0.1 max_vel_theta: 1.0 min_vel_theta: -1.0 min_in_place_vel_theta: 0.2 escape_vel: -0.1 holonomic_robot: false # Goal tolerance yaw_goal_tolerance: 0.03 xy_goal_tolerance: 0.08 latch_xy_goal_tolerance: true # Forward simulaton parameters sim_time: 1.2 sim_granularity: 0.025 angular_sim_granularity: 0.04 vx_samples: 15 vtheta_samples: 20 controller_frequency: 5 # Trajectory scoring parameters meter_scoring: true pdist_scale: 2.2 #0.6 gdist_scale: 0.8 #0.8 occdist_scale: 0.1 heading_lookahead: 0.325 heading_scoring: true heading_scoring_timestep: 0.8 dwa: true publish_cost_grid: false global_frame_id: map # Oscillation prevention parameter oscillation_reset_dist: 0.05 # Global plan parameters prune_plan: true ================================================ FILE: mir_navigation/config/costmap_common_params.yaml ================================================ robot_base_frame: $(arg prefix)base_footprint transform_tolerance: 0.4 update_frequency: 5.0 publish_frequency: 1.0 obstacle_range: 3.0 #mark_threshold: 1 publish_voxel_map: true footprint_padding: 0.0 navigation_map: map_topic: /map obstacles: observation_sources: b_scan_marking b_scan_clearing f_scan_marking f_scan_clearing b_scan_marking: topic: b_scan_rep117 data_type: LaserScan clearing: false marking: true inf_is_valid: false min_obstacle_height: 0.13 max_obstacle_height: 0.25 b_scan_clearing: topic: b_scan_rep117 data_type: LaserScan clearing: true marking: false inf_is_valid: false min_obstacle_height: 0.13 max_obstacle_height: 0.25 f_scan_marking: topic: f_scan_rep117 data_type: LaserScan clearing: false marking: true inf_is_valid: false min_obstacle_height: 0.13 max_obstacle_height: 0.25 f_scan_clearing: topic: f_scan_rep117 data_type: LaserScan clearing: true marking: false inf_is_valid: false min_obstacle_height: 0.13 max_obstacle_height: 0.25 virtual_walls_map: map_topic: /virtual_walls/map use_maximum: true ================================================ FILE: mir_navigation/config/costmap_global_params.yaml ================================================ global_costmap: global_frame: map update_frequency: 1.0 publish_frequency: 1.0 raytrace_range: 2.0 resolution: 0.05 z_resolution: 0.2 z_voxels: 10 inflation: 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. inflation_radius: 0.6 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius. # plugins are loaded via costmap_global_params_plugins_[mapping|planning].yaml ================================================ FILE: mir_navigation/config/costmap_global_params_plugins_no_virtual_walls.yaml ================================================ global_costmap: plugins: - {name: navigation_map, type: "costmap_2d::StaticLayer" } - {name: obstacles, type: "costmap_2d::VoxelLayer" } - {name: inflation, type: "costmap_2d::InflationLayer" } ================================================ FILE: mir_navigation/config/costmap_global_params_plugins_virtual_walls.yaml ================================================ global_costmap: plugins: - {name: navigation_map, type: "costmap_2d::StaticLayer" } - {name: obstacles, type: "costmap_2d::VoxelLayer" } - {name: virtual_walls_map, type: "costmap_2d::StaticLayer" } - {name: inflation, type: "costmap_2d::InflationLayer" } ================================================ FILE: mir_navigation/config/costmap_local_params.yaml ================================================ local_costmap: global_frame: $(arg prefix)odom rolling_window: true raytrace_range: 6.0 resolution: 0.05 z_resolution: 0.15 z_voxels: 8 inflation: 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. inflation_radius: 0.6 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius. width: 4.0 height: 4.0 origin_x: 0.0 origin_y: 0.0 # plugins are loaded via costmap_local_params_plugins_[mapping|planning].yaml ================================================ FILE: mir_navigation/config/costmap_local_params_plugins_no_virtual_walls.yaml ================================================ local_costmap: plugins: - {name: obstacles, type: "costmap_2d::VoxelLayer" } - {name: inflation, type: "costmap_2d::InflationLayer" } ================================================ FILE: mir_navigation/config/costmap_local_params_plugins_virtual_walls.yaml ================================================ local_costmap: plugins: - {name: virtual_walls_map, type: "costmap_2d::StaticLayer" } - {name: obstacles, type: "costmap_2d::VoxelLayer" } - {name: inflation, type: "costmap_2d::InflationLayer" } ================================================ FILE: mir_navigation/config/dwa_local_planner_params.yaml ================================================ base_local_planner: dwa_local_planner/DWAPlannerROS DWAPlannerROS: # Robot configuration max_vel_x: 0.8 min_vel_x: -0.2 max_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot max_trans_vel: 0.8 # choose slightly less than the base's capability min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity trans_stopped_vel: 0.03 # Warning! # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities # are non-negligible and small in place rotational velocities will be created. max_rot_vel: 1.0 # choose slightly less than the base's capability min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity rot_stopped_vel: 0.1 acc_lim_x: 1.5 acc_lim_y: 0.0 # diff drive robot acc_limit_trans: 1.5 acc_lim_theta: 2.0 # Goal tolerance yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 latch_xy_goal_tolerance: true # Forward simulation sim_time: 1.2 vx_samples: 15 vy_samples: 1 # diff drive robot, there is only one sample vtheta_samples: 20 # Trajectory scoring path_distance_bias: 64.0 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan goal_distance_bias: 12.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal occdist_scale: 0.5 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point stop_time_buffer: 0.2 # default: 0.2 mir: 0.2 - amount of time a robot must stop before colliding for a valid traj. scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint max_scaling_factor: 0.2 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed. prune_plan: true # Oscillation prevention oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags, in m oscillation_reset_angle: 0.2 # 0.2 - the angle the robot must turn before resetting Oscillation flags, in rad # Debugging publish_traj_pc : true publish_cost_grid_pc: true global_frame_id: /odom # or /odom ================================================ FILE: mir_navigation/config/dwb_local_planner_params.yaml ================================================ base_local_planner: nav_core_adapter::LocalPlannerAdapter LocalPlannerAdapter: planner_name: dwb_local_planner::DWBLocalPlanner DWBLocalPlanner: # Robot configuration max_vel_x: 0.8 min_vel_x: -0.2 max_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot max_speed_xy: 0.8 # max_trans_vel: 0.8 # choose slightly less than the base's capability min_speed_xy: 0.1 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity max_vel_theta: 1.0 # max_rot_vel: 1.0 # choose slightly less than the base's capability 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 acc_lim_x: 1.5 acc_lim_y: 0.0 # diff drive robot acc_lim_theta: 2.0 decel_lim_x: -1.5 decel_lim_y: -0.0 decel_lim_theta: -2.0 # Goal tolerance yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 #latch_xy_goal_tolerance: true # Whether to split the path into segments or not # Requires https://github.com/locusrobotics/robot_navigation/pull/50 split_path: true # Forward simulation (trajectory generation) trajectory_generator_name: dwb_plugins::StandardTrajectoryGenerator # or dwb_plugins::LimitedAccelGenerator sim_time: 0.8 vx_samples: 15 vy_samples: 1 # diff drive robot, there is only one sample vtheta_samples: 15 discretize_by_time: false angular_granularity: 0.15 linear_granularity: 0.05 # sim_period # include_last_point # Goal checking goal_checker_name: dwb_plugins::SimpleGoalChecker # stateful: true # Critics (trajectory scoring) #default_critic_namespaces: [dwb_critics, mir_dwb_critics] critics: [RotateToGoal, ObstacleFootprint, PathAlign, PathDistPruned, PathProgress] RotateToGoal: scale: 100.0 # lookahead_time: -1.0 # slowing_factor: 5.0 ObstacleFootprint: scale: 0.01 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles max_scaling_factor: 0.2 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed. scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint sum_scores: false # if true, return sum of scores of all trajectory points instead of only last one PathAlign: scale: 16.0 forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point PathDistPruned: scale: 32.0 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan class: 'mir_dwb_critics::PathDistPruned' PathProgress: scale: 24.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal heading_scale: 0.1 class: 'mir_dwb_critics::PathProgress' xy_local_goal_tolerance: 0.20 angle_threshold: 0.78539816 # 45 degrees # Prune already passed poses from plan prune_plan: true prune_distance: 1.0 # Old poses farther away than prune_distance (in m) will be pruned. # If the robot ever gets away further than this distance from the plan, # the error "Resulting plan has 0 poses in it" will be thrown and # replanning will be triggered. # Debugging publish_cost_grid_pc: true debug_trajectory_details: false publish_evaluation: true publish_global_plan: true publish_input_params: true publish_local_plan: true publish_trajectories: true publish_transformed_plan: true marker_lifetime: 0.5 ================================================ FILE: mir_navigation/config/eband_local_planner_params.yaml ================================================ base_local_planner: eband_local_planner/EBandPlannerROS EBandPlannerROS: # Robot configuration max_vel_lin: 0.8 # choose slightly less than the base's capability min_vel_lin: 0.1 # this is the min trans velocity when there is negligible rotational velocity trans_stopped_vel: 0.03 max_vel_th: 1.0 # choose slightly less than the base's capability min_vel_th: 0.1 # this is the min angular velocity when there is negligible translational velocity rot_stopped_vel: 0.1 min_in_place_vel_th: 0.1 # Minimum in-place angular velocity in_place_trans_vel: 0.0 # Minimum in place linear velocity max_acceleration: 1.5 # Maximum allowable acceleration max_translational_acceleration: 1.5 # Maximum linear acceleration max_rotational_acceleration: 2.0 # Maximum angular acceleration # Goal tolerance yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 # Elastic Band Parameters eband_min_relative_overlap: 0.7 # Min distance that denotes connectivity between consecutive bubbles eband_tiny_bubble_distance: 0.01 # Bubble geometric bound regarding tiny bubble distance eband_tiny_bubble_expansion: 0.01 # Bubble geometric bound regarding tiny bubble expansion eband_internal_force_gain: 1.0 # Force gain of forces between consecutive bubbles that tend to stretch the elastic band eband_external_force_gain: 2.0 # Force gain of forces that tend to move the bubbles away from obstacles num_iterations_eband_optimization: 3 # Number of iterations for eband optimization eband_equilibrium_approx_max_recursion_depth: 4 # Number of iterations for reaching the equilibrium between internal and external forces eband_equilibrium_relative_overshoot: 0.75 # Maximum relative equlibrium overshoot eband_significant_force_lower_bound: 0.15 # Minimum magnitude of force that is considered significant and used in the calculations costmap_weight: 10.0 # Costmap weight factor used in the calculation of distance to obstacles # Trajectory Controller Parameters k_prop: 4.0 # Proportional gain of the PID controller k_damp: 3.5 # Damping gain of the PID controller Ctrl_Rate: 10.0 # Control rate virtual_mass: 0.75 # Virtual mass rotation_correction_threshold: 0.5 # Rotation correction threshold differential_drive: True # Denotes whether to use the differential drive mode bubble_velocity_multiplier: 2.0 # Multiplier of bubble radius rotation_threshold_multiplier: 1.0 # Multiplier of rotation threshold disallow_hysteresis: False # Determines whether to try getting closer to the goal, in case of going past the tolerance ================================================ FILE: mir_navigation/config/mir_local_planner_params.yaml ================================================ base_local_planner: mirLocalPlanner/MIRPlannerROS MIRPlannerROS: # Robot configuration max_vel_x: 0.8 min_vel_x: -0.2 min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity # Warning! # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities # are non-negligible and small in place rotational velocities will be created. max_rot_vel: 1.0 # choose slightly less than the base's capability min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity acc_lim_x: 1.5 acc_lim_y: 0.0 # diff drive robot acc_lim_th: 2.0 min_inplace_rot: 0.15 max_inplace_rot: 0.6 min_in_place_rotational_vel: 0.2 escape_vel: -0.1 holonomic_robot: false # Goal tolerance yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 # Forward simulaton sim_time: 1.2 sim_granularity: 0.025 vx_samples: 15 vth_samples: 20 vtheta_samples: 20 # Trajectory scoring path_distance_bias: 0.4 # weighting for how much it should stick to the global path plan goal_distance_bias: 0.6 # weighting for how much it should attempt to reach its goal occdist_scale: 0.01 # weighting for how much the controller should avoid obstacles forward_point_distance: 0.325 # how far along to place an additional scoring point stop_time_buffer: 0.2 # amount of time a robot must stop before colliding for a valid traj. scaling_speed: 0.25 # absolute velocity at which to start scaling the robot's footprint max_scaling_factor: 0.2 # how much to scale the robot's footprint when at speed. heading_lookahead: 0.325 dwa: true # Oscillation prevention oscillation_reset_dist: 0.05 # how far to travel before resetting oscillation flags, in m # Debugging publish_visualization: false publish_cost_grid_pc: false global_frame_id: odom # MiR specific parameters tau_p: 5.0 # The proportional value in the CTE PID tracking tau_i: 0.1 # The integral value in the CTE PID tracking tau_d: 0.5 # The differential value in the CTE PID tracking tau_w: 9.0 # The proportional angle value in the CTE tracking k_rho: 1.0 # The proportional value to goal in Goal tracking k_alfa: 8.0 # The diff angle between the robot and the goal in the Goal tracking k_beta: -2.5 # The angle to the goal from the robot in the Goal tracking blocked_path_dist: 3.0 # At what distance should the planner react when the path is blocked blocked_path_dev: 60.0 # How far can we move from the planned path when it is blocked blocked_path_action: new_plan # Which action to take, when path is blocked occ_path_dist: 3.0 # At what distance should the planner react when the path is near obstacle occ_path_dev: 15.0 # How far can we move from the planned path when the path is near a obstacle occ_path_level: 120.0 # Threshold level for a obstacle cte_look_ahead: 0.2 # The max/min distance to add for the CTE tracking penalize_negative_x: true # Whether to penalize trajectories that have negative x velocities. # non-dynamic parameters dist_towards_obstacles: 1.5 dist_towards_obstacles_trolley: 1.75 goal_seek_tolerance: 2.0 goal_seek_tolerance_trolley: 0.25 ================================================ FILE: mir_navigation/config/move_base_common_params.yaml ================================================ ### footprint footprint: [[0.488,-0.293],[0.488,0.293],[-0.412,0.293],[-0.412,-0.293]] ### replanning controller_frequency: 5.0 # run controller at 5.0 Hz controller_patience: 15.0 # if the controller failed, clear obstacles and retry; after 15.0 s, abort and replan planner_frequency: 0.0 # don't continually replan (only when controller failed) planner_patience: 5.0 # if the first planning attempt failed, abort planning retries after 5.0 s... max_planning_retries: 10 # ... or after 10 attempts (whichever happens first) oscillation_timeout: 30.0 # abort controller and trigger recovery behaviors after 30.0 s ### recovery behaviors recovery_behavior_enabled: true recovery_behaviors: [{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}] conservative_reset: reset_distance: 3.0 # clear obstacles farther away than 3.0 m ================================================ FILE: mir_navigation/config/pose_local_planner_params.yaml ================================================ base_local_planner: pose_follower/PoseFollower PoseFollower: k_trans: 2.0 k_rot: 1.0 # 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) tolerance_trans: 0.3 # we've reached our goal only if we're within this angular distance tolerance_rot: 0.3 # we've reached our goal only if we're within range for this long and stopped tolerance_timeout: 0.5 # set this to true if you're using a holonomic robot holonomic: false # number of samples (scaling factors of our current desired twist) to check the validity of samples: 10 # go no faster than this max_vel_lin: 0.3 max_vel_th: 0.5 # minimum velocities to keep from getting stuck min_vel_lin: 0.03 min_vel_th: 0.1 # if we're rotating in place, go at least this fast to avoid getting stuck min_in_place_vel_th: 0.1 # when we're near the end and would be trying to go no faster than this translationally, just rotate in place instead in_place_trans_vel: 0.1 # we're "stopped" if we're going slower than these velocities trans_stopped_velocity: 0.03 rot_stopped_velocity: 0.1 # if this is true, we don't care whether we go backwards or forwards allow_backwards: true # if this is true, turn in place to face the new goal instead of arcing toward it turn_in_place_first: true # if turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location max_heading_diff_before_moving: 0.2 ================================================ FILE: mir_navigation/config/rpp_local_planner_params.yaml ================================================ # requires https://github.com/JohnTGZ/regulated_pure_pursuit_controller # # known bugs: # - ignores local costmap (will collide with dynamic obstacles) # - oscillates near goal (https://github.com/JohnTGZ/regulated_pure_pursuit_controller/issues/8) base_local_planner: regulated_pure_pursuit_controller/RegulatedPurePursuitController RegulatedPurePursuitController: # general params #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. min_global_plan_complete_size: 20 # (default: 20) global_plan_prune_distance: 1.0 # Unused. (default: 1.0) # Lookahead use_velocity_scaled_lookahead_dist: false # Whether to use the velocity scaled lookahead distances or constant lookahead_distance. (default: false) # only when false: lookahead_dist: 0.25 # The lookahead distance (m) to use to find the lookahead point. (default: 0.6) # only when true: min_lookahead_dist: 0.3 # The minimum lookahead distance (m) threshold. (default: 0.3) max_lookahead_dist: 0.9 # The maximum lookahead distance (m) threshold. (default: 0.9) lookahead_time: 1.5 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5) # Rotate to heading param - onle one of use_rotate_to_heading and allow_reversing can be set to true 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) # only when true: rotate_to_heading_angular_vel: 1.0 # The angular velocity to use. (default: 1.8) 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) max_angular_accel: 1.5 # Maximum allowable angular acceleration (rad/s/s) while rotating to heading. (default: 3.2) # Reversing - onle one of use_rotate_to_heading and allow_reversing can be set to true 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) # Speed desired_linear_vel: 0.6 # The desired maximum linear velocity (m/s) to use. (default: 0.5) max_angular_vel: 0.8 # (default: 1.5) 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) # Regulated linear velocity scaling use_regulated_linear_velocity_scaling: true # Whether to use the regulated features for path curvature (e.g. slow on high curvature paths). (default: true) # only when true: 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) 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) # Inflation cost scaling (Limit velocity by proximity to obstacles) 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) inflation_cost_scaling_factor: 3.0 # (default: 3.0) # must be > 0 cost_scaling_dist: 0.6 # (default: 0.6) cost_scaling_gain: 1.0 # (default: 1.0) # Collision avoidance 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) goal_dist_tol: 0.25 # (default: 0.25) control_frequency: 20 # (default: 20) transform_tolerance: 0.1 # The TF transform tolerance (seconds). (default: 0.1) ================================================ FILE: mir_navigation/config/sbpl_global_params.yaml ================================================ base_global_planner: SBPLLatticePlanner SBPLLatticePlanner: environment_type: XYThetaLattice planner_type: ARAPlanner allocated_time: 10.0 initial_epsilon: 15.0 forward_search: false nominalvel_mpersecs: 0.8 timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s ================================================ FILE: mir_navigation/config/teb_local_planner_params.yaml ================================================ # NOTE: When using the teb_local_planner, make sure to set the local costmap # resolution high (for example 0.1 m), otherwise the optimization will take # forever (around 10 minutes for each iteration). base_local_planner: teb_local_planner/TebLocalPlannerROS TebLocalPlannerROS: # Trajectory teb_autosize: true # Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended) dt_ref: 0.3 # Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate) dt_hysteresis: 0.1 # Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref 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 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) 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] 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) feasibility_check_no_poses: 5 # Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval global_plan_viapoint_sep: -0.1 # Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled] via_points_ordered: false # If true, the planner adheres to the order of via-points in the storage container 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. 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) # Robot max_vel_x: 0.8 # Maximum translational velocity of the robot max_vel_x_backwards: 0.2 # Maximum translational velocity of the robot for driving backwards max_vel_y: 0.0 # Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) max_vel_theta: 1.0 # Maximum angular velocity of the robot acc_lim_x: 1.5 # Maximum translational acceleration of the robot acc_lim_y: 0.0 # Maximum strafing acceleration of the robot acc_lim_theta: 2.0 # Maximum angular acceleration of the robot min_turning_radius: 0.0 # Minimum turning radius of a carlike robot (diff-drive robot: zero) 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! cmd_angle_instead_rotvel: false # Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance') is_footprint_dynamic: false # If true, update the footprint before checking trajectory feasibility footprint_model: type: "polygon" vertices: [[0.506,-0.32],[0.506,0.32],[-0.454,0.32],[-0.454,-0.32]] # Goal tolerance xy_goal_tolerance: 0.03 # Allowed final euclidean distance to the goal position yaw_goal_tolerance: 0.08 # Allowed final orientation error to the goal orientation 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) # Obstacles min_obstacle_dist: 0.4 # Minimum desired separation from obstacles 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) 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) 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. 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) 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). 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. 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. 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) 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 #costmap_converter_plugin: "" # #costmap_converter_spin_thread: true # #costmap_converter_rate: 5 # # Optimization no_inner_iterations: 5 # Number of solver iterations called in each outerloop iteration no_outer_iterations: 4 # Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations optimization_activate: true # Activate the optimization optimization_verbose: false # Print verbose information penalty_epsilon: 0.1 # Add a small safty margin to penalty functions for hard-constraint approximations weight_max_vel_x: 2.0 # Optimization weight for satisfying the maximum allowed translational velocity weight_max_vel_y: 2.0 # Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots) weight_max_vel_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular velocity weight_acc_lim_x: 1.0 # Optimization weight for satisfying the maximum allowed translational acceleration weight_acc_lim_y: 1.0 # Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots) weight_acc_lim_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular acceleration weight_kinematics_nh: 1000.0 # Optimization weight for satisfying the non-holonomic kinematics weight_kinematics_forward_drive: 1.0 # Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot) weight_kinematics_turning_radius: 1.0 # Optimization weight for enforcing a minimum turning radius (carlike robots) weight_optimaltime: 1.0 # Optimization weight for contracting the trajectory w.r.t transition time weight_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from obstacles weight_inflation: 0.1 # Optimization weight for the inflation penalty (should be small) weight_dynamic_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from dynamic obstacles weight_dynamic_obstacle_inflation: 0.1 # Optimization weight for the inflation penalty of dynamic obstacles (should be small) weight_viapoint: 1.0 # Optimization weight for minimizing the distance to via-points 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. # Homotopy Class Planner # enable_homotopy_class_planning: true # enable_multithreading: true # Activate multiple threading for planning multiple trajectories in parallel # simple_exploration: false # max_number_classes: 2 # Specify the maximum number of allowed alternative homotopy classes (limits computational effort) 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) 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.) selection_obst_cost_scale: 100.0 # Extra scaling of obstacle cost terms just for selecting the 'best' candidate (new_obst_cost: obst_cost*factor) 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) selection_alternative_time_cost: false # If true, time cost is replaced by the total transition time. roadmap_graph_no_samples: 15 # Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off 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) 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!) 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 ================================================ FILE: mir_navigation/launch/hector_mapping.launch ================================================ ================================================ FILE: mir_navigation/launch/move_base.xml ================================================ ================================================ FILE: mir_navigation/launch/start_maps.launch ================================================ ================================================ FILE: mir_navigation/launch/start_planner.launch ================================================ ================================================ FILE: mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m ================================================ % /* % * Copyright (c) 2008, Maxim Likhachev % * All rights reserved. % * % * Redistribution and use in source and binary forms, with or without % * modification, are permitted provided that the following conditions are met: % * % * * Redistributions of source code must retain the above copyright % * notice, this list of conditions and the following disclaimer. % * * Redistributions in binary form must reproduce the above copyright % * notice, this list of conditions and the following disclaimer in the % * documentation and/or other materials provided with the distribution. % * * Neither the name of the Carnegie Mellon University nor the names of its % * contributors may be used to endorse or promote products derived from % * this software without specific prior written permission. % * % * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" % * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE % * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE % * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE % * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR % * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF % * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS % * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN % * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) % * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE % * POSSIBILITY OF SUCH DAMAGE. % */ function[] = genmprim_unicycle_highcost_5cm(outfilename) % %generates motion primitives and saves them into file % %written by Maxim Likhachev %--------------------------------------------------- % %defines UNICYCLE_MPRIM_16DEGS = 1; if UNICYCLE_MPRIM_16DEGS == 1 resolution = 0.05; numberofangles = 16; %preferably a power of 2, definitely multiple of 8 numberofprimsperangle = 7; %multipliers (multiplier is used as costmult*cost) forwardcostmult = 1; backwardcostmult = 40; forwardandturncostmult = 2; sidestepcostmult = 10; turninplacecostmult = 20; %note, what is shown x,y,theta changes (not absolute numbers) %0 degreees basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult %x aligned with the heading of the robot, angles are positive %counterclockwise %0 theta change basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; %1/16 theta change basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; %turn in place basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; %45 degrees basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) %x aligned with the heading of the robot, angles are positive %counterclockwise %0 theta change basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; %1/16 theta change basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; %turn in place basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; %22.5 degrees basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) %x aligned with the heading of the robot, angles are positive %counterclockwise %0 theta change basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; %1/16 theta change basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; %turn in place basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; else fprintf(1, 'ERROR: undefined mprims type\n'); return; end; fout = fopen(outfilename, 'w'); %write the header fprintf(fout, 'resolution_m: %f\n', resolution); fprintf(fout, 'numberofangles: %d\n', numberofangles); fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); %iterate over angles for angleind = 1:numberofangles figure(1); hold off; text(0, 0, int2str(angleind)); %iterate over primitives for primind = 1:numberofprimsperangle fprintf(fout, 'primID: %d\n', primind-1); fprintf(fout, 'startangle_c: %d\n', angleind-1); %current angle currentangle = (angleind-1)*2*pi/numberofangles; currentangle_36000int = round((angleind-1)*36000/numberofangles); %compute which template to use if (rem(currentangle_36000int, 9000) == 0) basemprimendpts_c = basemprimendpts0_c(primind,:); angle = currentangle; elseif (rem(currentangle_36000int, 4500) == 0) basemprimendpts_c = basemprimendpts45_c(primind,:); angle = currentangle - 45*pi/180; elseif (rem(currentangle_36000int-7875, 9000) == 0) basemprimendpts_c = basemprimendpts33p75_c(primind,:); basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well angle = currentangle - 78.75*pi/180; fprintf(1, '78p75\n'); elseif (rem(currentangle_36000int-6750, 9000) == 0) basemprimendpts_c = basemprimendpts22p5_c(primind,:); basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); angle = currentangle - 67.5*pi/180; fprintf(1, '67p5\n'); elseif (rem(currentangle_36000int-5625, 9000) == 0) basemprimendpts_c = basemprimendpts11p25_c(primind,:); basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well angle = currentangle - 56.25*pi/180; fprintf(1, '56p25\n'); elseif (rem(currentangle_36000int-3375, 9000) == 0) basemprimendpts_c = basemprimendpts33p75_c(primind,:); angle = currentangle - 33.75*pi/180; fprintf(1, '33p75\n'); elseif (rem(currentangle_36000int-2250, 9000) == 0) basemprimendpts_c = basemprimendpts22p5_c(primind,:); angle = currentangle - 22.5*pi/180; fprintf(1, '22p5\n'); elseif (rem(currentangle_36000int-1125, 9000) == 0) basemprimendpts_c = basemprimendpts11p25_c(primind,:); angle = currentangle - 11.25*pi/180; fprintf(1, '11p25\n'); else fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); return; end; %now figure out what action will be baseendpose_c = basemprimendpts_c(1:3); additionalactioncostmult = basemprimendpts_c(4); endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); endpose_c = [endx_c endy_c endtheta_c]; fprintf(1, 'rotation angle=%f\n', angle*180/pi); if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); end; %generate intermediate poses (remember they are w.r.t 0,0 (and not %centers of the cells) numofsamples = 10; intermcells_m = zeros(numofsamples,3); if UNICYCLE_MPRIM_16DEGS == 1 startpt = [0 0 currentangle]; endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; intermcells_m = zeros(numofsamples,3); if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward for iind = 1:numofsamples intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... 0]; rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); end; else %unicycle-based move forward or backward R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; l = S(1); tvoverrv = S(2); rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); tv = tvoverrv*rv; if l < 0 fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); l = 0; end; %compute rv %rv = baseendpose_c(3)*2*pi/numberofangles; %compute tv %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) %tv = (tvx + tvy)/2.0; %generate samples for iind = 1:numofsamples dt = (iind-1)/(numofsamples-1); %dtheta = rv*dt + startpt(3); %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... % dtheta]; if(dt*tv < l) intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... startpt(2) + dt*tv*sin(startpt(3)) ... startpt(3)]; else dtheta = rv*(dt - l/tv) + startpt(3); intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... dtheta]; end; end; %correct errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... endpt(2) - intermcells_m(numofsamples,2)]; fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); interpfactor = [0:1/(numofsamples-1):1]; intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; end; end; %write out fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); for interind = 1:size(intermcells_m, 1) fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); end; plot(intermcells_m(:,1), intermcells_m(:,2)); axis([-0.3 0.3 -0.3 0.3]); text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); hold on; end; grid; pause; end; fclose('all'); ================================================ FILE: mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py ================================================ #!/usr/bin/env python3 # # Copyright (c) 2016, David Conner (Christopher Newport University) # Based on genmprim_unicycle.m # Copyright (c) 2008, Maxim Likhachev # All rights reserved. # converted by libermate utility (https://github.com/awesomebytes/libermate) # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # * Neither the name of the Carnegie Mellon University nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. import numpy as np import rospkg # if available import pylab (from matlibplot) matplotlib_found = False try: import matplotlib.pylab as plt matplotlib_found = True except ImportError: pass def matrix_size(mat, elem=None): if not elem: return mat.shape else: return mat.shape[int(elem) - 1] def genmprim_unicycle(outfilename, visualize=False, separate_plots=False): visualize = matplotlib_found and visualize # Plot the primitives # Local Variables: basemprimendpts22p5_c, endtheta_c, endx_c, # baseendpose_c, additionalactioncostmult, fout, numofsamples, # basemprimendpts45_c, primind, basemprimendpts0_c, rv, angle, outfilename, # numberofangles, startpt, UNICYCLE_MPRIM_16DEGS, sidestepcostmult, # rotation_angle, basemprimendpts_c, forwardandturncostmult, # forwardcostmult, turninplacecostmult, endpose_c, backwardcostmult, # interpfactor, S, R, tvoverrv, dtheta, intermcells_m, tv, dt, # currentangle, numberofprimsperangle, resolution, currentangle_36000int, # l, iind, errorxy, interind, endy_c, angleind, endpt # Function calls: plot, cos, pi, grid, figure, genmprim_unicycle, text, # int2str, pause, axis, sin, pinv, fprintf, fclose, rem, zeros, fopen, # round, size # % # %generates motion primitives and saves them into file # % # %written by Maxim Likhachev # %--------------------------------------------------- # % # %defines UNICYCLE_MPRIM_16DEGS = 1.0 if UNICYCLE_MPRIM_16DEGS == 1.0: resolution = 0.05 numberofangles = 16 # %preferably a power of 2, definitely multiple of 8 numberofprimsperangle = 7 # %multipliers (multiplier is used as costmult*cost) forwardcostmult = 1.0 backwardcostmult = 40.0 forwardandturncostmult = 2.0 # sidestepcostmult = 10.0 turninplacecostmult = 20.0 # %note, what is shown x,y,theta changes (not absolute numbers) # %0 degreees basemprimendpts0_c = np.zeros((numberofprimsperangle, 4)) # %x,y,theta,costmult # %x aligned with the heading of the robot, angles are positive # %counterclockwise # %0 theta change basemprimendpts0_c[0, :] = np.array(np.hstack((1.0, 0.0, 0.0, forwardcostmult))) basemprimendpts0_c[1, :] = np.array(np.hstack((8.0, 0.0, 0.0, forwardcostmult))) basemprimendpts0_c[2, :] = np.array(np.hstack((-1.0, 0.0, 0.0, backwardcostmult))) # %1/16 theta change basemprimendpts0_c[3, :] = np.array(np.hstack((8.0, 1.0, 1.0, forwardandturncostmult))) basemprimendpts0_c[4, :] = np.array(np.hstack((8.0, -1.0, -1.0, forwardandturncostmult))) # %turn in place basemprimendpts0_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) basemprimendpts0_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) # %45 degrees basemprimendpts45_c = np.zeros((numberofprimsperangle, 4)) # %x,y,theta,costmult (multiplier is used as costmult*cost) # %x aligned with the heading of the robot, angles are positive # %counterclockwise # %0 theta change basemprimendpts45_c[0, :] = np.array(np.hstack((1.0, 1.0, 0.0, forwardcostmult))) basemprimendpts45_c[1, :] = np.array(np.hstack((6.0, 6.0, 0.0, forwardcostmult))) basemprimendpts45_c[2, :] = np.array(np.hstack((-1.0, -1.0, 0.0, backwardcostmult))) # %1/16 theta change basemprimendpts45_c[3, :] = np.array(np.hstack((5.0, 7.0, 1.0, forwardandturncostmult))) basemprimendpts45_c[4, :] = np.array(np.hstack((7.0, 5.0, -1.0, forwardandturncostmult))) # %turn in place basemprimendpts45_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) basemprimendpts45_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) # %22.5 degrees basemprimendpts22p5_c = np.zeros((numberofprimsperangle, 4)) # %x,y,theta,costmult (multiplier is used as costmult*cost) # %x aligned with the heading of the robot, angles are positive # %counterclockwise # %0 theta change basemprimendpts22p5_c[0, :] = np.array(np.hstack((2.0, 1.0, 0.0, forwardcostmult))) basemprimendpts22p5_c[1, :] = np.array(np.hstack((6.0, 3.0, 0.0, forwardcostmult))) basemprimendpts22p5_c[2, :] = np.array(np.hstack((-2.0, -1.0, 0.0, backwardcostmult))) # %1/16 theta change basemprimendpts22p5_c[3, :] = np.array(np.hstack((5.0, 4.0, 1.0, forwardandturncostmult))) basemprimendpts22p5_c[4, :] = np.array(np.hstack((7.0, 2.0, -1.0, forwardandturncostmult))) # %turn in place basemprimendpts22p5_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) basemprimendpts22p5_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) else: print('ERROR: undefined mprims type\n') return [] fout = open(outfilename, 'w') # %write the header fout.write('resolution_m: %f\n' % (resolution)) fout.write('numberofangles: %d\n' % (numberofangles)) fout.write('totalnumberofprimitives: %d\n' % (numberofprimsperangle * numberofangles)) # %iterate over angles for angleind in np.arange(1.0, (numberofangles) + 1): currentangle = ((angleind - 1) * 2.0 * np.pi) / numberofangles currentangle_36000int = np.round((angleind - 1) * 36000.0 / numberofangles) if visualize: if separate_plots: fig = plt.figure(angleind) plt.title('angle {:2.0f} (= {:3.1f} degrees)'.format(angleind - 1, currentangle_36000int / 100.0)) else: fig = plt.figure(1) plt.axis('equal') plt.axis([-10 * resolution, 10 * resolution, -10 * resolution, 10 * resolution]) ax = fig.add_subplot(1, 1, 1) major_ticks = np.arange(-8 * resolution, 9 * resolution, 4 * resolution) minor_ticks = np.arange(-8 * resolution, 9 * resolution, resolution) ax.set_xticks(major_ticks) ax.set_xticks(minor_ticks, minor=True) ax.set_yticks(major_ticks) ax.set_yticks(minor_ticks, minor=True) ax.grid(which='minor', alpha=0.5) ax.grid(which='major', alpha=0.9) # %iterate over primitives for primind in np.arange(1.0, (numberofprimsperangle) + 1): fout.write('primID: %d\n' % (primind - 1)) fout.write('startangle_c: %d\n' % (angleind - 1)) # %current angle # %compute which template to use if (currentangle_36000int % 9000) == 0: basemprimendpts_c = basemprimendpts0_c[int(primind) - 1, :] angle = currentangle elif (currentangle_36000int % 4500) == 0: basemprimendpts_c = basemprimendpts45_c[int(primind) - 1, :] angle = currentangle - 45.0 * np.pi / 180.0 # commented out because basemprimendpts33p75_c is undefined # elif ((currentangle_36000int - 7875) % 9000) == 0: # basemprimendpts_c = ( # 1 * basemprimendpts33p75_c[primind, :] # ) # 1* to force deep copy to avoid reference update below # basemprimendpts_c[0] = basemprimendpts33p75_c[primind, 1] # # %reverse x and y # basemprimendpts_c[1] = basemprimendpts33p75_c[primind, 0] # basemprimendpts_c[2] = -basemprimendpts33p75_c[primind, 2] # # %reverse the angle as well # angle = currentangle - (78.75 * np.pi) / 180.0 # print('78p75\n') elif ((currentangle_36000int - 6750) % 9000) == 0: basemprimendpts_c = ( 1 * basemprimendpts22p5_c[int(primind) - 1, :] ) # 1* to force deep copy to avoid reference update below basemprimendpts_c[0] = basemprimendpts22p5_c[int(primind) - 1, 1] # %reverse x and y basemprimendpts_c[1] = basemprimendpts22p5_c[int(primind) - 1, 0] basemprimendpts_c[2] = -basemprimendpts22p5_c[int(primind) - 1, 2] # %reverse the angle as well # print( # '%d : %d %d %d onto %d %d %d\n' # % ( # primind - 1, # basemprimendpts22p5_c[int(primind) - 1, 0], # basemprimendpts22p5_c[int(primind) - 1, 1], # basemprimendpts22p5_c[int(primind) - 1, 2], # basemprimendpts_c[0], # basemprimendpts_c[1], # basemprimendpts_c[2], # ) # ) angle = currentangle - (67.5 * np.pi) / 180.0 print('67p5\n') # commented out because basemprimendpts11p25_c is undefined # elif ((currentangle_36000int - 5625) % 9000) == 0: # basemprimendpts_c = ( # 1 * basemprimendpts11p25_c[primind, :] # ) # 1* to force deep copy to avoid reference update below # basemprimendpts_c[0] = basemprimendpts11p25_c[primind, 1] # # %reverse x and y # basemprimendpts_c[1] = basemprimendpts11p25_c[primind, 0] # basemprimendpts_c[2] = -basemprimendpts11p25_c[primind, 2] # # %reverse the angle as well # angle = currentangle - (56.25 * np.pi) / 180.0 # print('56p25\n') # commented out because basemprimendpts33p75_c is undefined # elif ((currentangle_36000int - 3375) % 9000) == 0: # basemprimendpts_c = basemprimendpts33p75_c[int(primind), :] # angle = currentangle - (33.75 * np.pi) / 180.0 # print('33p75\n') elif ((currentangle_36000int - 2250) % 9000) == 0: basemprimendpts_c = basemprimendpts22p5_c[int(primind) - 1, :] angle = currentangle - (22.5 * np.pi) / 180.0 print('22p5\n') # commented out because basemprimendpts11p25_c is undefined # elif ((currentangle_36000int - 1125) % 9000) == 0: # basemprimendpts_c = basemprimendpts11p25_c[int(primind), :] # angle = currentangle - (11.25 * np.pi) / 180.0 # print('11p25\n') else: print('ERROR: invalid angular resolution. angle = %d\n' % currentangle_36000int) return [] # %now figure out what action will be baseendpose_c = basemprimendpts_c[0:3] additionalactioncostmult = basemprimendpts_c[3] endx_c = np.round((baseendpose_c[0] * np.cos(angle)) - (baseendpose_c[1] * np.sin(angle))) endy_c = np.round((baseendpose_c[0] * np.sin(angle)) + (baseendpose_c[1] * np.cos(angle))) endtheta_c = np.fmod(angleind - 1 + baseendpose_c[2], numberofangles) endpose_c = np.array(np.hstack((endx_c, endy_c, endtheta_c))) print("endpose_c=", endpose_c) print(('rotation angle=%f\n' % (angle * 180.0 / np.pi))) # if np.logical_and(baseendpose_c[1] == 0., baseendpose_c[2] == 0.): # %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); # %generate intermediate poses (remember they are w.r.t 0,0 (and not # %centers of the cells) numofsamples = 10 intermcells_m = np.zeros((numofsamples, 3)) if UNICYCLE_MPRIM_16DEGS == 1.0: startpt = np.array(np.hstack((0.0, 0.0, currentangle))) endpt = np.array( np.hstack( ( (endpose_c[0] * resolution), (endpose_c[1] * resolution), ( ((np.fmod(angleind - 1 + baseendpose_c[2], numberofangles)) * 2.0 * np.pi) / numberofangles ), ) ) ) print("startpt =", startpt) print("endpt =", endpt) intermcells_m = np.zeros((numofsamples, 3)) if np.logical_or(np.logical_and(endx_c == 0.0, endy_c == 0.0), baseendpose_c[2] == 0.0): # %turn in place or move forward for iind in np.arange(1.0, (numofsamples) + 1): fraction = float(iind - 1) / (numofsamples - 1) intermcells_m[int(iind) - 1, :] = np.array( ( startpt[0] + (endpt[0] - startpt[0]) * fraction, startpt[1] + (endpt[1] - startpt[1]) * fraction, 0, ) ) rotation_angle = baseendpose_c[2] * (2.0 * np.pi / numberofangles) intermcells_m[int(iind) - 1, 2] = np.fmod(startpt[2] + rotation_angle * fraction, (2.0 * np.pi)) # print " ",iind," of ",numofsamples," fraction=",fraction," rotation=",rotation_angle else: # %unicycle-based move forward or backward (http://sbpl.net/node/53) R = np.array( np.vstack( ( np.hstack((np.cos(startpt[2]), np.sin(endpt[2]) - np.sin(startpt[2]))), np.hstack((np.sin(startpt[2]), -np.cos(endpt[2]) + np.cos(startpt[2]))), ) ) ) S = np.dot(np.linalg.pinv(R), np.array(np.vstack((endpt[0] - startpt[0], endpt[1] - startpt[1])))) l = S[0] tvoverrv = S[1] rv = (baseendpose_c[2] * 2.0 * np.pi / numberofangles) + l / tvoverrv tv = tvoverrv * rv # print "R=\n",R # print "Rpi=\n",np.linalg.pinv(R) # print "S=\n",S # print "l=",l # print "tvoverrv=",tvoverrv # print "rv=",rv # print "tv=",tv if l < 0.0: print(('WARNING: l = %f < 0 -> bad action start/end points\n' % (l))) l = 0.0 # %compute rv # %rv = baseendpose_c(3)*2*pi/numberofangles; # %compute tv # %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) # %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) # %tv = (tvx + tvy)/2.0; # %generate samples for iind in np.arange(1, numofsamples + 1): dt = (iind - 1) / (numofsamples - 1) # %dtheta = rv*dt + startpt(3); # %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... # % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... # % dtheta]; if (dt * tv) < l: intermcells_m[int(iind) - 1, :] = np.array( np.hstack( ( startpt[0] + dt * tv * np.cos(startpt[2]), startpt[1] + dt * tv * np.sin(startpt[2]), startpt[2], ) ) ) else: dtheta = rv * (dt - l / tv) + startpt[2] intermcells_m[int(iind) - 1, :] = np.array( np.hstack( ( startpt[0] + l * np.cos(startpt[2]) + tvoverrv * (np.sin(dtheta) - np.sin(startpt[2])), startpt[1] + l * np.sin(startpt[2]) - tvoverrv * (np.cos(dtheta) - np.cos(startpt[2])), dtheta, ) ) ) # %correct errorxy = np.array( np.hstack( ( endpt[0] - intermcells_m[int(numofsamples) - 1, 0], endpt[1] - intermcells_m[int(numofsamples) - 1, 1], ) ) ) # print('l=%f errx=%f erry=%f\n'%(l, errorxy[0], errorxy[1])) interpfactor = np.array( np.hstack((np.arange(0.0, 1.0 + (1.0 / (numofsamples)), 1.0 / (numofsamples - 1)))) ) # print "intermcells_m=",intermcells_m # print "interp'=",interpfactor.conj().T intermcells_m[:, 0] = intermcells_m[:, 0] + errorxy[0] * interpfactor.conj().T intermcells_m[:, 1] = intermcells_m[:, 1] + errorxy[1] * interpfactor.conj().T # %write out fout.write('endpose_c: %d %d %d\n' % (endpose_c[0], endpose_c[1], endpose_c[2])) fout.write('additionalactioncostmult: %d\n' % (additionalactioncostmult)) fout.write('intermediateposes: %d\n' % (matrix_size(intermcells_m, 1.0))) for interind in np.arange(1.0, (matrix_size(intermcells_m, 1.0)) + 1): fout.write( '%.4f %.4f %.4f\n' % ( intermcells_m[int(interind) - 1, 0], intermcells_m[int(interind) - 1, 1], intermcells_m[int(interind) - 1, 2], ) ) if visualize: plt.plot(intermcells_m[:, 0], intermcells_m[:, 1], linestyle="-", marker="o") plt.text(endpt[0], endpt[1], '{:2.0f}'.format(endpose_c[2])) # if (visualize): # plt.waitforbuttonpress() # uncomment to plot each primitive set one at a time fout.close() if visualize: # plt.waitforbuttonpress() # hold until buttom pressed plt.show() # Keep windows open until the program is terminated return [] if __name__ == "__main__": rospack = rospkg.RosPack() outfilename = rospack.get_path('mir_navigation') + '/mprim/unicycle_highcost_5cm.mprim' genmprim_unicycle(outfilename, visualize=True) ================================================ FILE: mir_navigation/mprim/unicycle_5cm.mprim ================================================ resolution_m: 0.050000 numberofangles: 16 totalnumberofprimitives: 80 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0056 0.0000 0.0000 0.0111 0.0000 0.0000 0.0167 0.0000 0.0000 0.0222 0.0000 0.0000 0.0278 0.0000 0.0000 0.0333 0.0000 0.0000 0.0389 0.0000 0.0000 0.0444 0.0000 0.0000 0.0500 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 8 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0167 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0278 0.0000 0.0000 -0.0333 0.0000 0.0000 -0.0389 0.0000 0.0000 -0.0444 0.0000 0.0000 -0.0500 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 8 1 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 8 -1 -1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0111 0.0056 0.3927 0.0222 0.0111 0.3927 0.0333 0.0167 0.3927 0.0444 0.0222 0.3927 0.0556 0.0278 0.3927 0.0667 0.0333 0.3927 0.0778 0.0389 0.3927 0.0889 0.0444 0.3927 0.1000 0.0500 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0111 -0.0056 0.3927 -0.0222 -0.0111 0.3927 -0.0333 -0.0167 0.3927 -0.0444 -0.0222 0.3927 -0.0556 -0.0278 0.3927 -0.0667 -0.0333 0.3927 -0.0778 -0.0389 0.3927 -0.0889 -0.0444 0.3927 -0.1000 -0.0500 0.3927 primID: 3 startangle_c: 1 endpose_c: 5 4 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 7 2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0056 0.0056 0.7854 0.0111 0.0111 0.7854 0.0167 0.0167 0.7854 0.0222 0.0222 0.7854 0.0278 0.0278 0.7854 0.0333 0.0333 0.7854 0.0389 0.0389 0.7854 0.0444 0.0444 0.7854 0.0500 0.0500 0.7854 primID: 1 startangle_c: 2 endpose_c: 6 6 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0056 -0.0056 0.7854 -0.0111 -0.0111 0.7854 -0.0167 -0.0167 0.7854 -0.0222 -0.0222 0.7854 -0.0278 -0.0278 0.7854 -0.0333 -0.0333 0.7854 -0.0389 -0.0389 0.7854 -0.0444 -0.0444 0.7854 -0.0500 -0.0500 0.7854 primID: 3 startangle_c: 2 endpose_c: 5 7 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 7 5 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0056 0.0111 1.1781 0.0111 0.0222 1.1781 0.0167 0.0333 1.1781 0.0222 0.0444 1.1781 0.0278 0.0556 1.1781 0.0333 0.0667 1.1781 0.0389 0.0778 1.1781 0.0444 0.0889 1.1781 0.0500 0.1000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0056 -0.0111 1.1781 -0.0111 -0.0222 1.1781 -0.0167 -0.0333 1.1781 -0.0222 -0.0444 1.1781 -0.0278 -0.0556 1.1781 -0.0333 -0.0667 1.1781 -0.0389 -0.0778 1.1781 -0.0444 -0.0889 1.1781 -0.0500 -0.1000 1.1781 primID: 3 startangle_c: 3 endpose_c: 4 5 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0056 1.5708 0.0000 0.0111 1.5708 0.0000 0.0167 1.5708 0.0000 0.0222 1.5708 0.0000 0.0278 1.5708 0.0000 0.0333 1.5708 0.0000 0.0389 1.5708 0.0000 0.0444 1.5708 0.0000 0.0500 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 8 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0167 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0278 1.5708 0.0000 -0.0333 1.5708 0.0000 -0.0389 1.5708 0.0000 -0.0444 1.5708 0.0000 -0.0500 1.5708 primID: 3 startangle_c: 4 endpose_c: -1 8 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 1 8 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0000 0.0452 1.5708 -0.0000 0.0904 1.5708 -0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0056 0.0111 1.9635 -0.0111 0.0222 1.9635 -0.0167 0.0333 1.9635 -0.0222 0.0444 1.9635 -0.0278 0.0556 1.9635 -0.0333 0.0667 1.9635 -0.0389 0.0778 1.9635 -0.0444 0.0889 1.9635 -0.0500 0.1000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.9635 0.0056 -0.0111 1.9635 0.0111 -0.0222 1.9635 0.0167 -0.0333 1.9635 0.0222 -0.0444 1.9635 0.0278 -0.0556 1.9635 0.0333 -0.0667 1.9635 0.0389 -0.0778 1.9635 0.0444 -0.0889 1.9635 0.0500 -0.1000 1.9635 primID: 3 startangle_c: 5 endpose_c: -4 5 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0056 0.0056 2.3562 -0.0111 0.0111 2.3562 -0.0167 0.0167 2.3562 -0.0222 0.0222 2.3562 -0.0278 0.0278 2.3562 -0.0333 0.0333 2.3562 -0.0389 0.0389 2.3562 -0.0444 0.0444 2.3562 -0.0500 0.0500 2.3562 primID: 1 startangle_c: 6 endpose_c: -6 6 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 2.3562 0.0056 -0.0056 2.3562 0.0111 -0.0111 2.3562 0.0167 -0.0167 2.3562 0.0222 -0.0222 2.3562 0.0278 -0.0278 2.3562 0.0333 -0.0333 2.3562 0.0389 -0.0389 2.3562 0.0444 -0.0444 2.3562 0.0500 -0.0500 2.3562 primID: 3 startangle_c: 6 endpose_c: -7 5 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -5 7 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0111 0.0056 2.7489 -0.0222 0.0111 2.7489 -0.0333 0.0167 2.7489 -0.0444 0.0222 2.7489 -0.0556 0.0278 2.7489 -0.0667 0.0333 2.7489 -0.0778 0.0389 2.7489 -0.0889 0.0444 2.7489 -0.1000 0.0500 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 2.7489 0.0111 -0.0056 2.7489 0.0222 -0.0111 2.7489 0.0333 -0.0167 2.7489 0.0444 -0.0222 2.7489 0.0556 -0.0278 2.7489 0.0667 -0.0333 2.7489 0.0778 -0.0389 2.7489 0.0889 -0.0444 2.7489 0.1000 -0.0500 2.7489 primID: 3 startangle_c: 7 endpose_c: -5 4 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -7 2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0278 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0389 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0500 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -8 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.1416 0.0056 0.0000 3.1416 0.0111 0.0000 3.1416 0.0167 0.0000 3.1416 0.0222 0.0000 3.1416 0.0278 0.0000 3.1416 0.0333 0.0000 3.1416 0.0389 0.0000 3.1416 0.0444 0.0000 3.1416 0.0500 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -8 -1 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -8 1 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0111 -0.0056 3.5343 -0.0222 -0.0111 3.5343 -0.0333 -0.0167 3.5343 -0.0444 -0.0222 3.5343 -0.0556 -0.0278 3.5343 -0.0667 -0.0333 3.5343 -0.0778 -0.0389 3.5343 -0.0889 -0.0444 3.5343 -0.1000 -0.0500 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.5343 0.0111 0.0056 3.5343 0.0222 0.0111 3.5343 0.0333 0.0167 3.5343 0.0444 0.0222 3.5343 0.0556 0.0278 3.5343 0.0667 0.0333 3.5343 0.0778 0.0389 3.5343 0.0889 0.0444 3.5343 0.1000 0.0500 3.5343 primID: 3 startangle_c: 9 endpose_c: -5 -4 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -7 -2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0056 -0.0056 3.9270 -0.0111 -0.0111 3.9270 -0.0167 -0.0167 3.9270 -0.0222 -0.0222 3.9270 -0.0278 -0.0278 3.9270 -0.0333 -0.0333 3.9270 -0.0389 -0.0389 3.9270 -0.0444 -0.0444 3.9270 -0.0500 -0.0500 3.9270 primID: 1 startangle_c: 10 endpose_c: -6 -6 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.9270 0.0056 0.0056 3.9270 0.0111 0.0111 3.9270 0.0167 0.0167 3.9270 0.0222 0.0222 3.9270 0.0278 0.0278 3.9270 0.0333 0.0333 3.9270 0.0389 0.0389 3.9270 0.0444 0.0444 3.9270 0.0500 0.0500 3.9270 primID: 3 startangle_c: 10 endpose_c: -5 -7 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -7 -5 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0056 -0.0111 4.3197 -0.0111 -0.0222 4.3197 -0.0167 -0.0333 4.3197 -0.0222 -0.0444 4.3197 -0.0278 -0.0556 4.3197 -0.0333 -0.0667 4.3197 -0.0389 -0.0778 4.3197 -0.0444 -0.0889 4.3197 -0.0500 -0.1000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 4.3197 0.0056 0.0111 4.3197 0.0111 0.0222 4.3197 0.0167 0.0333 4.3197 0.0222 0.0444 4.3197 0.0278 0.0556 4.3197 0.0333 0.0667 4.3197 0.0389 0.0778 4.3197 0.0444 0.0889 4.3197 0.0500 0.1000 4.3197 primID: 3 startangle_c: 11 endpose_c: -4 -5 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0278 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0389 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0500 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -8 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0056 4.7124 0.0000 0.0111 4.7124 0.0000 0.0167 4.7124 0.0000 0.0222 4.7124 0.0000 0.0278 4.7124 0.0000 0.0333 4.7124 0.0000 0.0389 4.7124 0.0000 0.0444 4.7124 0.0000 0.0500 4.7124 primID: 3 startangle_c: 12 endpose_c: 1 -8 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -1 -8 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0056 -0.0111 5.1051 0.0111 -0.0222 5.1051 0.0167 -0.0333 5.1051 0.0222 -0.0444 5.1051 0.0278 -0.0556 5.1051 0.0333 -0.0667 5.1051 0.0389 -0.0778 5.1051 0.0444 -0.0889 5.1051 0.0500 -0.1000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0056 0.0111 5.1051 -0.0111 0.0222 5.1051 -0.0167 0.0333 5.1051 -0.0222 0.0444 5.1051 -0.0278 0.0556 5.1051 -0.0333 0.0667 5.1051 -0.0389 0.0778 5.1051 -0.0444 0.0889 5.1051 -0.0500 0.1000 5.1051 primID: 3 startangle_c: 13 endpose_c: 4 -5 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0056 -0.0056 5.4978 0.0111 -0.0111 5.4978 0.0167 -0.0167 5.4978 0.0222 -0.0222 5.4978 0.0278 -0.0278 5.4978 0.0333 -0.0333 5.4978 0.0389 -0.0389 5.4978 0.0444 -0.0444 5.4978 0.0500 -0.0500 5.4978 primID: 1 startangle_c: 14 endpose_c: 6 -6 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0056 0.0056 5.4978 -0.0111 0.0111 5.4978 -0.0167 0.0167 5.4978 -0.0222 0.0222 5.4978 -0.0278 0.0278 5.4978 -0.0333 0.0333 5.4978 -0.0389 0.0389 5.4978 -0.0444 0.0444 5.4978 -0.0500 0.0500 5.4978 primID: 3 startangle_c: 14 endpose_c: 7 -5 15 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 5 -7 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0111 -0.0056 5.8905 0.0222 -0.0111 5.8905 0.0333 -0.0167 5.8905 0.0444 -0.0222 5.8905 0.0556 -0.0278 5.8905 0.0667 -0.0333 5.8905 0.0778 -0.0389 5.8905 0.0889 -0.0444 5.8905 0.1000 -0.0500 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0111 0.0056 5.8905 -0.0222 0.0111 5.8905 -0.0333 0.0167 5.8905 -0.0444 0.0222 5.8905 -0.0556 0.0278 5.8905 -0.0667 0.0333 5.8905 -0.0778 0.0389 5.8905 -0.0889 0.0444 5.8905 -0.1000 0.0500 5.8905 primID: 3 startangle_c: 15 endpose_c: 5 -4 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 7 -2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 ================================================ FILE: mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim ================================================ resolution_m: 0.050000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0056 0.0000 0.0000 0.0111 0.0000 0.0000 0.0167 0.0000 0.0000 0.0222 0.0000 0.0000 0.0278 0.0000 0.0000 0.0333 0.0000 0.0000 0.0389 0.0000 0.0000 0.0444 0.0000 0.0000 0.0500 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 8 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0167 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0278 0.0000 0.0000 -0.0333 0.0000 0.0000 -0.0389 0.0000 0.0000 -0.0444 0.0000 0.0000 -0.0500 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 8 1 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 8 -1 -1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0111 0.0056 0.3927 0.0222 0.0111 0.3927 0.0333 0.0167 0.3927 0.0444 0.0222 0.3927 0.0556 0.0278 0.3927 0.0667 0.0333 0.3927 0.0778 0.0389 0.3927 0.0889 0.0444 0.3927 0.1000 0.0500 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0111 -0.0056 0.3927 -0.0222 -0.0111 0.3927 -0.0333 -0.0167 0.3927 -0.0444 -0.0222 0.3927 -0.0556 -0.0278 0.3927 -0.0667 -0.0333 0.3927 -0.0778 -0.0389 0.3927 -0.0889 -0.0444 0.3927 -0.1000 -0.0500 0.3927 primID: 3 startangle_c: 1 endpose_c: 5 4 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 7 2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 -0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0056 0.0056 0.7854 0.0111 0.0111 0.7854 0.0167 0.0167 0.7854 0.0222 0.0222 0.7854 0.0278 0.0278 0.7854 0.0333 0.0333 0.7854 0.0389 0.0389 0.7854 0.0444 0.0444 0.7854 0.0500 0.0500 0.7854 primID: 1 startangle_c: 2 endpose_c: 6 6 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0056 -0.0056 0.7854 -0.0111 -0.0111 0.7854 -0.0167 -0.0167 0.7854 -0.0222 -0.0222 0.7854 -0.0278 -0.0278 0.7854 -0.0333 -0.0333 0.7854 -0.0389 -0.0389 0.7854 -0.0444 -0.0444 0.7854 -0.0500 -0.0500 0.7854 primID: 3 startangle_c: 2 endpose_c: 5 7 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 7 5 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0056 0.0111 1.1781 0.0111 0.0222 1.1781 0.0167 0.0333 1.1781 0.0222 0.0444 1.1781 0.0278 0.0556 1.1781 0.0333 0.0667 1.1781 0.0389 0.0778 1.1781 0.0444 0.0889 1.1781 0.0500 0.1000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0056 -0.0111 1.1781 -0.0111 -0.0222 1.1781 -0.0167 -0.0333 1.1781 -0.0222 -0.0444 1.1781 -0.0278 -0.0556 1.1781 -0.0333 -0.0667 1.1781 -0.0389 -0.0778 1.1781 -0.0444 -0.0889 1.1781 -0.0500 -0.1000 1.1781 primID: 3 startangle_c: 3 endpose_c: 4 5 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0056 1.5708 0.0000 0.0111 1.5708 0.0000 0.0167 1.5708 0.0000 0.0222 1.5708 0.0000 0.0278 1.5708 0.0000 0.0333 1.5708 0.0000 0.0389 1.5708 0.0000 0.0444 1.5708 0.0000 0.0500 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 8 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0167 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0278 1.5708 0.0000 -0.0333 1.5708 0.0000 -0.0389 1.5708 0.0000 -0.0444 1.5708 0.0000 -0.0500 1.5708 primID: 3 startangle_c: 4 endpose_c: -1 8 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 1 8 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0056 0.0111 1.9635 -0.0111 0.0222 1.9635 -0.0167 0.0333 1.9635 -0.0222 0.0444 1.9635 -0.0278 0.0556 1.9635 -0.0333 0.0667 1.9635 -0.0389 0.0778 1.9635 -0.0444 0.0889 1.9635 -0.0500 0.1000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 1.9635 0.0056 -0.0111 1.9635 0.0111 -0.0222 1.9635 0.0167 -0.0333 1.9635 0.0222 -0.0444 1.9635 0.0278 -0.0556 1.9635 0.0333 -0.0667 1.9635 0.0389 -0.0778 1.9635 0.0444 -0.0889 1.9635 0.0500 -0.1000 1.9635 primID: 3 startangle_c: 5 endpose_c: -4 5 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0056 0.0056 2.3562 -0.0111 0.0111 2.3562 -0.0167 0.0167 2.3562 -0.0222 0.0222 2.3562 -0.0278 0.0278 2.3562 -0.0333 0.0333 2.3562 -0.0389 0.0389 2.3562 -0.0444 0.0444 2.3562 -0.0500 0.0500 2.3562 primID: 1 startangle_c: 6 endpose_c: -6 6 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 2.3562 0.0056 -0.0056 2.3562 0.0111 -0.0111 2.3562 0.0167 -0.0167 2.3562 0.0222 -0.0222 2.3562 0.0278 -0.0278 2.3562 0.0333 -0.0333 2.3562 0.0389 -0.0389 2.3562 0.0444 -0.0444 2.3562 0.0500 -0.0500 2.3562 primID: 3 startangle_c: 6 endpose_c: -7 5 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -5 7 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0111 0.0056 2.7489 -0.0222 0.0111 2.7489 -0.0333 0.0167 2.7489 -0.0444 0.0222 2.7489 -0.0556 0.0278 2.7489 -0.0667 0.0333 2.7489 -0.0778 0.0389 2.7489 -0.0889 0.0444 2.7489 -0.1000 0.0500 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 2.7489 0.0111 -0.0056 2.7489 0.0222 -0.0111 2.7489 0.0333 -0.0167 2.7489 0.0444 -0.0222 2.7489 0.0556 -0.0278 2.7489 0.0667 -0.0333 2.7489 0.0778 -0.0389 2.7489 0.0889 -0.0444 2.7489 0.1000 -0.0500 2.7489 primID: 3 startangle_c: 7 endpose_c: -5 4 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -7 2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0278 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0389 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0500 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -8 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.1416 0.0056 0.0000 3.1416 0.0111 0.0000 3.1416 0.0167 0.0000 3.1416 0.0222 0.0000 3.1416 0.0278 0.0000 3.1416 0.0333 0.0000 3.1416 0.0389 0.0000 3.1416 0.0444 0.0000 3.1416 0.0500 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -8 -1 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -8 1 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0111 -0.0056 3.5343 -0.0222 -0.0111 3.5343 -0.0333 -0.0167 3.5343 -0.0444 -0.0222 3.5343 -0.0556 -0.0278 3.5343 -0.0667 -0.0333 3.5343 -0.0778 -0.0389 3.5343 -0.0889 -0.0444 3.5343 -0.1000 -0.0500 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.5343 0.0111 0.0056 3.5343 0.0222 0.0111 3.5343 0.0333 0.0167 3.5343 0.0444 0.0222 3.5343 0.0556 0.0278 3.5343 0.0667 0.0333 3.5343 0.0778 0.0389 3.5343 0.0889 0.0444 3.5343 0.1000 0.0500 3.5343 primID: 3 startangle_c: 9 endpose_c: -5 -4 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -7 -2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0056 -0.0056 3.9270 -0.0111 -0.0111 3.9270 -0.0167 -0.0167 3.9270 -0.0222 -0.0222 3.9270 -0.0278 -0.0278 3.9270 -0.0333 -0.0333 3.9270 -0.0389 -0.0389 3.9270 -0.0444 -0.0444 3.9270 -0.0500 -0.0500 3.9270 primID: 1 startangle_c: 10 endpose_c: -6 -6 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 3.9270 0.0056 0.0056 3.9270 0.0111 0.0111 3.9270 0.0167 0.0167 3.9270 0.0222 0.0222 3.9270 0.0278 0.0278 3.9270 0.0333 0.0333 3.9270 0.0389 0.0389 3.9270 0.0444 0.0444 3.9270 0.0500 0.0500 3.9270 primID: 3 startangle_c: 10 endpose_c: -5 -7 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -7 -5 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0056 -0.0111 4.3197 -0.0111 -0.0222 4.3197 -0.0167 -0.0333 4.3197 -0.0222 -0.0444 4.3197 -0.0278 -0.0556 4.3197 -0.0333 -0.0667 4.3197 -0.0389 -0.0778 4.3197 -0.0444 -0.0889 4.3197 -0.0500 -0.1000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 4.3197 0.0056 0.0111 4.3197 0.0111 0.0222 4.3197 0.0167 0.0333 4.3197 0.0222 0.0444 4.3197 0.0278 0.0556 4.3197 0.0333 0.0667 4.3197 0.0389 0.0778 4.3197 0.0444 0.0889 4.3197 0.0500 0.1000 4.3197 primID: 3 startangle_c: 11 endpose_c: -4 -5 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0278 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0389 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0500 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -8 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0056 4.7124 0.0000 0.0111 4.7124 0.0000 0.0167 4.7124 0.0000 0.0222 4.7124 0.0000 0.0278 4.7124 0.0000 0.0333 4.7124 0.0000 0.0389 4.7124 0.0000 0.0444 4.7124 0.0000 0.0500 4.7124 primID: 3 startangle_c: 12 endpose_c: 1 -8 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0452 4.7124 0.0000 -0.0904 4.7124 0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -1 -8 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0056 -0.0111 5.1051 0.0111 -0.0222 5.1051 0.0167 -0.0333 5.1051 0.0222 -0.0444 5.1051 0.0278 -0.0556 5.1051 0.0333 -0.0667 5.1051 0.0389 -0.0778 5.1051 0.0444 -0.0889 5.1051 0.0500 -0.1000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0056 0.0111 5.1051 -0.0111 0.0222 5.1051 -0.0167 0.0333 5.1051 -0.0222 0.0444 5.1051 -0.0278 0.0556 5.1051 -0.0333 0.0667 5.1051 -0.0389 0.0778 5.1051 -0.0444 0.0889 5.1051 -0.0500 0.1000 5.1051 primID: 3 startangle_c: 13 endpose_c: 4 -5 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0056 -0.0056 5.4978 0.0111 -0.0111 5.4978 0.0167 -0.0167 5.4978 0.0222 -0.0222 5.4978 0.0278 -0.0278 5.4978 0.0333 -0.0333 5.4978 0.0389 -0.0389 5.4978 0.0444 -0.0444 5.4978 0.0500 -0.0500 5.4978 primID: 1 startangle_c: 14 endpose_c: 6 -6 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0056 0.0056 5.4978 -0.0111 0.0111 5.4978 -0.0167 0.0167 5.4978 -0.0222 0.0222 5.4978 -0.0278 0.0278 5.4978 -0.0333 0.0333 5.4978 -0.0389 0.0389 5.4978 -0.0444 0.0444 5.4978 -0.0500 0.0500 5.4978 primID: 3 startangle_c: 14 endpose_c: 7 -5 15 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 5 -7 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0111 -0.0056 5.8905 0.0222 -0.0111 5.8905 0.0333 -0.0167 5.8905 0.0444 -0.0222 5.8905 0.0556 -0.0278 5.8905 0.0667 -0.0333 5.8905 0.0778 -0.0389 5.8905 0.0889 -0.0444 5.8905 0.1000 -0.0500 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 5 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0111 0.0056 5.8905 -0.0222 0.0111 5.8905 -0.0333 0.0167 5.8905 -0.0444 0.0222 5.8905 -0.0556 0.0278 5.8905 -0.0667 0.0333 5.8905 -0.0778 0.0389 5.8905 -0.0889 0.0444 5.8905 -0.1000 0.0500 5.8905 primID: 3 startangle_c: 15 endpose_c: 5 -4 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 7 -2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim ================================================ resolution_m: 0.050000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0056 0.0000 0.0000 0.0111 0.0000 0.0000 0.0167 0.0000 0.0000 0.0222 0.0000 0.0000 0.0278 0.0000 0.0000 0.0333 0.0000 0.0000 0.0389 0.0000 0.0000 0.0444 0.0000 0.0000 0.0500 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 8 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0167 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0278 0.0000 0.0000 -0.0333 0.0000 0.0000 -0.0389 0.0000 0.0000 -0.0444 0.0000 0.0000 -0.0500 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 8 1 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 8 -1 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0111 0.0056 0.3927 0.0222 0.0111 0.3927 0.0333 0.0167 0.3927 0.0444 0.0222 0.3927 0.0556 0.0278 0.3927 0.0667 0.0333 0.3927 0.0778 0.0389 0.3927 0.0889 0.0444 0.3927 0.1000 0.0500 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0111 -0.0056 0.3927 -0.0222 -0.0111 0.3927 -0.0333 -0.0167 0.3927 -0.0444 -0.0222 0.3927 -0.0556 -0.0278 0.3927 -0.0667 -0.0333 0.3927 -0.0778 -0.0389 0.3927 -0.0889 -0.0444 0.3927 -0.1000 -0.0500 0.3927 primID: 3 startangle_c: 1 endpose_c: 5 4 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 7 2 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 -0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0056 0.0056 0.7854 0.0111 0.0111 0.7854 0.0167 0.0167 0.7854 0.0222 0.0222 0.7854 0.0278 0.0278 0.7854 0.0333 0.0333 0.7854 0.0389 0.0389 0.7854 0.0444 0.0444 0.7854 0.0500 0.0500 0.7854 primID: 1 startangle_c: 2 endpose_c: 6 6 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0056 -0.0056 0.7854 -0.0111 -0.0111 0.7854 -0.0167 -0.0167 0.7854 -0.0222 -0.0222 0.7854 -0.0278 -0.0278 0.7854 -0.0333 -0.0333 0.7854 -0.0389 -0.0389 0.7854 -0.0444 -0.0444 0.7854 -0.0500 -0.0500 0.7854 primID: 3 startangle_c: 2 endpose_c: 5 7 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 7 5 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0056 0.0111 1.1781 0.0111 0.0222 1.1781 0.0167 0.0333 1.1781 0.0222 0.0444 1.1781 0.0278 0.0556 1.1781 0.0333 0.0667 1.1781 0.0389 0.0778 1.1781 0.0444 0.0889 1.1781 0.0500 0.1000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0056 -0.0111 1.1781 -0.0111 -0.0222 1.1781 -0.0167 -0.0333 1.1781 -0.0222 -0.0444 1.1781 -0.0278 -0.0556 1.1781 -0.0333 -0.0667 1.1781 -0.0389 -0.0778 1.1781 -0.0444 -0.0889 1.1781 -0.0500 -0.1000 1.1781 primID: 3 startangle_c: 3 endpose_c: 4 5 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 2 7 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0056 1.5708 0.0000 0.0111 1.5708 0.0000 0.0167 1.5708 0.0000 0.0222 1.5708 0.0000 0.0278 1.5708 0.0000 0.0333 1.5708 0.0000 0.0389 1.5708 0.0000 0.0444 1.5708 0.0000 0.0500 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 8 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0167 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0278 1.5708 0.0000 -0.0333 1.5708 0.0000 -0.0389 1.5708 0.0000 -0.0444 1.5708 0.0000 -0.0500 1.5708 primID: 3 startangle_c: 4 endpose_c: -1 8 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 1 8 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0056 0.0111 1.9635 -0.0111 0.0222 1.9635 -0.0167 0.0333 1.9635 -0.0222 0.0444 1.9635 -0.0278 0.0556 1.9635 -0.0333 0.0667 1.9635 -0.0389 0.0778 1.9635 -0.0444 0.0889 1.9635 -0.0500 0.1000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0056 -0.0111 1.9635 0.0111 -0.0222 1.9635 0.0167 -0.0333 1.9635 0.0222 -0.0444 1.9635 0.0278 -0.0556 1.9635 0.0333 -0.0667 1.9635 0.0389 -0.0778 1.9635 0.0444 -0.0889 1.9635 0.0500 -0.1000 1.9635 primID: 3 startangle_c: 5 endpose_c: -4 5 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -2 7 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0056 0.0056 2.3562 -0.0111 0.0111 2.3562 -0.0167 0.0167 2.3562 -0.0222 0.0222 2.3562 -0.0278 0.0278 2.3562 -0.0333 0.0333 2.3562 -0.0389 0.0389 2.3562 -0.0444 0.0444 2.3562 -0.0500 0.0500 2.3562 primID: 1 startangle_c: 6 endpose_c: -6 6 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0056 -0.0056 2.3562 0.0111 -0.0111 2.3562 0.0167 -0.0167 2.3562 0.0222 -0.0222 2.3562 0.0278 -0.0278 2.3562 0.0333 -0.0333 2.3562 0.0389 -0.0389 2.3562 0.0444 -0.0444 2.3562 0.0500 -0.0500 2.3562 primID: 3 startangle_c: 6 endpose_c: -7 5 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -5 7 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0111 0.0056 2.7489 -0.0222 0.0111 2.7489 -0.0333 0.0167 2.7489 -0.0444 0.0222 2.7489 -0.0556 0.0278 2.7489 -0.0667 0.0333 2.7489 -0.0778 0.0389 2.7489 -0.0889 0.0444 2.7489 -0.1000 0.0500 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0111 -0.0056 2.7489 0.0222 -0.0111 2.7489 0.0333 -0.0167 2.7489 0.0444 -0.0222 2.7489 0.0556 -0.0278 2.7489 0.0667 -0.0333 2.7489 0.0778 -0.0389 2.7489 0.0889 -0.0444 2.7489 0.1000 -0.0500 2.7489 primID: 3 startangle_c: 7 endpose_c: -5 4 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -7 2 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0278 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0389 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0500 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -8 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0056 0.0000 3.1416 0.0111 0.0000 3.1416 0.0167 0.0000 3.1416 0.0222 0.0000 3.1416 0.0278 0.0000 3.1416 0.0333 0.0000 3.1416 0.0389 0.0000 3.1416 0.0444 0.0000 3.1416 0.0500 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -8 -1 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -8 1 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0111 -0.0056 3.5343 -0.0222 -0.0111 3.5343 -0.0333 -0.0167 3.5343 -0.0444 -0.0222 3.5343 -0.0556 -0.0278 3.5343 -0.0667 -0.0333 3.5343 -0.0778 -0.0389 3.5343 -0.0889 -0.0444 3.5343 -0.1000 -0.0500 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0111 0.0056 3.5343 0.0222 0.0111 3.5343 0.0333 0.0167 3.5343 0.0444 0.0222 3.5343 0.0556 0.0278 3.5343 0.0667 0.0333 3.5343 0.0778 0.0389 3.5343 0.0889 0.0444 3.5343 0.1000 0.0500 3.5343 primID: 3 startangle_c: 9 endpose_c: -5 -4 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -7 -2 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0056 -0.0056 3.9270 -0.0111 -0.0111 3.9270 -0.0167 -0.0167 3.9270 -0.0222 -0.0222 3.9270 -0.0278 -0.0278 3.9270 -0.0333 -0.0333 3.9270 -0.0389 -0.0389 3.9270 -0.0444 -0.0444 3.9270 -0.0500 -0.0500 3.9270 primID: 1 startangle_c: 10 endpose_c: -6 -6 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0056 0.0056 3.9270 0.0111 0.0111 3.9270 0.0167 0.0167 3.9270 0.0222 0.0222 3.9270 0.0278 0.0278 3.9270 0.0333 0.0333 3.9270 0.0389 0.0389 3.9270 0.0444 0.0444 3.9270 0.0500 0.0500 3.9270 primID: 3 startangle_c: 10 endpose_c: -5 -7 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -7 -5 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0056 -0.0111 4.3197 -0.0111 -0.0222 4.3197 -0.0167 -0.0333 4.3197 -0.0222 -0.0444 4.3197 -0.0278 -0.0556 4.3197 -0.0333 -0.0667 4.3197 -0.0389 -0.0778 4.3197 -0.0444 -0.0889 4.3197 -0.0500 -0.1000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0056 0.0111 4.3197 0.0111 0.0222 4.3197 0.0167 0.0333 4.3197 0.0222 0.0444 4.3197 0.0278 0.0556 4.3197 0.0333 0.0667 4.3197 0.0389 0.0778 4.3197 0.0444 0.0889 4.3197 0.0500 0.1000 4.3197 primID: 3 startangle_c: 11 endpose_c: -4 -5 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -2 -7 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0278 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0389 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0500 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -8 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0056 4.7124 0.0000 0.0111 4.7124 0.0000 0.0167 4.7124 0.0000 0.0222 4.7124 0.0000 0.0278 4.7124 0.0000 0.0333 4.7124 0.0000 0.0389 4.7124 0.0000 0.0444 4.7124 0.0000 0.0500 4.7124 primID: 3 startangle_c: 12 endpose_c: 1 -8 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0452 4.7124 0.0000 -0.0904 4.7124 0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -1 -8 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0056 -0.0111 5.1051 0.0111 -0.0222 5.1051 0.0167 -0.0333 5.1051 0.0222 -0.0444 5.1051 0.0278 -0.0556 5.1051 0.0333 -0.0667 5.1051 0.0389 -0.0778 5.1051 0.0444 -0.0889 5.1051 0.0500 -0.1000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0056 0.0111 5.1051 -0.0111 0.0222 5.1051 -0.0167 0.0333 5.1051 -0.0222 0.0444 5.1051 -0.0278 0.0556 5.1051 -0.0333 0.0667 5.1051 -0.0389 0.0778 5.1051 -0.0444 0.0889 5.1051 -0.0500 0.1000 5.1051 primID: 3 startangle_c: 13 endpose_c: 4 -5 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 2 -7 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0056 -0.0056 5.4978 0.0111 -0.0111 5.4978 0.0167 -0.0167 5.4978 0.0222 -0.0222 5.4978 0.0278 -0.0278 5.4978 0.0333 -0.0333 5.4978 0.0389 -0.0389 5.4978 0.0444 -0.0444 5.4978 0.0500 -0.0500 5.4978 primID: 1 startangle_c: 14 endpose_c: 6 -6 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0056 0.0056 5.4978 -0.0111 0.0111 5.4978 -0.0167 0.0167 5.4978 -0.0222 0.0222 5.4978 -0.0278 0.0278 5.4978 -0.0333 0.0333 5.4978 -0.0389 0.0389 5.4978 -0.0444 0.0444 5.4978 -0.0500 0.0500 5.4978 primID: 3 startangle_c: 14 endpose_c: 7 -5 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 5 -7 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0111 -0.0056 5.8905 0.0222 -0.0111 5.8905 0.0333 -0.0167 5.8905 0.0444 -0.0222 5.8905 0.0556 -0.0278 5.8905 0.0667 -0.0333 5.8905 0.0778 -0.0389 5.8905 0.0889 -0.0444 5.8905 0.1000 -0.0500 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0111 0.0056 5.8905 -0.0222 0.0111 5.8905 -0.0333 0.0167 5.8905 -0.0444 0.0222 5.8905 -0.0556 0.0278 5.8905 -0.0667 0.0333 5.8905 -0.0778 0.0389 5.8905 -0.0889 0.0444 5.8905 -0.1000 0.0500 5.8905 primID: 3 startangle_c: 15 endpose_c: 5 -4 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 7 -2 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 200 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim ================================================ resolution_m: 0.050000 numberofangles: 16 totalnumberofprimitives: 160 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0056 0.0000 0.0000 0.0111 0.0000 0.0000 0.0167 0.0000 0.0000 0.0222 0.0000 0.0000 0.0278 0.0000 0.0000 0.0333 0.0000 0.0000 0.0389 0.0000 0.0000 0.0444 0.0000 0.0000 0.0500 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 8 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: 16 4 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0904 0.0095 0.0349 0.1806 0.0222 0.0699 0.2707 0.0381 0.1048 0.3604 0.0572 0.1398 0.4496 0.0795 0.1747 0.5383 0.1050 0.2097 0.6264 0.1335 0.2446 0.7136 0.1652 0.2796 0.8000 0.2000 0.3145 primID: 3 startangle_c: 0 endpose_c: 16 -4 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0904 -0.0095 -0.0349 0.1806 -0.0222 -0.0699 0.2707 -0.0381 -0.1048 0.3604 -0.0572 -0.1398 0.4496 -0.0795 -0.1747 0.5383 -0.1050 -0.2097 0.6264 -0.1335 -0.2446 0.7136 -0.1652 -0.2796 0.8000 -0.2000 -0.3145 primID: 4 startangle_c: 0 endpose_c: 5 2 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 0.0280 0.0085 0.0223 0.0559 0.0177 0.0445 0.0839 0.0275 0.0668 0.1117 0.0380 0.0890 0.1396 0.0491 0.1113 0.1673 0.0609 0.1335 0.1950 0.0733 0.1558 0.2225 0.0863 0.1781 0.2500 0.1000 0.2003 primID: 5 startangle_c: 0 endpose_c: 5 -2 -1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 0.0280 -0.0085 -0.0223 0.0559 -0.0177 -0.0445 0.0839 -0.0275 -0.0668 0.1117 -0.0380 -0.0890 0.1396 -0.0491 -0.1113 0.1673 -0.0609 -0.1335 0.1950 -0.0733 -0.1558 0.2225 -0.0863 -0.1781 0.2500 -0.1000 -0.2003 primID: 6 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 7 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 8 startangle_c: 0 endpose_c: 8 1 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0056 0.0000 0.0889 0.0111 0.0000 0.1333 0.0167 0.0000 0.1778 0.0222 0.0000 0.2222 0.0278 0.0000 0.2667 0.0333 0.0000 0.3111 0.0389 0.0000 0.3556 0.0444 0.0000 0.4000 0.0500 0.0000 primID: 9 startangle_c: 0 endpose_c: 8 -1 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 -0.0056 0.0000 0.0889 -0.0111 0.0000 0.1333 -0.0167 0.0000 0.1778 -0.0222 0.0000 0.2222 -0.0278 0.0000 0.2667 -0.0333 0.0000 0.3111 -0.0389 0.0000 0.3556 -0.0444 0.0000 0.4000 -0.0500 0.0000 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0111 0.0056 0.3927 0.0222 0.0111 0.3927 0.0333 0.0167 0.3927 0.0444 0.0222 0.3927 0.0556 0.0278 0.3927 0.0667 0.0333 0.3927 0.0778 0.0389 0.3927 0.0889 0.0444 0.3927 0.1000 0.0500 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: 13 9 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0793 0.0378 0.4329 0.1572 0.0787 0.4732 0.2334 0.1229 0.5134 0.3079 0.1701 0.5537 0.3805 0.2204 0.5939 0.4512 0.2736 0.6342 0.5197 0.3296 0.6744 0.5860 0.3885 0.7147 0.6500 0.4500 0.7549 primID: 3 startangle_c: 1 endpose_c: 14 3 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0741 0.0305 0.3774 0.1493 0.0582 0.3302 0.2256 0.0824 0.2830 0.3031 0.1030 0.2359 0.3814 0.1199 0.1887 0.4604 0.1330 0.1415 0.5400 0.1424 0.0943 0.6199 0.1481 0.0472 0.7000 0.1500 -0.0000 primID: 4 startangle_c: 1 endpose_c: 5 4 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 5 startangle_c: 1 endpose_c: 6 1 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 0.0320 0.0105 0.3551 0.0644 0.0197 0.3174 0.0973 0.0278 0.2798 0.1304 0.0346 0.2421 0.1639 0.0402 0.2045 0.1977 0.0446 0.1669 0.2316 0.0476 0.1292 0.2658 0.0495 0.0916 0.3000 0.0500 0.0540 primID: 6 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 7 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 8 startangle_c: 1 endpose_c: 7 2 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0389 0.0111 0.3927 0.0778 0.0222 0.3927 0.1167 0.0333 0.3927 0.1556 0.0444 0.3927 0.1944 0.0556 0.3927 0.2333 0.0667 0.3927 0.2722 0.0778 0.3927 0.3111 0.0889 0.3927 0.3500 0.1000 0.3927 primID: 9 startangle_c: 1 endpose_c: 5 4 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0278 0.0222 0.3927 0.0556 0.0444 0.3927 0.0833 0.0667 0.3927 0.1111 0.0889 0.3927 0.1389 0.1111 0.3927 0.1667 0.1333 0.3927 0.1944 0.1556 0.3927 0.2222 0.1778 0.3927 0.2500 0.2000 0.3927 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0056 0.0056 0.7854 0.0111 0.0111 0.7854 0.0167 0.0167 0.7854 0.0222 0.0222 0.7854 0.0278 0.0278 0.7854 0.0333 0.0333 0.7854 0.0389 0.0389 0.7854 0.0444 0.0444 0.7854 0.0500 0.0500 0.7854 primID: 1 startangle_c: 2 endpose_c: 6 6 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: 11 14 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0705 0.0705 0.7854 0.1411 0.1411 0.7854 0.2116 0.2116 0.7854 0.2816 0.2828 0.8201 0.3469 0.3581 0.8917 0.4068 0.4379 0.9633 0.4607 0.5218 1.0349 0.5086 0.6093 1.1065 0.5500 0.7000 1.1781 primID: 3 startangle_c: 2 endpose_c: 14 11 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0705 0.0705 0.7854 0.1411 0.1411 0.7854 0.2116 0.2116 0.7854 0.2828 0.2816 0.7507 0.3581 0.3469 0.6791 0.4379 0.4068 0.6075 0.5218 0.4607 0.5359 0.6093 0.5086 0.4643 0.7000 0.5500 0.3927 primID: 4 startangle_c: 2 endpose_c: 4 6 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 0.0278 0.0292 0.8288 0.0543 0.0595 0.8722 0.0795 0.0910 0.9156 0.1033 0.1235 0.9590 0.1257 0.1571 1.0024 0.1466 0.1916 1.0458 0.1659 0.2269 1.0892 0.1838 0.2631 1.1326 0.2000 0.3000 1.1760 primID: 5 startangle_c: 2 endpose_c: 6 4 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 0.0292 0.0278 0.7420 0.0595 0.0543 0.6986 0.0910 0.0795 0.6552 0.1235 0.1033 0.6118 0.1571 0.1257 0.5684 0.1916 0.1466 0.5250 0.2269 0.1659 0.4816 0.2631 0.1838 0.4382 0.3000 0.2000 0.3948 primID: 6 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 7 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 8 startangle_c: 2 endpose_c: 6 7 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0389 0.7854 0.0667 0.0778 0.7854 0.1000 0.1167 0.7854 0.1333 0.1556 0.7854 0.1667 0.1944 0.7854 0.2000 0.2333 0.7854 0.2333 0.2722 0.7854 0.2667 0.3111 0.7854 0.3000 0.3500 0.7854 primID: 9 startangle_c: 2 endpose_c: 7 6 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0389 0.0333 0.7854 0.0778 0.0667 0.7854 0.1167 0.1000 0.7854 0.1556 0.1333 0.7854 0.1944 0.1667 0.7854 0.2333 0.2000 0.7854 0.2722 0.2333 0.7854 0.3111 0.2667 0.7854 0.3500 0.3000 0.7854 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0056 0.0111 1.1781 0.0111 0.0222 1.1781 0.0167 0.0333 1.1781 0.0222 0.0444 1.1781 0.0278 0.0556 1.1781 0.0333 0.0667 1.1781 0.0389 0.0778 1.1781 0.0444 0.0889 1.1781 0.0500 0.1000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: 9 13 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0378 0.0793 1.1378 0.0787 0.1572 1.0976 0.1229 0.2334 1.0574 0.1701 0.3079 1.0171 0.2204 0.3805 0.9769 0.2736 0.4512 0.9366 0.3296 0.5197 0.8964 0.3885 0.5860 0.8561 0.4500 0.6500 0.8159 primID: 3 startangle_c: 3 endpose_c: 3 14 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0305 0.0741 1.1934 0.0582 0.1493 1.2406 0.0824 0.2256 1.2878 0.1030 0.3031 1.3349 0.1199 0.3814 1.3821 0.1330 0.4604 1.4293 0.1424 0.5400 1.4765 0.1481 0.6199 1.5236 0.1500 0.7000 1.5708 primID: 4 startangle_c: 3 endpose_c: 4 5 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 5 startangle_c: 3 endpose_c: 1 6 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 0.0105 0.0320 1.2157 0.0197 0.0644 1.2534 0.0278 0.0973 1.2910 0.0346 0.1304 1.3286 0.0402 0.1639 1.3663 0.0446 0.1977 1.4039 0.0476 0.2316 1.4416 0.0495 0.2658 1.4792 0.0500 0.3000 1.5168 primID: 6 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 7 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 8 startangle_c: 3 endpose_c: 2 7 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0111 0.0389 1.1781 0.0222 0.0778 1.1781 0.0333 0.1167 1.1781 0.0444 0.1556 1.1781 0.0556 0.1944 1.1781 0.0667 0.2333 1.1781 0.0778 0.2722 1.1781 0.0889 0.3111 1.1781 0.1000 0.3500 1.1781 primID: 9 startangle_c: 3 endpose_c: 4 5 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0222 0.0278 1.1781 0.0444 0.0556 1.1781 0.0667 0.0833 1.1781 0.0889 0.1111 1.1781 0.1111 0.1389 1.1781 0.1333 0.1667 1.1781 0.1556 0.1944 1.1781 0.1778 0.2222 1.1781 0.2000 0.2500 1.1781 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0056 1.5708 0.0000 0.0111 1.5708 0.0000 0.0167 1.5708 0.0000 0.0222 1.5708 0.0000 0.0278 1.5708 0.0000 0.0333 1.5708 0.0000 0.0389 1.5708 0.0000 0.0444 1.5708 0.0000 0.0500 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 8 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: -4 16 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0095 0.0904 1.6057 -0.0222 0.1806 1.6407 -0.0381 0.2707 1.6756 -0.0572 0.3604 1.7106 -0.0795 0.4496 1.7455 -0.1050 0.5383 1.7805 -0.1335 0.6264 1.8154 -0.1652 0.7136 1.8503 -0.2000 0.8000 1.8853 primID: 3 startangle_c: 4 endpose_c: 4 16 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0095 0.0904 1.5359 0.0222 0.1806 1.5009 0.0381 0.2707 1.4660 0.0572 0.3604 1.4310 0.0795 0.4496 1.3961 0.1050 0.5383 1.3611 0.1335 0.6264 1.3262 0.1652 0.7136 1.2912 0.2000 0.8000 1.2563 primID: 4 startangle_c: 4 endpose_c: -2 5 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0085 0.0280 1.5931 -0.0177 0.0559 1.6153 -0.0275 0.0839 1.6376 -0.0380 0.1117 1.6598 -0.0491 0.1396 1.6821 -0.0609 0.1673 1.7043 -0.0733 0.1950 1.7266 -0.0863 0.2225 1.7489 -0.1000 0.2500 1.7711 primID: 5 startangle_c: 4 endpose_c: 2 5 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0085 0.0280 1.5485 0.0177 0.0559 1.5263 0.0275 0.0839 1.5040 0.0380 0.1117 1.4818 0.0491 0.1396 1.4595 0.0609 0.1673 1.4373 0.0733 0.1950 1.4150 0.0863 0.2225 1.3927 0.1000 0.2500 1.3705 primID: 6 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 7 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 8 startangle_c: 4 endpose_c: -1 8 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0056 0.0444 1.5708 -0.0111 0.0889 1.5708 -0.0167 0.1333 1.5708 -0.0222 0.1778 1.5708 -0.0278 0.2222 1.5708 -0.0333 0.2667 1.5708 -0.0389 0.3111 1.5708 -0.0444 0.3556 1.5708 -0.0500 0.4000 1.5708 primID: 9 startangle_c: 4 endpose_c: 1 8 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0056 0.0444 1.5708 0.0111 0.0889 1.5708 0.0167 0.1333 1.5708 0.0222 0.1778 1.5708 0.0278 0.2222 1.5708 0.0333 0.2667 1.5708 0.0389 0.3111 1.5708 0.0444 0.3556 1.5708 0.0500 0.4000 1.5708 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0056 0.0111 1.9635 -0.0111 0.0222 1.9635 -0.0167 0.0333 1.9635 -0.0222 0.0444 1.9635 -0.0278 0.0556 1.9635 -0.0333 0.0667 1.9635 -0.0389 0.0778 1.9635 -0.0444 0.0889 1.9635 -0.0500 0.1000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: -9 13 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0378 0.0793 2.0037 -0.0787 0.1572 2.0440 -0.1229 0.2334 2.0842 -0.1701 0.3079 2.1245 -0.2204 0.3805 2.1647 -0.2736 0.4512 2.2050 -0.3296 0.5197 2.2452 -0.3885 0.5860 2.2855 -0.4500 0.6500 2.3257 primID: 3 startangle_c: 5 endpose_c: -3 14 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0305 0.0741 1.9482 -0.0582 0.1493 1.9010 -0.0824 0.2256 1.8538 -0.1030 0.3031 1.8067 -0.1199 0.3814 1.7595 -0.1330 0.4604 1.7123 -0.1424 0.5400 1.6651 -0.1481 0.6199 1.6180 -0.1500 0.7000 1.5708 primID: 4 startangle_c: 5 endpose_c: -4 5 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 5 startangle_c: 5 endpose_c: -1 6 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0105 0.0320 1.9259 -0.0197 0.0644 1.8882 -0.0278 0.0973 1.8506 -0.0346 0.1304 1.8129 -0.0402 0.1639 1.7753 -0.0446 0.1977 1.7377 -0.0476 0.2316 1.7000 -0.0495 0.2658 1.6624 -0.0500 0.3000 1.6248 primID: 6 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 7 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 8 startangle_c: 5 endpose_c: -2 7 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0111 0.0389 1.9635 -0.0222 0.0778 1.9635 -0.0333 0.1167 1.9635 -0.0444 0.1556 1.9635 -0.0556 0.1944 1.9635 -0.0667 0.2333 1.9635 -0.0778 0.2722 1.9635 -0.0889 0.3111 1.9635 -0.1000 0.3500 1.9635 primID: 9 startangle_c: 5 endpose_c: -4 5 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0222 0.0278 1.9635 -0.0444 0.0556 1.9635 -0.0667 0.0833 1.9635 -0.0889 0.1111 1.9635 -0.1111 0.1389 1.9635 -0.1333 0.1667 1.9635 -0.1556 0.1944 1.9635 -0.1778 0.2222 1.9635 -0.2000 0.2500 1.9635 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0056 0.0056 2.3562 -0.0111 0.0111 2.3562 -0.0167 0.0167 2.3562 -0.0222 0.0222 2.3562 -0.0278 0.0278 2.3562 -0.0333 0.0333 2.3562 -0.0389 0.0389 2.3562 -0.0444 0.0444 2.3562 -0.0500 0.0500 2.3562 primID: 1 startangle_c: 6 endpose_c: -6 6 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: -14 11 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0705 0.0705 2.3562 -0.1411 0.1411 2.3562 -0.2116 0.2116 2.3562 -0.2828 0.2816 2.3909 -0.3581 0.3469 2.4625 -0.4379 0.4068 2.5341 -0.5218 0.4607 2.6057 -0.6093 0.5086 2.6773 -0.7000 0.5500 2.7489 primID: 3 startangle_c: 6 endpose_c: -11 14 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0705 0.0705 2.3562 -0.1411 0.1411 2.3562 -0.2116 0.2116 2.3562 -0.2816 0.2828 2.3215 -0.3469 0.3581 2.2499 -0.4068 0.4379 2.1783 -0.4607 0.5218 2.1067 -0.5086 0.6093 2.0351 -0.5500 0.7000 1.9635 primID: 4 startangle_c: 6 endpose_c: -6 4 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0292 0.0278 2.3996 -0.0595 0.0543 2.4430 -0.0910 0.0795 2.4864 -0.1235 0.1033 2.5298 -0.1571 0.1257 2.5732 -0.1916 0.1466 2.6166 -0.2269 0.1659 2.6600 -0.2631 0.1838 2.7034 -0.3000 0.2000 2.7468 primID: 5 startangle_c: 6 endpose_c: -4 6 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0278 0.0292 2.3128 -0.0543 0.0595 2.2694 -0.0795 0.0910 2.2260 -0.1033 0.1235 2.1826 -0.1257 0.1571 2.1392 -0.1466 0.1916 2.0958 -0.1659 0.2269 2.0524 -0.1838 0.2631 2.0090 -0.2000 0.3000 1.9656 primID: 6 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 7 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 8 startangle_c: 6 endpose_c: -7 6 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0389 0.0333 2.3562 -0.0778 0.0667 2.3562 -0.1167 0.1000 2.3562 -0.1556 0.1333 2.3562 -0.1944 0.1667 2.3562 -0.2333 0.2000 2.3562 -0.2722 0.2333 2.3562 -0.3111 0.2667 2.3562 -0.3500 0.3000 2.3562 primID: 9 startangle_c: 6 endpose_c: -6 7 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0389 2.3562 -0.0667 0.0778 2.3562 -0.1000 0.1167 2.3562 -0.1333 0.1556 2.3562 -0.1667 0.1944 2.3562 -0.2000 0.2333 2.3562 -0.2333 0.2722 2.3562 -0.2667 0.3111 2.3562 -0.3000 0.3500 2.3562 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0111 0.0056 2.7489 -0.0222 0.0111 2.7489 -0.0333 0.0167 2.7489 -0.0444 0.0222 2.7489 -0.0556 0.0278 2.7489 -0.0667 0.0333 2.7489 -0.0778 0.0389 2.7489 -0.0889 0.0444 2.7489 -0.1000 0.0500 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: -13 9 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0793 0.0378 2.7086 -0.1572 0.0787 2.6684 -0.2334 0.1229 2.6281 -0.3079 0.1701 2.5879 -0.3805 0.2204 2.5477 -0.4512 0.2736 2.5074 -0.5197 0.3296 2.4672 -0.5860 0.3885 2.4269 -0.6500 0.4500 2.3867 primID: 3 startangle_c: 7 endpose_c: -14 3 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0741 0.0305 2.7642 -0.1493 0.0582 2.8114 -0.2256 0.0824 2.8586 -0.3031 0.1030 2.9057 -0.3814 0.1199 2.9529 -0.4604 0.1330 3.0001 -0.5400 0.1424 3.0472 -0.6199 0.1481 3.0944 -0.7000 0.1500 3.1416 primID: 4 startangle_c: 7 endpose_c: -5 4 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 5 startangle_c: 7 endpose_c: -6 1 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0320 0.0105 2.7865 -0.0644 0.0197 2.8242 -0.0973 0.0278 2.8618 -0.1304 0.0346 2.8994 -0.1639 0.0402 2.9371 -0.1977 0.0446 2.9747 -0.2316 0.0476 3.0124 -0.2658 0.0495 3.0500 -0.3000 0.0500 3.0876 primID: 6 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 7 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 8 startangle_c: 7 endpose_c: -7 2 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0389 0.0111 2.7489 -0.0778 0.0222 2.7489 -0.1167 0.0333 2.7489 -0.1556 0.0444 2.7489 -0.1944 0.0556 2.7489 -0.2333 0.0667 2.7489 -0.2722 0.0778 2.7489 -0.3111 0.0889 2.7489 -0.3500 0.1000 2.7489 primID: 9 startangle_c: 7 endpose_c: -5 4 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0278 0.0222 2.7489 -0.0556 0.0444 2.7489 -0.0833 0.0667 2.7489 -0.1111 0.0889 2.7489 -0.1389 0.1111 2.7489 -0.1667 0.1333 2.7489 -0.1944 0.1556 2.7489 -0.2222 0.1778 2.7489 -0.2500 0.2000 2.7489 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0278 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0389 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0500 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -8 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: -16 -4 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0904 -0.0095 3.1765 -0.1806 -0.0222 3.2115 -0.2707 -0.0381 3.2464 -0.3604 -0.0572 3.2814 -0.4496 -0.0795 3.3163 -0.5383 -0.1050 3.3513 -0.6264 -0.1335 3.3862 -0.7136 -0.1652 3.4211 -0.8000 -0.2000 3.4561 primID: 3 startangle_c: 8 endpose_c: -16 4 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0904 0.0095 3.1066 -0.1806 0.0222 3.0717 -0.2707 0.0381 3.0368 -0.3604 0.0572 3.0018 -0.4496 0.0795 2.9669 -0.5383 0.1050 2.9319 -0.6264 0.1335 2.8970 -0.7136 0.1652 2.8620 -0.8000 0.2000 2.8271 primID: 4 startangle_c: 8 endpose_c: -5 -2 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0280 -0.0085 3.1639 -0.0559 -0.0177 3.1861 -0.0839 -0.0275 3.2084 -0.1117 -0.0380 3.2306 -0.1396 -0.0491 3.2529 -0.1673 -0.0609 3.2751 -0.1950 -0.0733 3.2974 -0.2225 -0.0863 3.3197 -0.2500 -0.1000 3.3419 primID: 5 startangle_c: 8 endpose_c: -5 2 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0280 0.0085 3.1193 -0.0559 0.0177 3.0971 -0.0839 0.0275 3.0748 -0.1117 0.0380 3.0526 -0.1396 0.0491 3.0303 -0.1673 0.0609 3.0080 -0.1950 0.0733 2.9858 -0.2225 0.0863 2.9635 -0.2500 0.1000 2.9413 primID: 6 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 7 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 8 startangle_c: 8 endpose_c: -8 -1 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 -0.0056 3.1416 -0.0889 -0.0111 3.1416 -0.1333 -0.0167 3.1416 -0.1778 -0.0222 3.1416 -0.2222 -0.0278 3.1416 -0.2667 -0.0333 3.1416 -0.3111 -0.0389 3.1416 -0.3556 -0.0444 3.1416 -0.4000 -0.0500 3.1416 primID: 9 startangle_c: 8 endpose_c: -8 1 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0056 3.1416 -0.0889 0.0111 3.1416 -0.1333 0.0167 3.1416 -0.1778 0.0222 3.1416 -0.2222 0.0278 3.1416 -0.2667 0.0333 3.1416 -0.3111 0.0389 3.1416 -0.3556 0.0444 3.1416 -0.4000 0.0500 3.1416 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0111 -0.0056 3.5343 -0.0222 -0.0111 3.5343 -0.0333 -0.0167 3.5343 -0.0444 -0.0222 3.5343 -0.0556 -0.0278 3.5343 -0.0667 -0.0333 3.5343 -0.0778 -0.0389 3.5343 -0.0889 -0.0444 3.5343 -0.1000 -0.0500 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: -13 -9 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0793 -0.0378 3.5745 -0.1572 -0.0787 3.6148 -0.2334 -0.1229 3.6550 -0.3079 -0.1701 3.6953 -0.3805 -0.2204 3.7355 -0.4512 -0.2736 3.7758 -0.5197 -0.3296 3.8160 -0.5860 -0.3885 3.8563 -0.6500 -0.4500 3.8965 primID: 3 startangle_c: 9 endpose_c: -14 -3 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0741 -0.0305 3.5190 -0.1493 -0.0582 3.4718 -0.2256 -0.0824 3.4246 -0.3031 -0.1030 3.3775 -0.3814 -0.1199 3.3303 -0.4604 -0.1330 3.2831 -0.5400 -0.1424 3.2359 -0.6199 -0.1481 3.1888 -0.7000 -0.1500 3.1416 primID: 4 startangle_c: 9 endpose_c: -5 -4 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 5 startangle_c: 9 endpose_c: -6 -1 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0320 -0.0105 3.4967 -0.0644 -0.0197 3.4590 -0.0973 -0.0278 3.4214 -0.1304 -0.0346 3.3837 -0.1639 -0.0402 3.3461 -0.1977 -0.0446 3.3085 -0.2316 -0.0476 3.2708 -0.2658 -0.0495 3.2332 -0.3000 -0.0500 3.1955 primID: 6 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 7 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 8 startangle_c: 9 endpose_c: -7 -2 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0389 -0.0111 3.5343 -0.0778 -0.0222 3.5343 -0.1167 -0.0333 3.5343 -0.1556 -0.0444 3.5343 -0.1944 -0.0556 3.5343 -0.2333 -0.0667 3.5343 -0.2722 -0.0778 3.5343 -0.3111 -0.0889 3.5343 -0.3500 -0.1000 3.5343 primID: 9 startangle_c: 9 endpose_c: -5 -4 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0278 -0.0222 3.5343 -0.0556 -0.0444 3.5343 -0.0833 -0.0667 3.5343 -0.1111 -0.0889 3.5343 -0.1389 -0.1111 3.5343 -0.1667 -0.1333 3.5343 -0.1944 -0.1556 3.5343 -0.2222 -0.1778 3.5343 -0.2500 -0.2000 3.5343 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0056 -0.0056 3.9270 -0.0111 -0.0111 3.9270 -0.0167 -0.0167 3.9270 -0.0222 -0.0222 3.9270 -0.0278 -0.0278 3.9270 -0.0333 -0.0333 3.9270 -0.0389 -0.0389 3.9270 -0.0444 -0.0444 3.9270 -0.0500 -0.0500 3.9270 primID: 1 startangle_c: 10 endpose_c: -6 -6 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: -11 -14 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0705 -0.0705 3.9270 -0.1411 -0.1411 3.9270 -0.2116 -0.2116 3.9270 -0.2816 -0.2828 3.9617 -0.3469 -0.3581 4.0333 -0.4068 -0.4379 4.1049 -0.4607 -0.5218 4.1765 -0.5086 -0.6093 4.2481 -0.5500 -0.7000 4.3197 primID: 3 startangle_c: 10 endpose_c: -14 -11 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0705 -0.0705 3.9270 -0.1411 -0.1411 3.9270 -0.2116 -0.2116 3.9270 -0.2828 -0.2816 3.8923 -0.3581 -0.3469 3.8207 -0.4379 -0.4068 3.7491 -0.5218 -0.4607 3.6775 -0.6093 -0.5086 3.6059 -0.7000 -0.5500 3.5343 primID: 4 startangle_c: 10 endpose_c: -4 -6 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0278 -0.0292 3.9704 -0.0543 -0.0595 4.0138 -0.0795 -0.0910 4.0572 -0.1033 -0.1235 4.1006 -0.1257 -0.1571 4.1440 -0.1466 -0.1916 4.1874 -0.1659 -0.2269 4.2308 -0.1838 -0.2631 4.2742 -0.2000 -0.3000 4.3176 primID: 5 startangle_c: 10 endpose_c: -6 -4 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0292 -0.0278 3.8836 -0.0595 -0.0543 3.8402 -0.0910 -0.0795 3.7968 -0.1235 -0.1033 3.7534 -0.1571 -0.1257 3.7100 -0.1916 -0.1466 3.6666 -0.2269 -0.1659 3.6232 -0.2631 -0.1838 3.5798 -0.3000 -0.2000 3.5364 primID: 6 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 7 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 8 startangle_c: 10 endpose_c: -6 -7 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0389 3.9270 -0.0667 -0.0778 3.9270 -0.1000 -0.1167 3.9270 -0.1333 -0.1556 3.9270 -0.1667 -0.1944 3.9270 -0.2000 -0.2333 3.9270 -0.2333 -0.2722 3.9270 -0.2667 -0.3111 3.9270 -0.3000 -0.3500 3.9270 primID: 9 startangle_c: 10 endpose_c: -7 -6 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0389 -0.0333 3.9270 -0.0778 -0.0667 3.9270 -0.1167 -0.1000 3.9270 -0.1556 -0.1333 3.9270 -0.1944 -0.1667 3.9270 -0.2333 -0.2000 3.9270 -0.2722 -0.2333 3.9270 -0.3111 -0.2667 3.9270 -0.3500 -0.3000 3.9270 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0056 -0.0111 4.3197 -0.0111 -0.0222 4.3197 -0.0167 -0.0333 4.3197 -0.0222 -0.0444 4.3197 -0.0278 -0.0556 4.3197 -0.0333 -0.0667 4.3197 -0.0389 -0.0778 4.3197 -0.0444 -0.0889 4.3197 -0.0500 -0.1000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: -9 -13 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0378 -0.0793 4.2794 -0.0787 -0.1572 4.2392 -0.1229 -0.2334 4.1989 -0.1701 -0.3079 4.1587 -0.2204 -0.3805 4.1185 -0.2736 -0.4512 4.0782 -0.3296 -0.5197 4.0380 -0.3885 -0.5860 3.9977 -0.4500 -0.6500 3.9575 primID: 3 startangle_c: 11 endpose_c: -3 -14 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0305 -0.0741 4.3350 -0.0582 -0.1493 4.3822 -0.0824 -0.2256 4.4294 -0.1030 -0.3031 4.4765 -0.1199 -0.3814 4.5237 -0.1330 -0.4604 4.5709 -0.1424 -0.5400 4.6180 -0.1481 -0.6199 4.6652 -0.1500 -0.7000 4.7124 primID: 4 startangle_c: 11 endpose_c: -4 -5 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 5 startangle_c: 11 endpose_c: -1 -6 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0105 -0.0320 4.3573 -0.0197 -0.0644 4.3950 -0.0278 -0.0973 4.4326 -0.0346 -0.1304 4.4702 -0.0402 -0.1639 4.5079 -0.0446 -0.1977 4.5455 -0.0476 -0.2316 4.5832 -0.0495 -0.2658 4.6208 -0.0500 -0.3000 4.6584 primID: 6 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 7 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 8 startangle_c: 11 endpose_c: -2 -7 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0111 -0.0389 4.3197 -0.0222 -0.0778 4.3197 -0.0333 -0.1167 4.3197 -0.0444 -0.1556 4.3197 -0.0556 -0.1944 4.3197 -0.0667 -0.2333 4.3197 -0.0778 -0.2722 4.3197 -0.0889 -0.3111 4.3197 -0.1000 -0.3500 4.3197 primID: 9 startangle_c: 11 endpose_c: -4 -5 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0222 -0.0278 4.3197 -0.0444 -0.0556 4.3197 -0.0667 -0.0833 4.3197 -0.0889 -0.1111 4.3197 -0.1111 -0.1389 4.3197 -0.1333 -0.1667 4.3197 -0.1556 -0.1944 4.3197 -0.1778 -0.2222 4.3197 -0.2000 -0.2500 4.3197 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0278 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0389 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0500 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -8 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 4 -16 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0095 -0.0904 4.7473 0.0222 -0.1806 4.7823 0.0381 -0.2707 4.8172 0.0572 -0.3604 4.8522 0.0795 -0.4496 4.8871 0.1050 -0.5383 4.9221 0.1335 -0.6264 4.9570 0.1652 -0.7136 4.9919 0.2000 -0.8000 5.0269 primID: 3 startangle_c: 12 endpose_c: -4 -16 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0095 -0.0904 4.6774 -0.0222 -0.1806 4.6425 -0.0381 -0.2707 4.6076 -0.0572 -0.3604 4.5726 -0.0795 -0.4496 4.5377 -0.1050 -0.5383 4.5027 -0.1335 -0.6264 4.4678 -0.1652 -0.7136 4.4328 -0.2000 -0.8000 4.3979 primID: 4 startangle_c: 12 endpose_c: 2 -5 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0085 -0.0280 4.7346 0.0177 -0.0559 4.7569 0.0275 -0.0839 4.7792 0.0380 -0.1117 4.8014 0.0491 -0.1396 4.8237 0.0609 -0.1673 4.8459 0.0733 -0.1950 4.8682 0.0863 -0.2225 4.8904 0.1000 -0.2500 4.9127 primID: 5 startangle_c: 12 endpose_c: -2 -5 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0085 -0.0280 4.6901 -0.0177 -0.0559 4.6679 -0.0275 -0.0839 4.6456 -0.0380 -0.1117 4.6234 -0.0491 -0.1396 4.6011 -0.0609 -0.1673 4.5788 -0.0733 -0.1950 4.5566 -0.0863 -0.2225 4.5343 -0.1000 -0.2500 4.5121 primID: 6 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 7 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 8 startangle_c: 12 endpose_c: 1 -8 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0056 -0.0444 4.7124 0.0111 -0.0889 4.7124 0.0167 -0.1333 4.7124 0.0222 -0.1778 4.7124 0.0278 -0.2222 4.7124 0.0333 -0.2667 4.7124 0.0389 -0.3111 4.7124 0.0444 -0.3556 4.7124 0.0500 -0.4000 4.7124 primID: 9 startangle_c: 12 endpose_c: -1 -8 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0056 -0.0444 4.7124 -0.0111 -0.0889 4.7124 -0.0167 -0.1333 4.7124 -0.0222 -0.1778 4.7124 -0.0278 -0.2222 4.7124 -0.0333 -0.2667 4.7124 -0.0389 -0.3111 4.7124 -0.0444 -0.3556 4.7124 -0.0500 -0.4000 4.7124 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0056 -0.0111 5.1051 0.0111 -0.0222 5.1051 0.0167 -0.0333 5.1051 0.0222 -0.0444 5.1051 0.0278 -0.0556 5.1051 0.0333 -0.0667 5.1051 0.0389 -0.0778 5.1051 0.0444 -0.0889 5.1051 0.0500 -0.1000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: 9 -13 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0378 -0.0793 5.1453 0.0787 -0.1572 5.1856 0.1229 -0.2334 5.2258 0.1701 -0.3079 5.2661 0.2204 -0.3805 5.3063 0.2736 -0.4512 5.3466 0.3296 -0.5197 5.3868 0.3885 -0.5860 5.4271 0.4500 -0.6500 5.4673 primID: 3 startangle_c: 13 endpose_c: 3 -14 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0305 -0.0741 5.0898 0.0582 -0.1493 5.0426 0.0824 -0.2256 4.9954 0.1030 -0.3031 4.9482 0.1199 -0.3814 4.9011 0.1330 -0.4604 4.8539 0.1424 -0.5400 4.8067 0.1481 -0.6199 4.7596 0.1500 -0.7000 4.7124 primID: 4 startangle_c: 13 endpose_c: 4 -5 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 5 startangle_c: 13 endpose_c: 1 -6 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 0.0105 -0.0320 5.0674 0.0197 -0.0644 5.0298 0.0278 -0.0973 4.9922 0.0346 -0.1304 4.9545 0.0402 -0.1639 4.9169 0.0446 -0.1977 4.8793 0.0476 -0.2316 4.8416 0.0495 -0.2658 4.8040 0.0500 -0.3000 4.7663 primID: 6 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 7 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 8 startangle_c: 13 endpose_c: 2 -7 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0111 -0.0389 5.1051 0.0222 -0.0778 5.1051 0.0333 -0.1167 5.1051 0.0444 -0.1556 5.1051 0.0556 -0.1944 5.1051 0.0667 -0.2333 5.1051 0.0778 -0.2722 5.1051 0.0889 -0.3111 5.1051 0.1000 -0.3500 5.1051 primID: 9 startangle_c: 13 endpose_c: 4 -5 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0222 -0.0278 5.1051 0.0444 -0.0556 5.1051 0.0667 -0.0833 5.1051 0.0889 -0.1111 5.1051 0.1111 -0.1389 5.1051 0.1333 -0.1667 5.1051 0.1556 -0.1944 5.1051 0.1778 -0.2222 5.1051 0.2000 -0.2500 5.1051 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0056 -0.0056 5.4978 0.0111 -0.0111 5.4978 0.0167 -0.0167 5.4978 0.0222 -0.0222 5.4978 0.0278 -0.0278 5.4978 0.0333 -0.0333 5.4978 0.0389 -0.0389 5.4978 0.0444 -0.0444 5.4978 0.0500 -0.0500 5.4978 primID: 1 startangle_c: 14 endpose_c: 6 -6 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: 14 -11 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0705 -0.0705 5.4978 0.1411 -0.1411 5.4978 0.2116 -0.2116 5.4978 0.2828 -0.2816 5.5325 0.3581 -0.3469 5.6041 0.4379 -0.4068 5.6757 0.5218 -0.4607 5.7473 0.6093 -0.5086 5.8189 0.7000 -0.5500 5.8905 primID: 3 startangle_c: 14 endpose_c: 11 -14 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0705 -0.0705 5.4978 0.1411 -0.1411 5.4978 0.2116 -0.2116 5.4978 0.2816 -0.2828 5.4631 0.3469 -0.3581 5.3915 0.4068 -0.4379 5.3199 0.4607 -0.5218 5.2483 0.5086 -0.6093 5.1767 0.5500 -0.7000 5.1051 primID: 4 startangle_c: 14 endpose_c: 6 -4 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 0.0292 -0.0278 5.5412 0.0595 -0.0543 5.5846 0.0910 -0.0795 5.6280 0.1235 -0.1033 5.6714 0.1571 -0.1257 5.7148 0.1916 -0.1466 5.7582 0.2269 -0.1659 5.8016 0.2631 -0.1838 5.8450 0.3000 -0.2000 5.8884 primID: 5 startangle_c: 14 endpose_c: 4 -6 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 0.0278 -0.0292 5.4544 0.0543 -0.0595 5.4110 0.0795 -0.0910 5.3676 0.1033 -0.1235 5.3242 0.1257 -0.1571 5.2808 0.1466 -0.1916 5.2374 0.1659 -0.2269 5.1940 0.1838 -0.2631 5.1506 0.2000 -0.3000 5.1072 primID: 6 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 7 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 8 startangle_c: 14 endpose_c: 7 -6 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0389 -0.0333 5.4978 0.0778 -0.0667 5.4978 0.1167 -0.1000 5.4978 0.1556 -0.1333 5.4978 0.1944 -0.1667 5.4978 0.2333 -0.2000 5.4978 0.2722 -0.2333 5.4978 0.3111 -0.2667 5.4978 0.3500 -0.3000 5.4978 primID: 9 startangle_c: 14 endpose_c: 6 -7 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0389 5.4978 0.0667 -0.0778 5.4978 0.1000 -0.1167 5.4978 0.1333 -0.1556 5.4978 0.1667 -0.1944 5.4978 0.2000 -0.2333 5.4978 0.2333 -0.2722 5.4978 0.2667 -0.3111 5.4978 0.3000 -0.3500 5.4978 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0111 -0.0056 5.8905 0.0222 -0.0111 5.8905 0.0333 -0.0167 5.8905 0.0444 -0.0222 5.8905 0.0556 -0.0278 5.8905 0.0667 -0.0333 5.8905 0.0778 -0.0389 5.8905 0.0889 -0.0444 5.8905 0.1000 -0.0500 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: 13 -9 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0793 -0.0378 5.8502 0.1572 -0.0787 5.8100 0.2334 -0.1229 5.7697 0.3079 -0.1701 5.7295 0.3805 -0.2204 5.6892 0.4512 -0.2736 5.6490 0.5197 -0.3296 5.6088 0.5860 -0.3885 5.5685 0.6500 -0.4500 5.5283 primID: 3 startangle_c: 15 endpose_c: 14 -3 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0741 -0.0305 5.9058 0.1493 -0.0582 5.9530 0.2256 -0.0824 6.0002 0.3031 -0.1030 6.0473 0.3814 -0.1199 6.0945 0.4604 -0.1330 6.1417 0.5400 -0.1424 6.1888 0.6199 -0.1481 6.2360 0.7000 -0.1500 6.2832 primID: 4 startangle_c: 15 endpose_c: 5 -4 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 5 startangle_c: 15 endpose_c: 6 -1 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 0.0320 -0.0105 5.9281 0.0644 -0.0197 5.9658 0.0973 -0.0278 6.0034 0.1304 -0.0346 6.0410 0.1639 -0.0402 6.0787 0.1977 -0.0446 6.1163 0.2316 -0.0476 6.1540 0.2658 -0.0495 6.1916 0.3000 -0.0500 6.2292 primID: 6 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 7 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 1000 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 primID: 8 startangle_c: 15 endpose_c: 7 -2 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0389 -0.0111 5.8905 0.0778 -0.0222 5.8905 0.1167 -0.0333 5.8905 0.1556 -0.0444 5.8905 0.1944 -0.0556 5.8905 0.2333 -0.0667 5.8905 0.2722 -0.0778 5.8905 0.3111 -0.0889 5.8905 0.3500 -0.1000 5.8905 primID: 9 startangle_c: 15 endpose_c: 5 -4 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0278 -0.0222 5.8905 0.0556 -0.0444 5.8905 0.0833 -0.0667 5.8905 0.1111 -0.0889 5.8905 0.1389 -0.1111 5.8905 0.1667 -0.1333 5.8905 0.1944 -0.1556 5.8905 0.2222 -0.1778 5.8905 0.2500 -0.2000 5.8905 ================================================ FILE: mir_navigation/mprim/unicycle_highcost_10cm.mprim ================================================ resolution_m: 0.100000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0111 0.0000 0.0000 0.0222 0.0000 0.0000 0.0333 0.0000 0.0000 0.0444 0.0000 0.0000 0.0556 0.0000 0.0000 0.0667 0.0000 0.0000 0.0778 0.0000 0.0000 0.0889 0.0000 0.0000 0.1000 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 4 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0333 0.0000 0.0000 -0.0444 0.0000 0.0000 -0.0556 0.0000 0.0000 -0.0667 0.0000 0.0000 -0.0778 0.0000 0.0000 -0.0889 0.0000 0.0000 -0.1000 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 4 1 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0048 0.0349 0.0903 0.0111 0.0699 0.1353 0.0191 0.1048 0.1802 0.0286 0.1398 0.2248 0.0398 0.1747 0.2692 0.0525 0.2097 0.3132 0.0668 0.2446 0.3568 0.0826 0.2796 0.4000 0.1000 0.3145 primID: 4 startangle_c: 0 endpose_c: 4 -1 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0048 -0.0349 0.0903 -0.0111 -0.0699 0.1353 -0.0191 -0.1048 0.1802 -0.0286 -0.1398 0.2248 -0.0398 -0.1747 0.2692 -0.0525 -0.2097 0.3132 -0.0668 -0.2446 0.3568 -0.0826 -0.2796 0.4000 -0.1000 -0.3145 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0222 0.0111 0.3927 0.0444 0.0222 0.3927 0.0667 0.0333 0.3927 0.0889 0.0444 0.3927 0.1111 0.0556 0.3927 0.1333 0.0667 0.3927 0.1556 0.0778 0.3927 0.1778 0.0889 0.3927 0.2000 0.1000 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0667 0.0333 0.3927 0.1333 0.0667 0.3927 0.2000 0.1000 0.3927 0.2667 0.1333 0.3927 0.3333 0.1667 0.3927 0.4000 0.2000 0.3927 0.4667 0.2333 0.3927 0.5333 0.2667 0.3927 0.6000 0.3000 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0222 -0.0111 0.3927 -0.0444 -0.0222 0.3927 -0.0667 -0.0333 0.3927 -0.0889 -0.0444 0.3927 -0.1111 -0.0556 0.3927 -0.1333 -0.0667 0.3927 -0.1556 -0.0778 0.3927 -0.1778 -0.0889 0.3927 -0.2000 -0.1000 0.3927 primID: 3 startangle_c: 1 endpose_c: 3 2 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0369 0.0162 0.4345 0.0731 0.0339 0.4783 0.1085 0.0533 0.5222 0.1430 0.0741 0.5661 0.1766 0.0965 0.6099 0.2091 0.1203 0.6538 0.2405 0.1455 0.6977 0.2709 0.1721 0.7415 0.3000 0.2000 0.7854 primID: 4 startangle_c: 1 endpose_c: 4 1 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0427 0.0177 0.3927 0.0854 0.0354 0.3927 0.1283 0.0523 0.3477 0.1722 0.0668 0.2898 0.2168 0.0787 0.2318 0.2621 0.0880 0.1739 0.3078 0.0947 0.1159 0.3538 0.0987 0.0580 0.4000 0.1000 0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0111 0.0111 0.7854 0.0222 0.0222 0.7854 0.0333 0.0333 0.7854 0.0444 0.0444 0.7854 0.0556 0.0556 0.7854 0.0667 0.0667 0.7854 0.0778 0.0778 0.7854 0.0889 0.0889 0.7854 0.1000 0.1000 0.7854 primID: 1 startangle_c: 2 endpose_c: 3 3 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0111 -0.0111 0.7854 -0.0222 -0.0222 0.7854 -0.0333 -0.0333 0.7854 -0.0444 -0.0444 0.7854 -0.0556 -0.0556 0.7854 -0.0667 -0.0667 0.7854 -0.0778 -0.0778 0.7854 -0.0889 -0.0889 0.7854 -0.1000 -0.1000 0.7854 primID: 3 startangle_c: 2 endpose_c: 2 4 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0262 0.0411 0.8119 0.0515 0.0831 0.8384 0.0758 0.1260 0.8649 0.0991 0.1697 0.8913 0.1214 0.2142 0.9178 0.1426 0.2595 0.9443 0.1628 0.3056 0.9708 0.1820 0.3525 0.9973 0.2000 0.4000 1.0238 primID: 4 startangle_c: 2 endpose_c: 4 2 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0411 0.0262 0.7589 0.0831 0.0515 0.7324 0.1260 0.0758 0.7059 0.1697 0.0991 0.6795 0.2142 0.1214 0.6530 0.2595 0.1426 0.6265 0.3056 0.1628 0.6000 0.3525 0.1820 0.5735 0.4000 0.2000 0.5470 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0111 0.0222 1.1781 0.0222 0.0444 1.1781 0.0333 0.0667 1.1781 0.0444 0.0889 1.1781 0.0556 0.1111 1.1781 0.0667 0.1333 1.1781 0.0778 0.1556 1.1781 0.0889 0.1778 1.1781 0.1000 0.2000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0333 0.0667 1.1781 0.0667 0.1333 1.1781 0.1000 0.2000 1.1781 0.1333 0.2667 1.1781 0.1667 0.3333 1.1781 0.2000 0.4000 1.1781 0.2333 0.4667 1.1781 0.2667 0.5333 1.1781 0.3000 0.6000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0111 -0.0222 1.1781 -0.0222 -0.0444 1.1781 -0.0333 -0.0667 1.1781 -0.0444 -0.0889 1.1781 -0.0556 -0.1111 1.1781 -0.0667 -0.1333 1.1781 -0.0778 -0.1556 1.1781 -0.0889 -0.1778 1.1781 -0.1000 -0.2000 1.1781 primID: 3 startangle_c: 3 endpose_c: 2 3 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0162 0.0369 1.1363 0.0339 0.0731 1.0925 0.0533 0.1085 1.0486 0.0741 0.1430 1.0047 0.0965 0.1766 0.9609 0.1203 0.2091 0.9170 0.1455 0.2405 0.8731 0.1721 0.2709 0.8293 0.2000 0.3000 0.7854 primID: 4 startangle_c: 3 endpose_c: 1 4 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0177 0.0427 1.1781 0.0354 0.0854 1.1781 0.0523 0.1283 1.2231 0.0668 0.1722 1.2810 0.0787 0.2168 1.3390 0.0880 0.2621 1.3969 0.0947 0.3078 1.4549 0.0987 0.3538 1.5128 0.1000 0.4000 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0111 1.5708 0.0000 0.0222 1.5708 0.0000 0.0333 1.5708 0.0000 0.0444 1.5708 0.0000 0.0556 1.5708 0.0000 0.0667 1.5708 0.0000 0.0778 1.5708 0.0000 0.0889 1.5708 0.0000 0.1000 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 4 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0333 1.5708 0.0000 -0.0444 1.5708 0.0000 -0.0556 1.5708 0.0000 -0.0667 1.5708 0.0000 -0.0778 1.5708 0.0000 -0.0889 1.5708 0.0000 -0.1000 1.5708 primID: 3 startangle_c: 4 endpose_c: -1 4 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0048 0.0452 1.6057 -0.0111 0.0903 1.6407 -0.0191 0.1353 1.6756 -0.0286 0.1802 1.7106 -0.0398 0.2248 1.7455 -0.0525 0.2692 1.7805 -0.0668 0.3132 1.8154 -0.0826 0.3568 1.8503 -0.1000 0.4000 1.8853 primID: 4 startangle_c: 4 endpose_c: 1 4 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0048 0.0452 1.5359 0.0111 0.0903 1.5009 0.0191 0.1353 1.4660 0.0286 0.1802 1.4310 0.0398 0.2248 1.3961 0.0525 0.2692 1.3611 0.0668 0.3132 1.3262 0.0826 0.3568 1.2912 0.1000 0.4000 1.2563 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0111 0.0222 1.9635 -0.0222 0.0444 1.9635 -0.0333 0.0667 1.9635 -0.0444 0.0889 1.9635 -0.0556 0.1111 1.9635 -0.0667 0.1333 1.9635 -0.0778 0.1556 1.9635 -0.0889 0.1778 1.9635 -0.1000 0.2000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0333 0.0667 1.9635 -0.0667 0.1333 1.9635 -0.1000 0.2000 1.9635 -0.1333 0.2667 1.9635 -0.1667 0.3333 1.9635 -0.2000 0.4000 1.9635 -0.2333 0.4667 1.9635 -0.2667 0.5333 1.9635 -0.3000 0.6000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0111 -0.0222 1.9635 0.0222 -0.0444 1.9635 0.0333 -0.0667 1.9635 0.0444 -0.0889 1.9635 0.0556 -0.1111 1.9635 0.0667 -0.1333 1.9635 0.0778 -0.1556 1.9635 0.0889 -0.1778 1.9635 0.1000 -0.2000 1.9635 primID: 3 startangle_c: 5 endpose_c: -2 3 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0162 0.0369 2.0053 -0.0339 0.0731 2.0491 -0.0533 0.1085 2.0930 -0.0741 0.1430 2.1369 -0.0965 0.1766 2.1807 -0.1203 0.2091 2.2246 -0.1455 0.2405 2.2685 -0.1721 0.2709 2.3123 -0.2000 0.3000 2.3562 primID: 4 startangle_c: 5 endpose_c: -1 4 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0177 0.0427 1.9635 -0.0354 0.0854 1.9635 -0.0523 0.1283 1.9185 -0.0668 0.1722 1.8606 -0.0787 0.2168 1.8026 -0.0880 0.2621 1.7447 -0.0947 0.3078 1.6867 -0.0987 0.3538 1.6287 -0.1000 0.4000 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0111 0.0111 2.3562 -0.0222 0.0222 2.3562 -0.0333 0.0333 2.3562 -0.0444 0.0444 2.3562 -0.0556 0.0556 2.3562 -0.0667 0.0667 2.3562 -0.0778 0.0778 2.3562 -0.0889 0.0889 2.3562 -0.1000 0.1000 2.3562 primID: 1 startangle_c: 6 endpose_c: -3 3 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0111 -0.0111 2.3562 0.0222 -0.0222 2.3562 0.0333 -0.0333 2.3562 0.0444 -0.0444 2.3562 0.0556 -0.0556 2.3562 0.0667 -0.0667 2.3562 0.0778 -0.0778 2.3562 0.0889 -0.0889 2.3562 0.1000 -0.1000 2.3562 primID: 3 startangle_c: 6 endpose_c: -4 2 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0411 0.0262 2.3827 -0.0831 0.0515 2.4092 -0.1260 0.0758 2.4357 -0.1697 0.0991 2.4621 -0.2142 0.1214 2.4886 -0.2595 0.1426 2.5151 -0.3056 0.1628 2.5416 -0.3525 0.1820 2.5681 -0.4000 0.2000 2.5946 primID: 4 startangle_c: 6 endpose_c: -2 4 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0262 0.0411 2.3297 -0.0515 0.0831 2.3032 -0.0758 0.1260 2.2767 -0.0991 0.1697 2.2502 -0.1214 0.2142 2.2238 -0.1426 0.2595 2.1973 -0.1628 0.3056 2.1708 -0.1820 0.3525 2.1443 -0.2000 0.4000 2.1178 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0222 0.0111 2.7489 -0.0444 0.0222 2.7489 -0.0667 0.0333 2.7489 -0.0889 0.0444 2.7489 -0.1111 0.0556 2.7489 -0.1333 0.0667 2.7489 -0.1556 0.0778 2.7489 -0.1778 0.0889 2.7489 -0.2000 0.1000 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0667 0.0333 2.7489 -0.1333 0.0667 2.7489 -0.2000 0.1000 2.7489 -0.2667 0.1333 2.7489 -0.3333 0.1667 2.7489 -0.4000 0.2000 2.7489 -0.4667 0.2333 2.7489 -0.5333 0.2667 2.7489 -0.6000 0.3000 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0222 -0.0111 2.7489 0.0444 -0.0222 2.7489 0.0667 -0.0333 2.7489 0.0889 -0.0444 2.7489 0.1111 -0.0556 2.7489 0.1333 -0.0667 2.7489 0.1556 -0.0778 2.7489 0.1778 -0.0889 2.7489 0.2000 -0.1000 2.7489 primID: 3 startangle_c: 7 endpose_c: -3 2 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0369 0.0162 2.7071 -0.0731 0.0339 2.6633 -0.1085 0.0533 2.6194 -0.1430 0.0741 2.5755 -0.1766 0.0965 2.5317 -0.2091 0.1203 2.4878 -0.2405 0.1455 2.4439 -0.2709 0.1721 2.4001 -0.3000 0.2000 2.3562 primID: 4 startangle_c: 7 endpose_c: -4 1 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0427 0.0177 2.7489 -0.0854 0.0354 2.7489 -0.1283 0.0523 2.7939 -0.1722 0.0668 2.8518 -0.2168 0.0787 2.9098 -0.2621 0.0880 2.9677 -0.3078 0.0947 3.0257 -0.3538 0.0987 3.0836 -0.4000 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0556 0.0000 3.1416 -0.0667 0.0000 3.1416 -0.0778 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1000 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -4 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0111 0.0000 3.1416 0.0222 0.0000 3.1416 0.0333 0.0000 3.1416 0.0444 0.0000 3.1416 0.0556 0.0000 3.1416 0.0667 0.0000 3.1416 0.0778 0.0000 3.1416 0.0889 0.0000 3.1416 0.1000 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -4 -1 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 -0.0048 3.1765 -0.0903 -0.0111 3.2115 -0.1353 -0.0191 3.2464 -0.1802 -0.0286 3.2814 -0.2248 -0.0398 3.3163 -0.2692 -0.0525 3.3513 -0.3132 -0.0668 3.3862 -0.3568 -0.0826 3.4211 -0.4000 -0.1000 3.4561 primID: 4 startangle_c: 8 endpose_c: -4 1 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0048 3.1066 -0.0903 0.0111 3.0717 -0.1353 0.0191 3.0368 -0.1802 0.0286 3.0018 -0.2248 0.0398 2.9669 -0.2692 0.0525 2.9319 -0.3132 0.0668 2.8970 -0.3568 0.0826 2.8620 -0.4000 0.1000 2.8271 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0222 -0.0111 3.5343 -0.0444 -0.0222 3.5343 -0.0667 -0.0333 3.5343 -0.0889 -0.0444 3.5343 -0.1111 -0.0556 3.5343 -0.1333 -0.0667 3.5343 -0.1556 -0.0778 3.5343 -0.1778 -0.0889 3.5343 -0.2000 -0.1000 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0667 -0.0333 3.5343 -0.1333 -0.0667 3.5343 -0.2000 -0.1000 3.5343 -0.2667 -0.1333 3.5343 -0.3333 -0.1667 3.5343 -0.4000 -0.2000 3.5343 -0.4667 -0.2333 3.5343 -0.5333 -0.2667 3.5343 -0.6000 -0.3000 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0222 0.0111 3.5343 0.0444 0.0222 3.5343 0.0667 0.0333 3.5343 0.0889 0.0444 3.5343 0.1111 0.0556 3.5343 0.1333 0.0667 3.5343 0.1556 0.0778 3.5343 0.1778 0.0889 3.5343 0.2000 0.1000 3.5343 primID: 3 startangle_c: 9 endpose_c: -3 -2 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0369 -0.0162 3.5761 -0.0731 -0.0339 3.6199 -0.1085 -0.0533 3.6638 -0.1430 -0.0741 3.7077 -0.1766 -0.0965 3.7515 -0.2091 -0.1203 3.7954 -0.2405 -0.1455 3.8393 -0.2709 -0.1721 3.8831 -0.3000 -0.2000 3.9270 primID: 4 startangle_c: 9 endpose_c: -4 -1 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0427 -0.0177 3.5343 -0.0854 -0.0354 3.5343 -0.1283 -0.0523 3.4893 -0.1722 -0.0668 3.4313 -0.2168 -0.0787 3.3734 -0.2621 -0.0880 3.3154 -0.3078 -0.0947 3.2575 -0.3538 -0.0987 3.1995 -0.4000 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0111 -0.0111 3.9270 -0.0222 -0.0222 3.9270 -0.0333 -0.0333 3.9270 -0.0444 -0.0444 3.9270 -0.0556 -0.0556 3.9270 -0.0667 -0.0667 3.9270 -0.0778 -0.0778 3.9270 -0.0889 -0.0889 3.9270 -0.1000 -0.1000 3.9270 primID: 1 startangle_c: 10 endpose_c: -3 -3 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0111 0.0111 3.9270 0.0222 0.0222 3.9270 0.0333 0.0333 3.9270 0.0444 0.0444 3.9270 0.0556 0.0556 3.9270 0.0667 0.0667 3.9270 0.0778 0.0778 3.9270 0.0889 0.0889 3.9270 0.1000 0.1000 3.9270 primID: 3 startangle_c: 10 endpose_c: -2 -4 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0262 -0.0411 3.9535 -0.0515 -0.0831 3.9800 -0.0758 -0.1260 4.0064 -0.0991 -0.1697 4.0329 -0.1214 -0.2142 4.0594 -0.1426 -0.2595 4.0859 -0.1628 -0.3056 4.1124 -0.1820 -0.3525 4.1389 -0.2000 -0.4000 4.1654 primID: 4 startangle_c: 10 endpose_c: -4 -2 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0411 -0.0262 3.9005 -0.0831 -0.0515 3.8740 -0.1260 -0.0758 3.8475 -0.1697 -0.0991 3.8210 -0.2142 -0.1214 3.7946 -0.2595 -0.1426 3.7681 -0.3056 -0.1628 3.7416 -0.3525 -0.1820 3.7151 -0.4000 -0.2000 3.6886 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0111 -0.0222 4.3197 -0.0222 -0.0444 4.3197 -0.0333 -0.0667 4.3197 -0.0444 -0.0889 4.3197 -0.0556 -0.1111 4.3197 -0.0667 -0.1333 4.3197 -0.0778 -0.1556 4.3197 -0.0889 -0.1778 4.3197 -0.1000 -0.2000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0333 -0.0667 4.3197 -0.0667 -0.1333 4.3197 -0.1000 -0.2000 4.3197 -0.1333 -0.2667 4.3197 -0.1667 -0.3333 4.3197 -0.2000 -0.4000 4.3197 -0.2333 -0.4667 4.3197 -0.2667 -0.5333 4.3197 -0.3000 -0.6000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0111 0.0222 4.3197 0.0222 0.0444 4.3197 0.0333 0.0667 4.3197 0.0444 0.0889 4.3197 0.0556 0.1111 4.3197 0.0667 0.1333 4.3197 0.0778 0.1556 4.3197 0.0889 0.1778 4.3197 0.1000 0.2000 4.3197 primID: 3 startangle_c: 11 endpose_c: -2 -3 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0162 -0.0369 4.2779 -0.0339 -0.0731 4.2341 -0.0533 -0.1085 4.1902 -0.0741 -0.1430 4.1463 -0.0965 -0.1766 4.1025 -0.1203 -0.2091 4.0586 -0.1455 -0.2405 4.0147 -0.1721 -0.2709 3.9709 -0.2000 -0.3000 3.9270 primID: 4 startangle_c: 11 endpose_c: -1 -4 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0177 -0.0427 4.3197 -0.0354 -0.0854 4.3197 -0.0523 -0.1283 4.3647 -0.0668 -0.1722 4.4226 -0.0787 -0.2168 4.4806 -0.0880 -0.2621 4.5385 -0.0947 -0.3078 4.5965 -0.0987 -0.3538 4.6544 -0.1000 -0.4000 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0556 4.7124 0.0000 -0.0667 4.7124 0.0000 -0.0778 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1000 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -4 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0111 4.7124 0.0000 0.0222 4.7124 0.0000 0.0333 4.7124 0.0000 0.0444 4.7124 0.0000 0.0556 4.7124 0.0000 0.0667 4.7124 0.0000 0.0778 4.7124 0.0000 0.0889 4.7124 0.0000 0.1000 4.7124 primID: 3 startangle_c: 12 endpose_c: 1 -4 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0048 -0.0452 4.7473 0.0111 -0.0903 4.7823 0.0191 -0.1353 4.8172 0.0286 -0.1802 4.8522 0.0398 -0.2248 4.8871 0.0525 -0.2692 4.9221 0.0668 -0.3132 4.9570 0.0826 -0.3568 4.9919 0.1000 -0.4000 5.0269 primID: 4 startangle_c: 12 endpose_c: -1 -4 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0048 -0.0452 4.6774 -0.0111 -0.0903 4.6425 -0.0191 -0.1353 4.6076 -0.0286 -0.1802 4.5726 -0.0398 -0.2248 4.5377 -0.0525 -0.2692 4.5027 -0.0668 -0.3132 4.4678 -0.0826 -0.3568 4.4328 -0.1000 -0.4000 4.3979 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0111 -0.0222 5.1051 0.0222 -0.0444 5.1051 0.0333 -0.0667 5.1051 0.0444 -0.0889 5.1051 0.0556 -0.1111 5.1051 0.0667 -0.1333 5.1051 0.0778 -0.1556 5.1051 0.0889 -0.1778 5.1051 0.1000 -0.2000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0333 -0.0667 5.1051 0.0667 -0.1333 5.1051 0.1000 -0.2000 5.1051 0.1333 -0.2667 5.1051 0.1667 -0.3333 5.1051 0.2000 -0.4000 5.1051 0.2333 -0.4667 5.1051 0.2667 -0.5333 5.1051 0.3000 -0.6000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0111 0.0222 5.1051 -0.0222 0.0444 5.1051 -0.0333 0.0667 5.1051 -0.0444 0.0889 5.1051 -0.0556 0.1111 5.1051 -0.0667 0.1333 5.1051 -0.0778 0.1556 5.1051 -0.0889 0.1778 5.1051 -0.1000 0.2000 5.1051 primID: 3 startangle_c: 13 endpose_c: 2 -3 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0162 -0.0369 5.1469 0.0339 -0.0731 5.1907 0.0533 -0.1085 5.2346 0.0741 -0.1430 5.2785 0.0965 -0.1766 5.3223 0.1203 -0.2091 5.3662 0.1455 -0.2405 5.4101 0.1721 -0.2709 5.4539 0.2000 -0.3000 5.4978 primID: 4 startangle_c: 13 endpose_c: 1 -4 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0177 -0.0427 5.1051 0.0354 -0.0854 5.1051 0.0523 -0.1283 5.0601 0.0668 -0.1722 5.0021 0.0787 -0.2168 4.9442 0.0880 -0.2621 4.8862 0.0947 -0.3078 4.8283 0.0987 -0.3538 4.7703 0.1000 -0.4000 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0111 -0.0111 5.4978 0.0222 -0.0222 5.4978 0.0333 -0.0333 5.4978 0.0444 -0.0444 5.4978 0.0556 -0.0556 5.4978 0.0667 -0.0667 5.4978 0.0778 -0.0778 5.4978 0.0889 -0.0889 5.4978 0.1000 -0.1000 5.4978 primID: 1 startangle_c: 14 endpose_c: 3 -3 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0111 0.0111 5.4978 -0.0222 0.0222 5.4978 -0.0333 0.0333 5.4978 -0.0444 0.0444 5.4978 -0.0556 0.0556 5.4978 -0.0667 0.0667 5.4978 -0.0778 0.0778 5.4978 -0.0889 0.0889 5.4978 -0.1000 0.1000 5.4978 primID: 3 startangle_c: 14 endpose_c: 4 -2 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0411 -0.0262 5.5243 0.0831 -0.0515 5.5508 0.1260 -0.0758 5.5772 0.1697 -0.0991 5.6037 0.2142 -0.1214 5.6302 0.2595 -0.1426 5.6567 0.3056 -0.1628 5.6832 0.3525 -0.1820 5.7097 0.4000 -0.2000 5.7362 primID: 4 startangle_c: 14 endpose_c: 2 -4 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0262 -0.0411 5.4713 0.0515 -0.0831 5.4448 0.0758 -0.1260 5.4183 0.0991 -0.1697 5.3918 0.1214 -0.2142 5.3654 0.1426 -0.2595 5.3389 0.1628 -0.3056 5.3124 0.1820 -0.3525 5.2859 0.2000 -0.4000 5.2594 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0222 -0.0111 5.8905 0.0444 -0.0222 5.8905 0.0667 -0.0333 5.8905 0.0889 -0.0444 5.8905 0.1111 -0.0556 5.8905 0.1333 -0.0667 5.8905 0.1556 -0.0778 5.8905 0.1778 -0.0889 5.8905 0.2000 -0.1000 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0667 -0.0333 5.8905 0.1333 -0.0667 5.8905 0.2000 -0.1000 5.8905 0.2667 -0.1333 5.8905 0.3333 -0.1667 5.8905 0.4000 -0.2000 5.8905 0.4667 -0.2333 5.8905 0.5333 -0.2667 5.8905 0.6000 -0.3000 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0222 0.0111 5.8905 -0.0444 0.0222 5.8905 -0.0667 0.0333 5.8905 -0.0889 0.0444 5.8905 -0.1111 0.0556 5.8905 -0.1333 0.0667 5.8905 -0.1556 0.0778 5.8905 -0.1778 0.0889 5.8905 -0.2000 0.1000 5.8905 primID: 3 startangle_c: 15 endpose_c: 3 -2 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0369 -0.0162 5.8487 0.0731 -0.0339 5.8049 0.1085 -0.0533 5.7610 0.1430 -0.0741 5.7171 0.1766 -0.0965 5.6733 0.2091 -0.1203 5.6294 0.2405 -0.1455 5.5855 0.2709 -0.1721 5.5417 0.3000 -0.2000 5.4978 primID: 4 startangle_c: 15 endpose_c: 4 -1 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0427 -0.0177 5.8905 0.0854 -0.0354 5.8905 0.1283 -0.0523 5.9355 0.1722 -0.0668 5.9934 0.2168 -0.0787 6.0514 0.2621 -0.0880 6.1093 0.3078 -0.0947 6.1673 0.3538 -0.0987 6.2252 0.4000 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_highcost_1cm.mprim ================================================ resolution_m: 0.010000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0011 0.0000 0.0000 0.0022 0.0000 0.0000 0.0033 0.0000 0.0000 0.0044 0.0000 0.0000 0.0056 0.0000 0.0000 0.0067 0.0000 0.0000 0.0078 0.0000 0.0000 0.0089 0.0000 0.0000 0.0100 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 20 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0222 0.0000 0.0000 0.0444 0.0000 0.0000 0.0667 0.0000 0.0000 0.0889 0.0000 0.0000 0.1111 0.0000 0.0000 0.1333 0.0000 0.0000 0.1556 0.0000 0.0000 0.1778 0.0000 0.0000 0.2000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0011 0.0000 0.0000 -0.0022 0.0000 0.0000 -0.0033 0.0000 0.0000 -0.0044 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0067 0.0000 0.0000 -0.0078 0.0000 0.0000 -0.0089 0.0000 0.0000 -0.0100 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 40 5 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 40 -5 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0022 0.0011 0.3927 0.0044 0.0022 0.3927 0.0067 0.0033 0.3927 0.0089 0.0044 0.3927 0.0111 0.0056 0.3927 0.0133 0.0067 0.3927 0.0156 0.0078 0.3927 0.0178 0.0089 0.3927 0.0200 0.0100 0.3927 primID: 1 startangle_c: 1 endpose_c: 20 10 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0222 0.0111 0.3927 0.0444 0.0222 0.3927 0.0667 0.0333 0.3927 0.0889 0.0444 0.3927 0.1111 0.0556 0.3927 0.1333 0.0667 0.3927 0.1556 0.0778 0.3927 0.1778 0.0889 0.3927 0.2000 0.1000 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0022 -0.0011 0.3927 -0.0044 -0.0022 0.3927 -0.0067 -0.0033 0.3927 -0.0089 -0.0044 0.3927 -0.0111 -0.0056 0.3927 -0.0133 -0.0067 0.3927 -0.0156 -0.0078 0.3927 -0.0178 -0.0089 0.3927 -0.0200 -0.0100 0.3927 primID: 3 startangle_c: 1 endpose_c: 25 20 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 35 10 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 -0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0011 0.0011 0.7854 0.0022 0.0022 0.7854 0.0033 0.0033 0.7854 0.0044 0.0044 0.7854 0.0056 0.0056 0.7854 0.0067 0.0067 0.7854 0.0078 0.0078 0.7854 0.0089 0.0089 0.7854 0.0100 0.0100 0.7854 primID: 1 startangle_c: 2 endpose_c: 10 10 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0111 0.0111 0.7854 0.0222 0.0222 0.7854 0.0333 0.0333 0.7854 0.0444 0.0444 0.7854 0.0556 0.0556 0.7854 0.0667 0.0667 0.7854 0.0778 0.0778 0.7854 0.0889 0.0889 0.7854 0.1000 0.1000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0011 -0.0011 0.7854 -0.0022 -0.0022 0.7854 -0.0033 -0.0033 0.7854 -0.0044 -0.0044 0.7854 -0.0056 -0.0056 0.7854 -0.0067 -0.0067 0.7854 -0.0078 -0.0078 0.7854 -0.0089 -0.0089 0.7854 -0.0100 -0.0100 0.7854 primID: 3 startangle_c: 2 endpose_c: 25 35 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 35 25 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0011 0.0022 1.1781 0.0022 0.0044 1.1781 0.0033 0.0067 1.1781 0.0044 0.0089 1.1781 0.0056 0.0111 1.1781 0.0067 0.0133 1.1781 0.0078 0.0156 1.1781 0.0089 0.0178 1.1781 0.0100 0.0200 1.1781 primID: 1 startangle_c: 3 endpose_c: 10 20 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0111 0.0222 1.1781 0.0222 0.0444 1.1781 0.0333 0.0667 1.1781 0.0444 0.0889 1.1781 0.0556 0.1111 1.1781 0.0667 0.1333 1.1781 0.0778 0.1556 1.1781 0.0889 0.1778 1.1781 0.1000 0.2000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0011 -0.0022 1.1781 -0.0022 -0.0044 1.1781 -0.0033 -0.0067 1.1781 -0.0044 -0.0089 1.1781 -0.0056 -0.0111 1.1781 -0.0067 -0.0133 1.1781 -0.0078 -0.0156 1.1781 -0.0089 -0.0178 1.1781 -0.0100 -0.0200 1.1781 primID: 3 startangle_c: 3 endpose_c: 20 25 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 10 35 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0011 1.5708 0.0000 0.0022 1.5708 0.0000 0.0033 1.5708 0.0000 0.0044 1.5708 0.0000 0.0056 1.5708 0.0000 0.0067 1.5708 0.0000 0.0078 1.5708 0.0000 0.0089 1.5708 0.0000 0.0100 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 20 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0222 1.5708 0.0000 0.0444 1.5708 0.0000 0.0667 1.5708 0.0000 0.0889 1.5708 0.0000 0.1111 1.5708 0.0000 0.1333 1.5708 0.0000 0.1556 1.5708 0.0000 0.1778 1.5708 0.0000 0.2000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0011 1.5708 0.0000 -0.0022 1.5708 0.0000 -0.0033 1.5708 0.0000 -0.0044 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0067 1.5708 0.0000 -0.0078 1.5708 0.0000 -0.0089 1.5708 0.0000 -0.0100 1.5708 primID: 3 startangle_c: 4 endpose_c: -5 40 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 5 40 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0011 0.0022 1.9635 -0.0022 0.0044 1.9635 -0.0033 0.0067 1.9635 -0.0044 0.0089 1.9635 -0.0056 0.0111 1.9635 -0.0067 0.0133 1.9635 -0.0078 0.0156 1.9635 -0.0089 0.0178 1.9635 -0.0100 0.0200 1.9635 primID: 1 startangle_c: 5 endpose_c: -10 20 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0111 0.0222 1.9635 -0.0222 0.0444 1.9635 -0.0333 0.0667 1.9635 -0.0444 0.0889 1.9635 -0.0556 0.1111 1.9635 -0.0667 0.1333 1.9635 -0.0778 0.1556 1.9635 -0.0889 0.1778 1.9635 -0.1000 0.2000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0011 -0.0022 1.9635 0.0022 -0.0044 1.9635 0.0033 -0.0067 1.9635 0.0044 -0.0089 1.9635 0.0056 -0.0111 1.9635 0.0067 -0.0133 1.9635 0.0078 -0.0156 1.9635 0.0089 -0.0178 1.9635 0.0100 -0.0200 1.9635 primID: 3 startangle_c: 5 endpose_c: -20 25 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -10 35 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0011 0.0011 2.3562 -0.0022 0.0022 2.3562 -0.0033 0.0033 2.3562 -0.0044 0.0044 2.3562 -0.0056 0.0056 2.3562 -0.0067 0.0067 2.3562 -0.0078 0.0078 2.3562 -0.0089 0.0089 2.3562 -0.0100 0.0100 2.3562 primID: 1 startangle_c: 6 endpose_c: -10 10 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0111 0.0111 2.3562 -0.0222 0.0222 2.3562 -0.0333 0.0333 2.3562 -0.0444 0.0444 2.3562 -0.0556 0.0556 2.3562 -0.0667 0.0667 2.3562 -0.0778 0.0778 2.3562 -0.0889 0.0889 2.3562 -0.1000 0.1000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0011 -0.0011 2.3562 0.0022 -0.0022 2.3562 0.0033 -0.0033 2.3562 0.0044 -0.0044 2.3562 0.0056 -0.0056 2.3562 0.0067 -0.0067 2.3562 0.0078 -0.0078 2.3562 0.0089 -0.0089 2.3562 0.0100 -0.0100 2.3562 primID: 3 startangle_c: 6 endpose_c: -35 25 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -25 35 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0022 0.0011 2.7489 -0.0044 0.0022 2.7489 -0.0067 0.0033 2.7489 -0.0089 0.0044 2.7489 -0.0111 0.0056 2.7489 -0.0133 0.0067 2.7489 -0.0156 0.0078 2.7489 -0.0178 0.0089 2.7489 -0.0200 0.0100 2.7489 primID: 1 startangle_c: 7 endpose_c: -20 10 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0222 0.0111 2.7489 -0.0444 0.0222 2.7489 -0.0667 0.0333 2.7489 -0.0889 0.0444 2.7489 -0.1111 0.0556 2.7489 -0.1333 0.0667 2.7489 -0.1556 0.0778 2.7489 -0.1778 0.0889 2.7489 -0.2000 0.1000 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0022 -0.0011 2.7489 0.0044 -0.0022 2.7489 0.0067 -0.0033 2.7489 0.0089 -0.0044 2.7489 0.0111 -0.0056 2.7489 0.0133 -0.0067 2.7489 0.0156 -0.0078 2.7489 0.0178 -0.0089 2.7489 0.0200 -0.0100 2.7489 primID: 3 startangle_c: 7 endpose_c: -25 20 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -35 10 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0011 0.0000 3.1416 -0.0022 0.0000 3.1416 -0.0033 0.0000 3.1416 -0.0044 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0067 0.0000 3.1416 -0.0078 0.0000 3.1416 -0.0089 0.0000 3.1416 -0.0100 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -20 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0667 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1111 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1556 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0011 0.0000 3.1416 0.0022 0.0000 3.1416 0.0033 0.0000 3.1416 0.0044 0.0000 3.1416 0.0056 0.0000 3.1416 0.0067 0.0000 3.1416 0.0078 0.0000 3.1416 0.0089 0.0000 3.1416 0.0100 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -40 -5 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -40 5 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0022 -0.0011 3.5343 -0.0044 -0.0022 3.5343 -0.0067 -0.0033 3.5343 -0.0089 -0.0044 3.5343 -0.0111 -0.0056 3.5343 -0.0133 -0.0067 3.5343 -0.0156 -0.0078 3.5343 -0.0178 -0.0089 3.5343 -0.0200 -0.0100 3.5343 primID: 1 startangle_c: 9 endpose_c: -20 -10 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0222 -0.0111 3.5343 -0.0444 -0.0222 3.5343 -0.0667 -0.0333 3.5343 -0.0889 -0.0444 3.5343 -0.1111 -0.0556 3.5343 -0.1333 -0.0667 3.5343 -0.1556 -0.0778 3.5343 -0.1778 -0.0889 3.5343 -0.2000 -0.1000 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0022 0.0011 3.5343 0.0044 0.0022 3.5343 0.0067 0.0033 3.5343 0.0089 0.0044 3.5343 0.0111 0.0056 3.5343 0.0133 0.0067 3.5343 0.0156 0.0078 3.5343 0.0178 0.0089 3.5343 0.0200 0.0100 3.5343 primID: 3 startangle_c: 9 endpose_c: -25 -20 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -35 -10 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0011 -0.0011 3.9270 -0.0022 -0.0022 3.9270 -0.0033 -0.0033 3.9270 -0.0044 -0.0044 3.9270 -0.0056 -0.0056 3.9270 -0.0067 -0.0067 3.9270 -0.0078 -0.0078 3.9270 -0.0089 -0.0089 3.9270 -0.0100 -0.0100 3.9270 primID: 1 startangle_c: 10 endpose_c: -10 -10 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0111 -0.0111 3.9270 -0.0222 -0.0222 3.9270 -0.0333 -0.0333 3.9270 -0.0444 -0.0444 3.9270 -0.0556 -0.0556 3.9270 -0.0667 -0.0667 3.9270 -0.0778 -0.0778 3.9270 -0.0889 -0.0889 3.9270 -0.1000 -0.1000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0011 0.0011 3.9270 0.0022 0.0022 3.9270 0.0033 0.0033 3.9270 0.0044 0.0044 3.9270 0.0056 0.0056 3.9270 0.0067 0.0067 3.9270 0.0078 0.0078 3.9270 0.0089 0.0089 3.9270 0.0100 0.0100 3.9270 primID: 3 startangle_c: 10 endpose_c: -25 -35 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -35 -25 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0011 -0.0022 4.3197 -0.0022 -0.0044 4.3197 -0.0033 -0.0067 4.3197 -0.0044 -0.0089 4.3197 -0.0056 -0.0111 4.3197 -0.0067 -0.0133 4.3197 -0.0078 -0.0156 4.3197 -0.0089 -0.0178 4.3197 -0.0100 -0.0200 4.3197 primID: 1 startangle_c: 11 endpose_c: -10 -20 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0111 -0.0222 4.3197 -0.0222 -0.0444 4.3197 -0.0333 -0.0667 4.3197 -0.0444 -0.0889 4.3197 -0.0556 -0.1111 4.3197 -0.0667 -0.1333 4.3197 -0.0778 -0.1556 4.3197 -0.0889 -0.1778 4.3197 -0.1000 -0.2000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0011 0.0022 4.3197 0.0022 0.0044 4.3197 0.0033 0.0067 4.3197 0.0044 0.0089 4.3197 0.0056 0.0111 4.3197 0.0067 0.0133 4.3197 0.0078 0.0156 4.3197 0.0089 0.0178 4.3197 0.0100 0.0200 4.3197 primID: 3 startangle_c: 11 endpose_c: -20 -25 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -10 -35 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0011 4.7124 0.0000 -0.0022 4.7124 0.0000 -0.0033 4.7124 0.0000 -0.0044 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0067 4.7124 0.0000 -0.0078 4.7124 0.0000 -0.0089 4.7124 0.0000 -0.0100 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -20 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0667 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1111 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1556 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0011 4.7124 0.0000 0.0022 4.7124 0.0000 0.0033 4.7124 0.0000 0.0044 4.7124 0.0000 0.0056 4.7124 0.0000 0.0067 4.7124 0.0000 0.0078 4.7124 0.0000 0.0089 4.7124 0.0000 0.0100 4.7124 primID: 3 startangle_c: 12 endpose_c: 5 -40 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0452 4.7124 0.0000 -0.0904 4.7124 0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -5 -40 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0011 -0.0022 5.1051 0.0022 -0.0044 5.1051 0.0033 -0.0067 5.1051 0.0044 -0.0089 5.1051 0.0056 -0.0111 5.1051 0.0067 -0.0133 5.1051 0.0078 -0.0156 5.1051 0.0089 -0.0178 5.1051 0.0100 -0.0200 5.1051 primID: 1 startangle_c: 13 endpose_c: 10 -20 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0111 -0.0222 5.1051 0.0222 -0.0444 5.1051 0.0333 -0.0667 5.1051 0.0444 -0.0889 5.1051 0.0556 -0.1111 5.1051 0.0667 -0.1333 5.1051 0.0778 -0.1556 5.1051 0.0889 -0.1778 5.1051 0.1000 -0.2000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0011 0.0022 5.1051 -0.0022 0.0044 5.1051 -0.0033 0.0067 5.1051 -0.0044 0.0089 5.1051 -0.0056 0.0111 5.1051 -0.0067 0.0133 5.1051 -0.0078 0.0156 5.1051 -0.0089 0.0178 5.1051 -0.0100 0.0200 5.1051 primID: 3 startangle_c: 13 endpose_c: 20 -25 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 10 -35 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0011 -0.0011 5.4978 0.0022 -0.0022 5.4978 0.0033 -0.0033 5.4978 0.0044 -0.0044 5.4978 0.0056 -0.0056 5.4978 0.0067 -0.0067 5.4978 0.0078 -0.0078 5.4978 0.0089 -0.0089 5.4978 0.0100 -0.0100 5.4978 primID: 1 startangle_c: 14 endpose_c: 10 -10 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0111 -0.0111 5.4978 0.0222 -0.0222 5.4978 0.0333 -0.0333 5.4978 0.0444 -0.0444 5.4978 0.0556 -0.0556 5.4978 0.0667 -0.0667 5.4978 0.0778 -0.0778 5.4978 0.0889 -0.0889 5.4978 0.1000 -0.1000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0011 0.0011 5.4978 -0.0022 0.0022 5.4978 -0.0033 0.0033 5.4978 -0.0044 0.0044 5.4978 -0.0056 0.0056 5.4978 -0.0067 0.0067 5.4978 -0.0078 0.0078 5.4978 -0.0089 0.0089 5.4978 -0.0100 0.0100 5.4978 primID: 3 startangle_c: 14 endpose_c: 35 -25 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 25 -35 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0022 -0.0011 5.8905 0.0044 -0.0022 5.8905 0.0067 -0.0033 5.8905 0.0089 -0.0044 5.8905 0.0111 -0.0056 5.8905 0.0133 -0.0067 5.8905 0.0156 -0.0078 5.8905 0.0178 -0.0089 5.8905 0.0200 -0.0100 5.8905 primID: 1 startangle_c: 15 endpose_c: 20 -10 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0222 -0.0111 5.8905 0.0444 -0.0222 5.8905 0.0667 -0.0333 5.8905 0.0889 -0.0444 5.8905 0.1111 -0.0556 5.8905 0.1333 -0.0667 5.8905 0.1556 -0.0778 5.8905 0.1778 -0.0889 5.8905 0.2000 -0.1000 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0022 0.0011 5.8905 -0.0044 0.0022 5.8905 -0.0067 0.0033 5.8905 -0.0089 0.0044 5.8905 -0.0111 0.0056 5.8905 -0.0133 0.0067 5.8905 -0.0156 0.0078 5.8905 -0.0178 0.0089 5.8905 -0.0200 0.0100 5.8905 primID: 3 startangle_c: 15 endpose_c: 25 -20 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 35 -10 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_highcost_2_5cm.mprim ================================================ resolution_m: 0.025000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0028 0.0000 0.0000 0.0056 0.0000 0.0000 0.0083 0.0000 0.0000 0.0111 0.0000 0.0000 0.0139 0.0000 0.0000 0.0167 0.0000 0.0000 0.0194 0.0000 0.0000 0.0222 0.0000 0.0000 0.0250 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 12 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0333 0.0000 0.0000 0.0667 0.0000 0.0000 0.1000 0.0000 0.0000 0.1333 0.0000 0.0000 0.1667 0.0000 0.0000 0.2000 0.0000 0.0000 0.2333 0.0000 0.0000 0.2667 0.0000 0.0000 0.3000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0028 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0083 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0139 0.0000 0.0000 -0.0167 0.0000 0.0000 -0.0194 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0250 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 16 2 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 16 -2 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0056 0.0028 0.3927 0.0111 0.0056 0.3927 0.0167 0.0083 0.3927 0.0222 0.0111 0.3927 0.0278 0.0139 0.3927 0.0333 0.0167 0.3927 0.0389 0.0194 0.3927 0.0444 0.0222 0.3927 0.0500 0.0250 0.3927 primID: 1 startangle_c: 1 endpose_c: 12 6 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0056 -0.0028 0.3927 -0.0111 -0.0056 0.3927 -0.0167 -0.0083 0.3927 -0.0222 -0.0111 0.3927 -0.0278 -0.0139 0.3927 -0.0333 -0.0167 0.3927 -0.0389 -0.0194 0.3927 -0.0444 -0.0222 0.3927 -0.0500 -0.0250 0.3927 primID: 3 startangle_c: 1 endpose_c: 10 8 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 14 4 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 -0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0028 0.0028 0.7854 0.0056 0.0056 0.7854 0.0083 0.0083 0.7854 0.0111 0.0111 0.7854 0.0139 0.0139 0.7854 0.0167 0.0167 0.7854 0.0194 0.0194 0.7854 0.0222 0.0222 0.7854 0.0250 0.0250 0.7854 primID: 1 startangle_c: 2 endpose_c: 12 12 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0028 -0.0028 0.7854 -0.0056 -0.0056 0.7854 -0.0083 -0.0083 0.7854 -0.0111 -0.0111 0.7854 -0.0139 -0.0139 0.7854 -0.0167 -0.0167 0.7854 -0.0194 -0.0194 0.7854 -0.0222 -0.0222 0.7854 -0.0250 -0.0250 0.7854 primID: 3 startangle_c: 2 endpose_c: 10 14 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 14 10 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0028 0.0056 1.1781 0.0056 0.0111 1.1781 0.0083 0.0167 1.1781 0.0111 0.0222 1.1781 0.0139 0.0278 1.1781 0.0167 0.0333 1.1781 0.0194 0.0389 1.1781 0.0222 0.0444 1.1781 0.0250 0.0500 1.1781 primID: 1 startangle_c: 3 endpose_c: 6 12 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0028 -0.0056 1.1781 -0.0056 -0.0111 1.1781 -0.0083 -0.0167 1.1781 -0.0111 -0.0222 1.1781 -0.0139 -0.0278 1.1781 -0.0167 -0.0333 1.1781 -0.0194 -0.0389 1.1781 -0.0222 -0.0444 1.1781 -0.0250 -0.0500 1.1781 primID: 3 startangle_c: 3 endpose_c: 8 10 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 4 14 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0028 1.5708 0.0000 0.0056 1.5708 0.0000 0.0083 1.5708 0.0000 0.0111 1.5708 0.0000 0.0139 1.5708 0.0000 0.0167 1.5708 0.0000 0.0194 1.5708 0.0000 0.0222 1.5708 0.0000 0.0250 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 12 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0333 1.5708 0.0000 0.0667 1.5708 0.0000 0.1000 1.5708 0.0000 0.1333 1.5708 0.0000 0.1667 1.5708 0.0000 0.2000 1.5708 0.0000 0.2333 1.5708 0.0000 0.2667 1.5708 0.0000 0.3000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0028 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0083 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0139 1.5708 0.0000 -0.0167 1.5708 0.0000 -0.0194 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0250 1.5708 primID: 3 startangle_c: 4 endpose_c: -2 16 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 2 16 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0028 0.0056 1.9635 -0.0056 0.0111 1.9635 -0.0083 0.0167 1.9635 -0.0111 0.0222 1.9635 -0.0139 0.0278 1.9635 -0.0167 0.0333 1.9635 -0.0194 0.0389 1.9635 -0.0222 0.0444 1.9635 -0.0250 0.0500 1.9635 primID: 1 startangle_c: 5 endpose_c: -6 12 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0028 -0.0056 1.9635 0.0056 -0.0111 1.9635 0.0083 -0.0167 1.9635 0.0111 -0.0222 1.9635 0.0139 -0.0278 1.9635 0.0167 -0.0333 1.9635 0.0194 -0.0389 1.9635 0.0222 -0.0444 1.9635 0.0250 -0.0500 1.9635 primID: 3 startangle_c: 5 endpose_c: -8 10 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -4 14 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0028 0.0028 2.3562 -0.0056 0.0056 2.3562 -0.0083 0.0083 2.3562 -0.0111 0.0111 2.3562 -0.0139 0.0139 2.3562 -0.0167 0.0167 2.3562 -0.0194 0.0194 2.3562 -0.0222 0.0222 2.3562 -0.0250 0.0250 2.3562 primID: 1 startangle_c: 6 endpose_c: -12 12 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0028 -0.0028 2.3562 0.0056 -0.0056 2.3562 0.0083 -0.0083 2.3562 0.0111 -0.0111 2.3562 0.0139 -0.0139 2.3562 0.0167 -0.0167 2.3562 0.0194 -0.0194 2.3562 0.0222 -0.0222 2.3562 0.0250 -0.0250 2.3562 primID: 3 startangle_c: 6 endpose_c: -14 10 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -10 14 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0056 0.0028 2.7489 -0.0111 0.0056 2.7489 -0.0167 0.0083 2.7489 -0.0222 0.0111 2.7489 -0.0278 0.0139 2.7489 -0.0333 0.0167 2.7489 -0.0389 0.0194 2.7489 -0.0444 0.0222 2.7489 -0.0500 0.0250 2.7489 primID: 1 startangle_c: 7 endpose_c: -12 6 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0056 -0.0028 2.7489 0.0111 -0.0056 2.7489 0.0167 -0.0083 2.7489 0.0222 -0.0111 2.7489 0.0278 -0.0139 2.7489 0.0333 -0.0167 2.7489 0.0389 -0.0194 2.7489 0.0444 -0.0222 2.7489 0.0500 -0.0250 2.7489 primID: 3 startangle_c: 7 endpose_c: -10 8 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -14 4 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0028 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0083 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0139 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0194 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0250 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -12 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0667 0.0000 3.1416 -0.1000 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1667 0.0000 3.1416 -0.2000 0.0000 3.1416 -0.2333 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0028 0.0000 3.1416 0.0056 0.0000 3.1416 0.0083 0.0000 3.1416 0.0111 0.0000 3.1416 0.0139 0.0000 3.1416 0.0167 0.0000 3.1416 0.0194 0.0000 3.1416 0.0222 0.0000 3.1416 0.0250 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -16 -2 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -16 2 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0056 -0.0028 3.5343 -0.0111 -0.0056 3.5343 -0.0167 -0.0083 3.5343 -0.0222 -0.0111 3.5343 -0.0278 -0.0139 3.5343 -0.0333 -0.0167 3.5343 -0.0389 -0.0194 3.5343 -0.0444 -0.0222 3.5343 -0.0500 -0.0250 3.5343 primID: 1 startangle_c: 9 endpose_c: -12 -6 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0056 0.0028 3.5343 0.0111 0.0056 3.5343 0.0167 0.0083 3.5343 0.0222 0.0111 3.5343 0.0278 0.0139 3.5343 0.0333 0.0167 3.5343 0.0389 0.0194 3.5343 0.0444 0.0222 3.5343 0.0500 0.0250 3.5343 primID: 3 startangle_c: 9 endpose_c: -10 -8 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -14 -4 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0028 -0.0028 3.9270 -0.0056 -0.0056 3.9270 -0.0083 -0.0083 3.9270 -0.0111 -0.0111 3.9270 -0.0139 -0.0139 3.9270 -0.0167 -0.0167 3.9270 -0.0194 -0.0194 3.9270 -0.0222 -0.0222 3.9270 -0.0250 -0.0250 3.9270 primID: 1 startangle_c: 10 endpose_c: -12 -12 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0028 0.0028 3.9270 0.0056 0.0056 3.9270 0.0083 0.0083 3.9270 0.0111 0.0111 3.9270 0.0139 0.0139 3.9270 0.0167 0.0167 3.9270 0.0194 0.0194 3.9270 0.0222 0.0222 3.9270 0.0250 0.0250 3.9270 primID: 3 startangle_c: 10 endpose_c: -10 -14 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -14 -10 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0028 -0.0056 4.3197 -0.0056 -0.0111 4.3197 -0.0083 -0.0167 4.3197 -0.0111 -0.0222 4.3197 -0.0139 -0.0278 4.3197 -0.0167 -0.0333 4.3197 -0.0194 -0.0389 4.3197 -0.0222 -0.0444 4.3197 -0.0250 -0.0500 4.3197 primID: 1 startangle_c: 11 endpose_c: -6 -12 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0028 0.0056 4.3197 0.0056 0.0111 4.3197 0.0083 0.0167 4.3197 0.0111 0.0222 4.3197 0.0139 0.0278 4.3197 0.0167 0.0333 4.3197 0.0194 0.0389 4.3197 0.0222 0.0444 4.3197 0.0250 0.0500 4.3197 primID: 3 startangle_c: 11 endpose_c: -8 -10 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -4 -14 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0028 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0083 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0139 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0194 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0250 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -12 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0667 4.7124 0.0000 -0.1000 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1667 4.7124 0.0000 -0.2000 4.7124 0.0000 -0.2333 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0028 4.7124 0.0000 0.0056 4.7124 0.0000 0.0083 4.7124 0.0000 0.0111 4.7124 0.0000 0.0139 4.7124 0.0000 0.0167 4.7124 0.0000 0.0194 4.7124 0.0000 0.0222 4.7124 0.0000 0.0250 4.7124 primID: 3 startangle_c: 12 endpose_c: 2 -16 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0452 4.7124 0.0000 -0.0904 4.7124 0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -2 -16 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0028 -0.0056 5.1051 0.0056 -0.0111 5.1051 0.0083 -0.0167 5.1051 0.0111 -0.0222 5.1051 0.0139 -0.0278 5.1051 0.0167 -0.0333 5.1051 0.0194 -0.0389 5.1051 0.0222 -0.0444 5.1051 0.0250 -0.0500 5.1051 primID: 1 startangle_c: 13 endpose_c: 6 -12 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0028 0.0056 5.1051 -0.0056 0.0111 5.1051 -0.0083 0.0167 5.1051 -0.0111 0.0222 5.1051 -0.0139 0.0278 5.1051 -0.0167 0.0333 5.1051 -0.0194 0.0389 5.1051 -0.0222 0.0444 5.1051 -0.0250 0.0500 5.1051 primID: 3 startangle_c: 13 endpose_c: 8 -10 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 4 -14 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0028 -0.0028 5.4978 0.0056 -0.0056 5.4978 0.0083 -0.0083 5.4978 0.0111 -0.0111 5.4978 0.0139 -0.0139 5.4978 0.0167 -0.0167 5.4978 0.0194 -0.0194 5.4978 0.0222 -0.0222 5.4978 0.0250 -0.0250 5.4978 primID: 1 startangle_c: 14 endpose_c: 12 -12 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0028 0.0028 5.4978 -0.0056 0.0056 5.4978 -0.0083 0.0083 5.4978 -0.0111 0.0111 5.4978 -0.0139 0.0139 5.4978 -0.0167 0.0167 5.4978 -0.0194 0.0194 5.4978 -0.0222 0.0222 5.4978 -0.0250 0.0250 5.4978 primID: 3 startangle_c: 14 endpose_c: 14 -10 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 10 -14 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0056 -0.0028 5.8905 0.0111 -0.0056 5.8905 0.0167 -0.0083 5.8905 0.0222 -0.0111 5.8905 0.0278 -0.0139 5.8905 0.0333 -0.0167 5.8905 0.0389 -0.0194 5.8905 0.0444 -0.0222 5.8905 0.0500 -0.0250 5.8905 primID: 1 startangle_c: 15 endpose_c: 12 -6 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0056 0.0028 5.8905 -0.0111 0.0056 5.8905 -0.0167 0.0083 5.8905 -0.0222 0.0111 5.8905 -0.0278 0.0139 5.8905 -0.0333 0.0167 5.8905 -0.0389 0.0194 5.8905 -0.0444 0.0222 5.8905 -0.0500 0.0250 5.8905 primID: 3 startangle_c: 15 endpose_c: 10 -8 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 14 -4 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_highcost_2cm.mprim ================================================ resolution_m: 0.020000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.0000 0.0022 0.0000 0.0000 0.0044 0.0000 0.0000 0.0067 0.0000 0.0000 0.0089 0.0000 0.0000 0.0111 0.0000 0.0000 0.0133 0.0000 0.0000 0.0156 0.0000 0.0000 0.0178 0.0000 0.0000 0.0200 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 20 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0022 0.0000 0.0000 -0.0044 0.0000 0.0000 -0.0067 0.0000 0.0000 -0.0089 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0133 0.0000 0.0000 -0.0156 0.0000 0.0000 -0.0178 0.0000 0.0000 -0.0200 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 15 3 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0342 0.0008 0.0434 0.0683 0.0031 0.0868 0.1023 0.0069 0.1302 0.1361 0.0121 0.1736 0.1696 0.0188 0.2170 0.2029 0.0270 0.2604 0.2357 0.0366 0.3038 0.2681 0.0476 0.3472 0.3000 0.0600 0.3906 primID: 4 startangle_c: 0 endpose_c: 15 -3 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0342 -0.0008 -0.0434 0.0683 -0.0031 -0.0868 0.1023 -0.0069 -0.1302 0.1361 -0.0121 -0.1736 0.1696 -0.0188 -0.2170 0.2029 -0.0270 -0.2604 0.2357 -0.0366 -0.3038 0.2681 -0.0476 -0.3472 0.3000 -0.0600 -0.3906 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.3927 0.0044 0.0022 0.3927 0.0089 0.0044 0.3927 0.0133 0.0067 0.3927 0.0178 0.0089 0.3927 0.0222 0.0111 0.3927 0.0267 0.0133 0.3927 0.0311 0.0156 0.3927 0.0356 0.0178 0.3927 0.0400 0.0200 0.3927 primID: 1 startangle_c: 1 endpose_c: 15 8 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0178 0.3927 0.0667 0.0356 0.3927 0.1000 0.0533 0.3927 0.1333 0.0711 0.3927 0.1667 0.0889 0.3927 0.2000 0.1067 0.3927 0.2333 0.1244 0.3927 0.2667 0.1422 0.3927 0.3000 0.1600 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0044 -0.0022 0.3927 -0.0089 -0.0044 0.3927 -0.0133 -0.0067 0.3927 -0.0178 -0.0089 0.3927 -0.0222 -0.0111 0.3927 -0.0267 -0.0133 0.3927 -0.0311 -0.0156 0.3927 -0.0356 -0.0178 0.3927 -0.0400 -0.0200 0.3927 primID: 3 startangle_c: 1 endpose_c: 12 10 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0285 0.0188 0.4210 0.0566 0.0385 0.4492 0.0842 0.0590 0.4775 0.1115 0.0804 0.5057 0.1382 0.1027 0.5340 0.1645 0.1258 0.5623 0.1902 0.1497 0.5905 0.2154 0.1745 0.6188 0.2400 0.2000 0.6470 primID: 4 startangle_c: 1 endpose_c: 18 5 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0387 0.0160 0.3927 0.0774 0.0320 0.3927 0.1161 0.0481 0.3927 0.1549 0.0636 0.3512 0.1947 0.0766 0.2809 0.2353 0.0868 0.2107 0.2765 0.0941 0.1405 0.3182 0.0985 0.0702 0.3600 0.1000 0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 0.7854 0.0022 0.0022 0.7854 0.0044 0.0044 0.7854 0.0067 0.0067 0.7854 0.0089 0.0089 0.7854 0.0111 0.0111 0.7854 0.0133 0.0133 0.7854 0.0156 0.0156 0.7854 0.0178 0.0178 0.7854 0.0200 0.0200 0.7854 primID: 1 startangle_c: 2 endpose_c: 15 15 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0022 -0.0022 0.7854 -0.0044 -0.0044 0.7854 -0.0067 -0.0067 0.7854 -0.0089 -0.0089 0.7854 -0.0111 -0.0111 0.7854 -0.0133 -0.0133 0.7854 -0.0156 -0.0156 0.7854 -0.0178 -0.0178 0.7854 -0.0200 -0.0200 0.7854 primID: 3 startangle_c: 2 endpose_c: 12 18 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0334 0.0350 0.8288 0.0652 0.0714 0.8722 0.0954 0.1092 0.9156 0.1240 0.1482 0.9590 0.1508 0.1885 1.0024 0.1759 0.2299 1.0458 0.1991 0.2723 1.0892 0.2205 0.3157 1.1326 0.2400 0.3600 1.1760 primID: 4 startangle_c: 2 endpose_c: 18 12 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0350 0.0334 0.7420 0.0714 0.0652 0.6986 0.1092 0.0954 0.6552 0.1482 0.1240 0.6118 0.1885 0.1508 0.5684 0.2299 0.1759 0.5250 0.2723 0.1991 0.4816 0.3157 0.2205 0.4382 0.3600 0.2400 0.3948 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.1781 0.0022 0.0044 1.1781 0.0044 0.0089 1.1781 0.0067 0.0133 1.1781 0.0089 0.0178 1.1781 0.0111 0.0222 1.1781 0.0133 0.0267 1.1781 0.0156 0.0311 1.1781 0.0178 0.0356 1.1781 0.0200 0.0400 1.1781 primID: 1 startangle_c: 3 endpose_c: 8 15 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0178 0.0333 1.1781 0.0356 0.0667 1.1781 0.0533 0.1000 1.1781 0.0711 0.1333 1.1781 0.0889 0.1667 1.1781 0.1067 0.2000 1.1781 0.1244 0.2333 1.1781 0.1422 0.2667 1.1781 0.1600 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0022 -0.0044 1.1781 -0.0044 -0.0089 1.1781 -0.0067 -0.0133 1.1781 -0.0089 -0.0178 1.1781 -0.0111 -0.0222 1.1781 -0.0133 -0.0267 1.1781 -0.0156 -0.0311 1.1781 -0.0178 -0.0356 1.1781 -0.0200 -0.0400 1.1781 primID: 3 startangle_c: 3 endpose_c: 10 12 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0188 0.0285 1.1498 0.0385 0.0566 1.1216 0.0590 0.0842 1.0933 0.0804 0.1115 1.0651 0.1027 0.1382 1.0368 0.1258 0.1645 1.0085 0.1497 0.1902 0.9803 0.1745 0.2154 0.9520 0.2000 0.2400 0.9238 primID: 4 startangle_c: 3 endpose_c: 5 18 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0160 0.0387 1.1781 0.0320 0.0774 1.1781 0.0481 0.1161 1.1781 0.0636 0.1549 1.2196 0.0766 0.1947 1.2898 0.0868 0.2353 1.3601 0.0941 0.2765 1.4303 0.0985 0.3182 1.5006 0.1000 0.3600 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0022 1.5708 0.0000 0.0044 1.5708 0.0000 0.0067 1.5708 0.0000 0.0089 1.5708 0.0000 0.0111 1.5708 0.0000 0.0133 1.5708 0.0000 0.0156 1.5708 0.0000 0.0178 1.5708 0.0000 0.0200 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 20 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0022 1.5708 0.0000 -0.0044 1.5708 0.0000 -0.0067 1.5708 0.0000 -0.0089 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0133 1.5708 0.0000 -0.0156 1.5708 0.0000 -0.0178 1.5708 0.0000 -0.0200 1.5708 primID: 3 startangle_c: 4 endpose_c: -3 15 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 -0.0008 0.0342 1.6142 -0.0031 0.0683 1.6576 -0.0069 0.1023 1.7010 -0.0121 0.1361 1.7444 -0.0188 0.1696 1.7878 -0.0270 0.2029 1.8312 -0.0366 0.2357 1.8746 -0.0476 0.2681 1.9180 -0.0600 0.3000 1.9614 primID: 4 startangle_c: 4 endpose_c: 3 15 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0008 0.0342 1.5274 0.0031 0.0683 1.4840 0.0069 0.1023 1.4406 0.0121 0.1361 1.3972 0.0188 0.1696 1.3538 0.0270 0.2029 1.3104 0.0366 0.2357 1.2670 0.0476 0.2681 1.2236 0.0600 0.3000 1.1802 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0022 0.0044 1.9635 -0.0044 0.0089 1.9635 -0.0067 0.0133 1.9635 -0.0089 0.0178 1.9635 -0.0111 0.0222 1.9635 -0.0133 0.0267 1.9635 -0.0156 0.0311 1.9635 -0.0178 0.0356 1.9635 -0.0200 0.0400 1.9635 primID: 1 startangle_c: 5 endpose_c: -8 15 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0178 0.0333 1.9635 -0.0356 0.0667 1.9635 -0.0533 0.1000 1.9635 -0.0711 0.1333 1.9635 -0.0889 0.1667 1.9635 -0.1067 0.2000 1.9635 -0.1244 0.2333 1.9635 -0.1422 0.2667 1.9635 -0.1600 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 1.9635 0.0022 -0.0044 1.9635 0.0044 -0.0089 1.9635 0.0067 -0.0133 1.9635 0.0089 -0.0178 1.9635 0.0111 -0.0222 1.9635 0.0133 -0.0267 1.9635 0.0156 -0.0311 1.9635 0.0178 -0.0356 1.9635 0.0200 -0.0400 1.9635 primID: 3 startangle_c: 5 endpose_c: -10 12 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0188 0.0285 1.9918 -0.0385 0.0566 2.0200 -0.0590 0.0842 2.0483 -0.0804 0.1115 2.0765 -0.1027 0.1382 2.1048 -0.1258 0.1645 2.1330 -0.1497 0.1902 2.1613 -0.1745 0.2154 2.1896 -0.2000 0.2400 2.2178 primID: 4 startangle_c: 5 endpose_c: -5 18 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0160 0.0387 1.9635 -0.0320 0.0774 1.9635 -0.0481 0.1161 1.9635 -0.0636 0.1549 1.9220 -0.0766 0.1947 1.8517 -0.0868 0.2353 1.7815 -0.0941 0.2765 1.7113 -0.0985 0.3182 1.6410 -0.1000 0.3600 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0022 0.0022 2.3562 -0.0044 0.0044 2.3562 -0.0067 0.0067 2.3562 -0.0089 0.0089 2.3562 -0.0111 0.0111 2.3562 -0.0133 0.0133 2.3562 -0.0156 0.0156 2.3562 -0.0178 0.0178 2.3562 -0.0200 0.0200 2.3562 primID: 1 startangle_c: 6 endpose_c: -15 15 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.3562 0.0022 -0.0022 2.3562 0.0044 -0.0044 2.3562 0.0067 -0.0067 2.3562 0.0089 -0.0089 2.3562 0.0111 -0.0111 2.3562 0.0133 -0.0133 2.3562 0.0156 -0.0156 2.3562 0.0178 -0.0178 2.3562 0.0200 -0.0200 2.3562 primID: 3 startangle_c: 6 endpose_c: -18 12 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0350 0.0334 2.3996 -0.0714 0.0652 2.4430 -0.1092 0.0954 2.4864 -0.1482 0.1240 2.5298 -0.1885 0.1508 2.5732 -0.2299 0.1759 2.6166 -0.2723 0.1991 2.6600 -0.3157 0.2205 2.7034 -0.3600 0.2400 2.7468 primID: 4 startangle_c: 6 endpose_c: -12 18 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0334 0.0350 2.3128 -0.0652 0.0714 2.2694 -0.0954 0.1092 2.2260 -0.1240 0.1482 2.1826 -0.1508 0.1885 2.1392 -0.1759 0.2299 2.0958 -0.1991 0.2723 2.0524 -0.2205 0.3157 2.0090 -0.2400 0.3600 1.9656 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0044 0.0022 2.7489 -0.0089 0.0044 2.7489 -0.0133 0.0067 2.7489 -0.0178 0.0089 2.7489 -0.0222 0.0111 2.7489 -0.0267 0.0133 2.7489 -0.0311 0.0156 2.7489 -0.0356 0.0178 2.7489 -0.0400 0.0200 2.7489 primID: 1 startangle_c: 7 endpose_c: -15 8 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0178 2.7489 -0.0667 0.0356 2.7489 -0.1000 0.0533 2.7489 -0.1333 0.0711 2.7489 -0.1667 0.0889 2.7489 -0.2000 0.1067 2.7489 -0.2333 0.1244 2.7489 -0.2667 0.1422 2.7489 -0.3000 0.1600 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 2.7489 0.0044 -0.0022 2.7489 0.0089 -0.0044 2.7489 0.0133 -0.0067 2.7489 0.0178 -0.0089 2.7489 0.0222 -0.0111 2.7489 0.0267 -0.0133 2.7489 0.0311 -0.0156 2.7489 0.0356 -0.0178 2.7489 0.0400 -0.0200 2.7489 primID: 3 startangle_c: 7 endpose_c: -12 10 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0285 0.0188 2.7206 -0.0566 0.0385 2.6924 -0.0842 0.0590 2.6641 -0.1115 0.0804 2.6359 -0.1382 0.1027 2.6076 -0.1645 0.1258 2.5793 -0.1902 0.1497 2.5511 -0.2154 0.1745 2.5228 -0.2400 0.2000 2.4946 primID: 4 startangle_c: 7 endpose_c: -18 5 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0387 0.0160 2.7489 -0.0774 0.0320 2.7489 -0.1161 0.0481 2.7489 -0.1549 0.0636 2.7904 -0.1947 0.0766 2.8606 -0.2353 0.0868 2.9309 -0.2765 0.0941 3.0011 -0.3182 0.0985 3.0714 -0.3600 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0022 0.0000 3.1416 -0.0044 0.0000 3.1416 -0.0067 0.0000 3.1416 -0.0089 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0133 0.0000 3.1416 -0.0156 0.0000 3.1416 -0.0178 0.0000 3.1416 -0.0200 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -20 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.1416 0.0022 0.0000 3.1416 0.0044 0.0000 3.1416 0.0067 0.0000 3.1416 0.0089 0.0000 3.1416 0.0111 0.0000 3.1416 0.0133 0.0000 3.1416 0.0156 0.0000 3.1416 0.0178 0.0000 3.1416 0.0200 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -15 -3 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0342 -0.0008 3.1850 -0.0683 -0.0031 3.2284 -0.1023 -0.0069 3.2718 -0.1361 -0.0121 3.3152 -0.1696 -0.0188 3.3586 -0.2029 -0.0270 3.4020 -0.2357 -0.0366 3.4454 -0.2681 -0.0476 3.4888 -0.3000 -0.0600 3.5322 primID: 4 startangle_c: 8 endpose_c: -15 3 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0342 0.0008 3.0982 -0.0683 0.0031 3.0548 -0.1023 0.0069 3.0114 -0.1361 0.0121 2.9680 -0.1696 0.0188 2.9246 -0.2029 0.0270 2.8812 -0.2357 0.0366 2.8378 -0.2681 0.0476 2.7944 -0.3000 0.0600 2.7510 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0044 -0.0022 3.5343 -0.0089 -0.0044 3.5343 -0.0133 -0.0067 3.5343 -0.0178 -0.0089 3.5343 -0.0222 -0.0111 3.5343 -0.0267 -0.0133 3.5343 -0.0311 -0.0156 3.5343 -0.0356 -0.0178 3.5343 -0.0400 -0.0200 3.5343 primID: 1 startangle_c: 9 endpose_c: -15 -8 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0178 3.5343 -0.0667 -0.0356 3.5343 -0.1000 -0.0533 3.5343 -0.1333 -0.0711 3.5343 -0.1667 -0.0889 3.5343 -0.2000 -0.1067 3.5343 -0.2333 -0.1244 3.5343 -0.2667 -0.1422 3.5343 -0.3000 -0.1600 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.5343 0.0044 0.0022 3.5343 0.0089 0.0044 3.5343 0.0133 0.0067 3.5343 0.0178 0.0089 3.5343 0.0222 0.0111 3.5343 0.0267 0.0133 3.5343 0.0311 0.0156 3.5343 0.0356 0.0178 3.5343 0.0400 0.0200 3.5343 primID: 3 startangle_c: 9 endpose_c: -12 -10 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0285 -0.0188 3.5626 -0.0566 -0.0385 3.5908 -0.0842 -0.0590 3.6191 -0.1115 -0.0804 3.6473 -0.1382 -0.1027 3.6756 -0.1645 -0.1258 3.7038 -0.1902 -0.1497 3.7321 -0.2154 -0.1745 3.7604 -0.2400 -0.2000 3.7886 primID: 4 startangle_c: 9 endpose_c: -18 -5 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0387 -0.0160 3.5343 -0.0774 -0.0320 3.5343 -0.1161 -0.0481 3.5343 -0.1549 -0.0636 3.4928 -0.1947 -0.0766 3.4225 -0.2353 -0.0868 3.3523 -0.2765 -0.0941 3.2821 -0.3182 -0.0985 3.2118 -0.3600 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0022 -0.0022 3.9270 -0.0044 -0.0044 3.9270 -0.0067 -0.0067 3.9270 -0.0089 -0.0089 3.9270 -0.0111 -0.0111 3.9270 -0.0133 -0.0133 3.9270 -0.0156 -0.0156 3.9270 -0.0178 -0.0178 3.9270 -0.0200 -0.0200 3.9270 primID: 1 startangle_c: 10 endpose_c: -15 -15 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 3.9270 0.0022 0.0022 3.9270 0.0044 0.0044 3.9270 0.0067 0.0067 3.9270 0.0089 0.0089 3.9270 0.0111 0.0111 3.9270 0.0133 0.0133 3.9270 0.0156 0.0156 3.9270 0.0178 0.0178 3.9270 0.0200 0.0200 3.9270 primID: 3 startangle_c: 10 endpose_c: -12 -18 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0334 -0.0350 3.9704 -0.0652 -0.0714 4.0138 -0.0954 -0.1092 4.0572 -0.1240 -0.1482 4.1006 -0.1508 -0.1885 4.1440 -0.1759 -0.2299 4.1874 -0.1991 -0.2723 4.2308 -0.2205 -0.3157 4.2742 -0.2400 -0.3600 4.3176 primID: 4 startangle_c: 10 endpose_c: -18 -12 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0350 -0.0334 3.8836 -0.0714 -0.0652 3.8402 -0.1092 -0.0954 3.7968 -0.1482 -0.1240 3.7534 -0.1885 -0.1508 3.7100 -0.2299 -0.1759 3.6666 -0.2723 -0.1991 3.6232 -0.3157 -0.2205 3.5798 -0.3600 -0.2400 3.5364 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0022 -0.0044 4.3197 -0.0044 -0.0089 4.3197 -0.0067 -0.0133 4.3197 -0.0089 -0.0178 4.3197 -0.0111 -0.0222 4.3197 -0.0133 -0.0267 4.3197 -0.0156 -0.0311 4.3197 -0.0178 -0.0356 4.3197 -0.0200 -0.0400 4.3197 primID: 1 startangle_c: 11 endpose_c: -8 -15 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0178 -0.0333 4.3197 -0.0356 -0.0667 4.3197 -0.0533 -0.1000 4.3197 -0.0711 -0.1333 4.3197 -0.0889 -0.1667 4.3197 -0.1067 -0.2000 4.3197 -0.1244 -0.2333 4.3197 -0.1422 -0.2667 4.3197 -0.1600 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.3197 0.0022 0.0044 4.3197 0.0044 0.0089 4.3197 0.0067 0.0133 4.3197 0.0089 0.0178 4.3197 0.0111 0.0222 4.3197 0.0133 0.0267 4.3197 0.0156 0.0311 4.3197 0.0178 0.0356 4.3197 0.0200 0.0400 4.3197 primID: 3 startangle_c: 11 endpose_c: -10 -12 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0188 -0.0285 4.2914 -0.0385 -0.0566 4.2632 -0.0590 -0.0842 4.2349 -0.0804 -0.1115 4.2067 -0.1027 -0.1382 4.1784 -0.1258 -0.1645 4.1501 -0.1497 -0.1902 4.1219 -0.1745 -0.2154 4.0936 -0.2000 -0.2400 4.0654 primID: 4 startangle_c: 11 endpose_c: -5 -18 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0160 -0.0387 4.3197 -0.0320 -0.0774 4.3197 -0.0481 -0.1161 4.3197 -0.0636 -0.1549 4.3612 -0.0766 -0.1947 4.4314 -0.0868 -0.2353 4.5017 -0.0941 -0.2765 4.5719 -0.0985 -0.3182 4.6422 -0.1000 -0.3600 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0022 4.7124 0.0000 -0.0044 4.7124 0.0000 -0.0067 4.7124 0.0000 -0.0089 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0133 4.7124 0.0000 -0.0156 4.7124 0.0000 -0.0178 4.7124 0.0000 -0.0200 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -20 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0022 4.7124 0.0000 0.0044 4.7124 0.0000 0.0067 4.7124 0.0000 0.0089 4.7124 0.0000 0.0111 4.7124 0.0000 0.0133 4.7124 0.0000 0.0156 4.7124 0.0000 0.0178 4.7124 0.0000 0.0200 4.7124 primID: 3 startangle_c: 12 endpose_c: 3 -15 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0008 -0.0342 4.7558 0.0031 -0.0683 4.7992 0.0069 -0.1023 4.8426 0.0121 -0.1361 4.8860 0.0188 -0.1696 4.9294 0.0270 -0.2029 4.9728 0.0366 -0.2357 5.0162 0.0476 -0.2681 5.0596 0.0600 -0.3000 5.1030 primID: 4 startangle_c: 12 endpose_c: -3 -15 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0008 -0.0342 4.6690 -0.0031 -0.0683 4.6256 -0.0069 -0.1023 4.5822 -0.0121 -0.1361 4.5388 -0.0188 -0.1696 4.4954 -0.0270 -0.2029 4.4520 -0.0366 -0.2357 4.4086 -0.0476 -0.2681 4.3652 -0.0600 -0.3000 4.3218 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.1051 0.0022 -0.0044 5.1051 0.0044 -0.0089 5.1051 0.0067 -0.0133 5.1051 0.0089 -0.0178 5.1051 0.0111 -0.0222 5.1051 0.0133 -0.0267 5.1051 0.0156 -0.0311 5.1051 0.0178 -0.0356 5.1051 0.0200 -0.0400 5.1051 primID: 1 startangle_c: 13 endpose_c: 8 -15 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0178 -0.0333 5.1051 0.0356 -0.0667 5.1051 0.0533 -0.1000 5.1051 0.0711 -0.1333 5.1051 0.0889 -0.1667 5.1051 0.1067 -0.2000 5.1051 0.1244 -0.2333 5.1051 0.1422 -0.2667 5.1051 0.1600 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0022 0.0044 5.1051 -0.0044 0.0089 5.1051 -0.0067 0.0133 5.1051 -0.0089 0.0178 5.1051 -0.0111 0.0222 5.1051 -0.0133 0.0267 5.1051 -0.0156 0.0311 5.1051 -0.0178 0.0356 5.1051 -0.0200 0.0400 5.1051 primID: 3 startangle_c: 13 endpose_c: 10 -12 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0188 -0.0285 5.1333 0.0385 -0.0566 5.1616 0.0590 -0.0842 5.1899 0.0804 -0.1115 5.2181 0.1027 -0.1382 5.2464 0.1258 -0.1645 5.2746 0.1497 -0.1902 5.3029 0.1745 -0.2154 5.3312 0.2000 -0.2400 5.3594 primID: 4 startangle_c: 13 endpose_c: 5 -18 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0160 -0.0387 5.1051 0.0320 -0.0774 5.1051 0.0481 -0.1161 5.1051 0.0636 -0.1549 5.0636 0.0766 -0.1947 4.9933 0.0868 -0.2353 4.9231 0.0941 -0.2765 4.8529 0.0985 -0.3182 4.7826 0.1000 -0.3600 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.4978 0.0022 -0.0022 5.4978 0.0044 -0.0044 5.4978 0.0067 -0.0067 5.4978 0.0089 -0.0089 5.4978 0.0111 -0.0111 5.4978 0.0133 -0.0133 5.4978 0.0156 -0.0156 5.4978 0.0178 -0.0178 5.4978 0.0200 -0.0200 5.4978 primID: 1 startangle_c: 14 endpose_c: 15 -15 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0022 0.0022 5.4978 -0.0044 0.0044 5.4978 -0.0067 0.0067 5.4978 -0.0089 0.0089 5.4978 -0.0111 0.0111 5.4978 -0.0133 0.0133 5.4978 -0.0156 0.0156 5.4978 -0.0178 0.0178 5.4978 -0.0200 0.0200 5.4978 primID: 3 startangle_c: 14 endpose_c: 18 -12 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0350 -0.0334 5.5412 0.0714 -0.0652 5.5846 0.1092 -0.0954 5.6280 0.1482 -0.1240 5.6714 0.1885 -0.1508 5.7148 0.2299 -0.1759 5.7582 0.2723 -0.1991 5.8016 0.3157 -0.2205 5.8450 0.3600 -0.2400 5.8884 primID: 4 startangle_c: 14 endpose_c: 12 -18 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0334 -0.0350 5.4544 0.0652 -0.0714 5.4110 0.0954 -0.1092 5.3676 0.1240 -0.1482 5.3242 0.1508 -0.1885 5.2808 0.1759 -0.2299 5.2374 0.1991 -0.2723 5.1940 0.2205 -0.3157 5.1506 0.2400 -0.3600 5.1072 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 10 intermediateposes: 10 0.0000 0.0000 5.8905 0.0044 -0.0022 5.8905 0.0089 -0.0044 5.8905 0.0133 -0.0067 5.8905 0.0178 -0.0089 5.8905 0.0222 -0.0111 5.8905 0.0267 -0.0133 5.8905 0.0311 -0.0156 5.8905 0.0356 -0.0178 5.8905 0.0400 -0.0200 5.8905 primID: 1 startangle_c: 15 endpose_c: 15 -8 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0178 5.8905 0.0667 -0.0356 5.8905 0.1000 -0.0533 5.8905 0.1333 -0.0711 5.8905 0.1667 -0.0889 5.8905 0.2000 -0.1067 5.8905 0.2333 -0.1244 5.8905 0.2667 -0.1422 5.8905 0.3000 -0.1600 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 50 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0044 0.0022 5.8905 -0.0089 0.0044 5.8905 -0.0133 0.0067 5.8905 -0.0178 0.0089 5.8905 -0.0222 0.0111 5.8905 -0.0267 0.0133 5.8905 -0.0311 0.0156 5.8905 -0.0356 0.0178 5.8905 -0.0400 0.0200 5.8905 primID: 3 startangle_c: 15 endpose_c: 12 -10 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0285 -0.0188 5.8622 0.0566 -0.0385 5.8340 0.0842 -0.0590 5.8057 0.1115 -0.0804 5.7775 0.1382 -0.1027 5.7492 0.1645 -0.1258 5.7209 0.1902 -0.1497 5.6927 0.2154 -0.1745 5.6644 0.2400 -0.2000 5.6362 primID: 4 startangle_c: 15 endpose_c: 18 -5 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0387 -0.0160 5.8905 0.0774 -0.0320 5.8905 0.1161 -0.0481 5.8905 0.1549 -0.0636 5.9320 0.1947 -0.0766 6.0022 0.2353 -0.0868 6.0725 0.2765 -0.0941 6.1427 0.3182 -0.0985 6.2129 0.3600 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 100 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.2360 0.0000 0.0000 4.5815 0.0000 0.0000 3.9270 0.0000 0.0000 3.2725 0.0000 0.0000 2.6180 0.0000 0.0000 1.9635 0.0000 0.0000 1.3090 0.0000 0.0000 0.6545 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/mprim/unicycle_highcost_5cm.mprim ================================================ resolution_m: 0.050000 numberofangles: 16 totalnumberofprimitives: 112 primID: 0 startangle_c: 0 endpose_c: 1 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0056 0.0000 0.0000 0.0111 0.0000 0.0000 0.0167 0.0000 0.0000 0.0222 0.0000 0.0000 0.0278 0.0000 0.0000 0.0333 0.0000 0.0000 0.0389 0.0000 0.0000 0.0444 0.0000 0.0000 0.0500 0.0000 0.0000 primID: 1 startangle_c: 0 endpose_c: 8 0 0 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.0000 0.0444 0.0000 0.0000 0.0889 0.0000 0.0000 0.1333 0.0000 0.0000 0.1778 0.0000 0.0000 0.2222 0.0000 0.0000 0.2667 0.0000 0.0000 0.3111 0.0000 0.0000 0.3556 0.0000 0.0000 0.4000 0.0000 0.0000 primID: 2 startangle_c: 0 endpose_c: -1 0 0 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 0.0000 -0.0056 0.0000 0.0000 -0.0111 0.0000 0.0000 -0.0167 0.0000 0.0000 -0.0222 0.0000 0.0000 -0.0278 0.0000 0.0000 -0.0333 0.0000 0.0000 -0.0389 0.0000 0.0000 -0.0444 0.0000 0.0000 -0.0500 0.0000 0.0000 primID: 3 startangle_c: 0 endpose_c: 8 1 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 -0.0000 0.0000 0.0904 -0.0000 0.0000 0.1355 -0.0000 0.0000 0.1807 0.0008 0.0488 0.2257 0.0045 0.1176 0.2703 0.0114 0.1864 0.3144 0.0213 0.2551 0.3577 0.0342 0.3239 0.4000 0.0500 0.3927 primID: 4 startangle_c: 0 endpose_c: 8 -1 -1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.0000 0.0452 0.0000 0.0000 0.0904 0.0000 0.0000 0.1355 0.0000 0.0000 0.1807 -0.0008 -0.0488 0.2257 -0.0045 -0.1176 0.2703 -0.0114 -0.1864 0.3144 -0.0213 -0.2551 0.3577 -0.0342 -0.3239 0.4000 -0.0500 -0.3927 primID: 5 startangle_c: 0 endpose_c: 0 0 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 0.0436 0.0000 0.0000 0.0873 0.0000 0.0000 0.1309 0.0000 0.0000 0.1745 0.0000 0.0000 0.2182 0.0000 0.0000 0.2618 0.0000 0.0000 0.3054 0.0000 0.0000 0.3491 0.0000 0.0000 0.3927 primID: 6 startangle_c: 0 endpose_c: 0 0 -1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.0000 0.0000 0.0000 -0.0436 0.0000 0.0000 -0.0873 0.0000 0.0000 -0.1309 0.0000 0.0000 -0.1745 0.0000 0.0000 -0.2182 0.0000 0.0000 -0.2618 0.0000 0.0000 -0.3054 0.0000 0.0000 -0.3491 0.0000 0.0000 -0.3927 primID: 0 startangle_c: 1 endpose_c: 2 1 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0111 0.0056 0.3927 0.0222 0.0111 0.3927 0.0333 0.0167 0.3927 0.0444 0.0222 0.3927 0.0556 0.0278 0.3927 0.0667 0.0333 0.3927 0.0778 0.0389 0.3927 0.0889 0.0444 0.3927 0.1000 0.0500 0.3927 primID: 1 startangle_c: 1 endpose_c: 6 3 1 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.3927 0.0333 0.0167 0.3927 0.0667 0.0333 0.3927 0.1000 0.0500 0.3927 0.1333 0.0667 0.3927 0.1667 0.0833 0.3927 0.2000 0.1000 0.3927 0.2333 0.1167 0.3927 0.2667 0.1333 0.3927 0.3000 0.1500 0.3927 primID: 2 startangle_c: 1 endpose_c: -2 -1 1 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 0.3927 -0.0111 -0.0056 0.3927 -0.0222 -0.0111 0.3927 -0.0333 -0.0167 0.3927 -0.0444 -0.0222 0.3927 -0.0556 -0.0278 0.3927 -0.0667 -0.0333 0.3927 -0.0778 -0.0389 0.3927 -0.0889 -0.0444 0.3927 -0.1000 -0.0500 0.3927 primID: 3 startangle_c: 1 endpose_c: 5 4 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0298 0.0184 0.4230 0.0592 0.0379 0.4533 0.0881 0.0583 0.4836 0.1165 0.0796 0.5139 0.1444 0.1019 0.5442 0.1717 0.1251 0.5745 0.1984 0.1492 0.6048 0.2245 0.1742 0.6351 0.2500 0.2000 0.6654 primID: 4 startangle_c: 1 endpose_c: 7 2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.3927 0.0377 0.0156 0.3927 0.0754 0.0312 0.3927 0.1131 0.0468 0.3927 0.1508 0.0623 0.3736 0.1893 0.0758 0.2989 0.2287 0.0863 0.2242 0.2687 0.0939 0.1494 0.3092 0.0985 0.0747 0.3500 0.1000 -0.0000 primID: 5 startangle_c: 1 endpose_c: 0 0 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.4363 0.0000 0.0000 0.4800 0.0000 0.0000 0.5236 0.0000 0.0000 0.5672 0.0000 0.0000 0.6109 0.0000 0.0000 0.6545 0.0000 0.0000 0.6981 0.0000 0.0000 0.7418 0.0000 0.0000 0.7854 primID: 6 startangle_c: 1 endpose_c: 0 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.3927 0.0000 0.0000 0.3491 0.0000 0.0000 0.3054 0.0000 0.0000 0.2618 0.0000 0.0000 0.2182 0.0000 0.0000 0.1745 0.0000 0.0000 0.1309 0.0000 0.0000 0.0873 0.0000 0.0000 0.0436 0.0000 0.0000 0.0000 primID: 0 startangle_c: 2 endpose_c: 1 1 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0056 0.0056 0.7854 0.0111 0.0111 0.7854 0.0167 0.0167 0.7854 0.0222 0.0222 0.7854 0.0278 0.0278 0.7854 0.0333 0.0333 0.7854 0.0389 0.0389 0.7854 0.0444 0.0444 0.7854 0.0500 0.0500 0.7854 primID: 1 startangle_c: 2 endpose_c: 6 6 2 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 0.7854 0.0333 0.0333 0.7854 0.0667 0.0667 0.7854 0.1000 0.1000 0.7854 0.1333 0.1333 0.7854 0.1667 0.1667 0.7854 0.2000 0.2000 0.7854 0.2333 0.2333 0.7854 0.2667 0.2667 0.7854 0.3000 0.3000 0.7854 primID: 2 startangle_c: 2 endpose_c: -1 -1 2 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 0.7854 -0.0056 -0.0056 0.7854 -0.0111 -0.0111 0.7854 -0.0167 -0.0167 0.7854 -0.0222 -0.0222 0.7854 -0.0278 -0.0278 0.7854 -0.0333 -0.0333 0.7854 -0.0389 -0.0389 0.7854 -0.0444 -0.0444 0.7854 -0.0500 -0.0500 0.7854 primID: 3 startangle_c: 2 endpose_c: 5 7 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0678 0.0684 0.8151 0.1000 0.1043 0.8669 0.1302 0.1418 0.9188 0.1584 0.1809 0.9707 0.1846 0.2213 1.0225 0.2086 0.2631 1.0744 0.2304 0.3060 1.1262 0.2500 0.3500 1.1781 primID: 4 startangle_c: 2 endpose_c: 7 5 1 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 0.7854 0.0341 0.0341 0.7854 0.0684 0.0678 0.7557 0.1043 0.1000 0.7039 0.1418 0.1302 0.6520 0.1809 0.1584 0.6001 0.2213 0.1846 0.5483 0.2631 0.2086 0.4964 0.3060 0.2304 0.4446 0.3500 0.2500 0.3927 primID: 5 startangle_c: 2 endpose_c: 0 0 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.8290 0.0000 0.0000 0.8727 0.0000 0.0000 0.9163 0.0000 0.0000 0.9599 0.0000 0.0000 1.0036 0.0000 0.0000 1.0472 0.0000 0.0000 1.0908 0.0000 0.0000 1.1345 0.0000 0.0000 1.1781 primID: 6 startangle_c: 2 endpose_c: 0 0 1 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 0.7854 0.0000 0.0000 0.7418 0.0000 0.0000 0.6981 0.0000 0.0000 0.6545 0.0000 0.0000 0.6109 0.0000 0.0000 0.5672 0.0000 0.0000 0.5236 0.0000 0.0000 0.4800 0.0000 0.0000 0.4363 0.0000 0.0000 0.3927 primID: 0 startangle_c: 3 endpose_c: 1 2 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0056 0.0111 1.1781 0.0111 0.0222 1.1781 0.0167 0.0333 1.1781 0.0222 0.0444 1.1781 0.0278 0.0556 1.1781 0.0333 0.0667 1.1781 0.0389 0.0778 1.1781 0.0444 0.0889 1.1781 0.0500 0.1000 1.1781 primID: 1 startangle_c: 3 endpose_c: 3 6 3 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.1781 0.0167 0.0333 1.1781 0.0333 0.0667 1.1781 0.0500 0.1000 1.1781 0.0667 0.1333 1.1781 0.0833 0.1667 1.1781 0.1000 0.2000 1.1781 0.1167 0.2333 1.1781 0.1333 0.2667 1.1781 0.1500 0.3000 1.1781 primID: 2 startangle_c: 3 endpose_c: -1 -2 3 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 1.1781 -0.0056 -0.0111 1.1781 -0.0111 -0.0222 1.1781 -0.0167 -0.0333 1.1781 -0.0222 -0.0444 1.1781 -0.0278 -0.0556 1.1781 -0.0333 -0.0667 1.1781 -0.0389 -0.0778 1.1781 -0.0444 -0.0889 1.1781 -0.0500 -0.1000 1.1781 primID: 3 startangle_c: 3 endpose_c: 4 5 2 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0184 0.0298 1.1478 0.0379 0.0592 1.1175 0.0583 0.0881 1.0872 0.0796 0.1165 1.0569 0.1019 0.1444 1.0266 0.1251 0.1717 0.9963 0.1492 0.1984 0.9660 0.1742 0.2245 0.9357 0.2000 0.2500 0.9054 primID: 4 startangle_c: 3 endpose_c: 2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.1781 0.0156 0.0377 1.1781 0.0312 0.0754 1.1781 0.0468 0.1131 1.1781 0.0623 0.1508 1.1972 0.0758 0.1893 1.2719 0.0863 0.2287 1.3466 0.0939 0.2687 1.4214 0.0985 0.3092 1.4961 0.1000 0.3500 1.5708 primID: 5 startangle_c: 3 endpose_c: 0 0 2 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.1345 0.0000 0.0000 1.0908 0.0000 0.0000 1.0472 0.0000 0.0000 1.0036 0.0000 0.0000 0.9599 0.0000 0.0000 0.9163 0.0000 0.0000 0.8727 0.0000 0.0000 0.8290 0.0000 0.0000 0.7854 primID: 6 startangle_c: 3 endpose_c: 0 0 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.1781 0.0000 0.0000 1.2217 0.0000 0.0000 1.2654 0.0000 0.0000 1.3090 0.0000 0.0000 1.3526 0.0000 0.0000 1.3963 0.0000 0.0000 1.4399 0.0000 0.0000 1.4835 0.0000 0.0000 1.5272 0.0000 0.0000 1.5708 primID: 0 startangle_c: 4 endpose_c: 0 1 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0056 1.5708 0.0000 0.0111 1.5708 0.0000 0.0167 1.5708 0.0000 0.0222 1.5708 0.0000 0.0278 1.5708 0.0000 0.0333 1.5708 0.0000 0.0389 1.5708 0.0000 0.0444 1.5708 0.0000 0.0500 1.5708 primID: 1 startangle_c: 4 endpose_c: 0 8 4 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0444 1.5708 0.0000 0.0889 1.5708 0.0000 0.1333 1.5708 0.0000 0.1778 1.5708 0.0000 0.2222 1.5708 0.0000 0.2667 1.5708 0.0000 0.3111 1.5708 0.0000 0.3556 1.5708 0.0000 0.4000 1.5708 primID: 2 startangle_c: 4 endpose_c: 0 -1 4 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 -0.0056 1.5708 0.0000 -0.0111 1.5708 0.0000 -0.0167 1.5708 0.0000 -0.0222 1.5708 0.0000 -0.0278 1.5708 0.0000 -0.0333 1.5708 0.0000 -0.0389 1.5708 0.0000 -0.0444 1.5708 0.0000 -0.0500 1.5708 primID: 3 startangle_c: 4 endpose_c: -1 8 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 -0.0008 0.1807 1.6196 -0.0045 0.2257 1.6884 -0.0114 0.2703 1.7572 -0.0213 0.3144 1.8259 -0.0342 0.3577 1.8947 -0.0500 0.4000 1.9635 primID: 4 startangle_c: 4 endpose_c: 1 8 3 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0452 1.5708 0.0000 0.0904 1.5708 0.0000 0.1355 1.5708 0.0008 0.1807 1.5220 0.0045 0.2257 1.4532 0.0114 0.2703 1.3844 0.0213 0.3144 1.3156 0.0342 0.3577 1.2469 0.0500 0.4000 1.1781 primID: 5 startangle_c: 4 endpose_c: 0 0 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.6144 0.0000 0.0000 1.6581 0.0000 0.0000 1.7017 0.0000 0.0000 1.7453 0.0000 0.0000 1.7890 0.0000 0.0000 1.8326 0.0000 0.0000 1.8762 0.0000 0.0000 1.9199 0.0000 0.0000 1.9635 primID: 6 startangle_c: 4 endpose_c: 0 0 3 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.5708 0.0000 0.0000 1.5272 0.0000 0.0000 1.4835 0.0000 0.0000 1.4399 0.0000 0.0000 1.3963 0.0000 0.0000 1.3526 0.0000 0.0000 1.3090 0.0000 0.0000 1.2654 0.0000 0.0000 1.2217 0.0000 0.0000 1.1781 primID: 0 startangle_c: 5 endpose_c: -1 2 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0056 0.0111 1.9635 -0.0111 0.0222 1.9635 -0.0167 0.0333 1.9635 -0.0222 0.0444 1.9635 -0.0278 0.0556 1.9635 -0.0333 0.0667 1.9635 -0.0389 0.0778 1.9635 -0.0444 0.0889 1.9635 -0.0500 0.1000 1.9635 primID: 1 startangle_c: 5 endpose_c: -3 6 5 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0167 0.0333 1.9635 -0.0333 0.0667 1.9635 -0.0500 0.1000 1.9635 -0.0667 0.1333 1.9635 -0.0833 0.1667 1.9635 -0.1000 0.2000 1.9635 -0.1167 0.2333 1.9635 -0.1333 0.2667 1.9635 -0.1500 0.3000 1.9635 primID: 2 startangle_c: 5 endpose_c: 1 -2 5 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 1.9635 0.0056 -0.0111 1.9635 0.0111 -0.0222 1.9635 0.0167 -0.0333 1.9635 0.0222 -0.0444 1.9635 0.0278 -0.0556 1.9635 0.0333 -0.0667 1.9635 0.0389 -0.0778 1.9635 0.0444 -0.0889 1.9635 0.0500 -0.1000 1.9635 primID: 3 startangle_c: 5 endpose_c: -4 5 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0184 0.0298 1.9938 -0.0379 0.0592 2.0241 -0.0583 0.0881 2.0544 -0.0796 0.1165 2.0847 -0.1019 0.1444 2.1150 -0.1251 0.1717 2.1453 -0.1492 0.1984 2.1756 -0.1742 0.2245 2.2059 -0.2000 0.2500 2.2362 primID: 4 startangle_c: 5 endpose_c: -2 7 4 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 1.9635 -0.0156 0.0377 1.9635 -0.0312 0.0754 1.9635 -0.0468 0.1131 1.9635 -0.0623 0.1508 1.9444 -0.0758 0.1893 1.8697 -0.0863 0.2287 1.7950 -0.0939 0.2687 1.7202 -0.0985 0.3092 1.6455 -0.1000 0.3500 1.5708 primID: 5 startangle_c: 5 endpose_c: 0 0 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 2.0071 0.0000 0.0000 2.0508 0.0000 0.0000 2.0944 0.0000 0.0000 2.1380 0.0000 0.0000 2.1817 0.0000 0.0000 2.2253 0.0000 0.0000 2.2689 0.0000 0.0000 2.3126 0.0000 0.0000 2.3562 primID: 6 startangle_c: 5 endpose_c: 0 0 4 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 1.9635 0.0000 0.0000 1.9199 0.0000 0.0000 1.8762 0.0000 0.0000 1.8326 0.0000 0.0000 1.7890 0.0000 0.0000 1.7453 0.0000 0.0000 1.7017 0.0000 0.0000 1.6581 0.0000 0.0000 1.6144 0.0000 0.0000 1.5708 primID: 0 startangle_c: 6 endpose_c: -1 1 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0056 0.0056 2.3562 -0.0111 0.0111 2.3562 -0.0167 0.0167 2.3562 -0.0222 0.0222 2.3562 -0.0278 0.0278 2.3562 -0.0333 0.0333 2.3562 -0.0389 0.0389 2.3562 -0.0444 0.0444 2.3562 -0.0500 0.0500 2.3562 primID: 1 startangle_c: 6 endpose_c: -6 6 6 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0333 0.0333 2.3562 -0.0667 0.0667 2.3562 -0.1000 0.1000 2.3562 -0.1333 0.1333 2.3562 -0.1667 0.1667 2.3562 -0.2000 0.2000 2.3562 -0.2333 0.2333 2.3562 -0.2667 0.2667 2.3562 -0.3000 0.3000 2.3562 primID: 2 startangle_c: 6 endpose_c: 1 -1 6 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 2.3562 0.0056 -0.0056 2.3562 0.0111 -0.0111 2.3562 0.0167 -0.0167 2.3562 0.0222 -0.0222 2.3562 0.0278 -0.0278 2.3562 0.0333 -0.0333 2.3562 0.0389 -0.0389 2.3562 0.0444 -0.0444 2.3562 0.0500 -0.0500 2.3562 primID: 3 startangle_c: 6 endpose_c: -7 5 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0684 0.0678 2.3859 -0.1043 0.1000 2.4377 -0.1418 0.1302 2.4896 -0.1809 0.1584 2.5415 -0.2213 0.1846 2.5933 -0.2631 0.2086 2.6452 -0.3060 0.2304 2.6970 -0.3500 0.2500 2.7489 primID: 4 startangle_c: 6 endpose_c: -5 7 5 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.3562 -0.0341 0.0341 2.3562 -0.0678 0.0684 2.3265 -0.1000 0.1043 2.2747 -0.1302 0.1418 2.2228 -0.1584 0.1809 2.1709 -0.1846 0.2213 2.1191 -0.2086 0.2631 2.0672 -0.2304 0.3060 2.0154 -0.2500 0.3500 1.9635 primID: 5 startangle_c: 6 endpose_c: 0 0 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3998 0.0000 0.0000 2.4435 0.0000 0.0000 2.4871 0.0000 0.0000 2.5307 0.0000 0.0000 2.5744 0.0000 0.0000 2.6180 0.0000 0.0000 2.6616 0.0000 0.0000 2.7053 0.0000 0.0000 2.7489 primID: 6 startangle_c: 6 endpose_c: 0 0 5 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.3562 0.0000 0.0000 2.3126 0.0000 0.0000 2.2689 0.0000 0.0000 2.2253 0.0000 0.0000 2.1817 0.0000 0.0000 2.1380 0.0000 0.0000 2.0944 0.0000 0.0000 2.0508 0.0000 0.0000 2.0071 0.0000 0.0000 1.9635 primID: 0 startangle_c: 7 endpose_c: -2 1 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0111 0.0056 2.7489 -0.0222 0.0111 2.7489 -0.0333 0.0167 2.7489 -0.0444 0.0222 2.7489 -0.0556 0.0278 2.7489 -0.0667 0.0333 2.7489 -0.0778 0.0389 2.7489 -0.0889 0.0444 2.7489 -0.1000 0.0500 2.7489 primID: 1 startangle_c: 7 endpose_c: -6 3 7 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0333 0.0167 2.7489 -0.0667 0.0333 2.7489 -0.1000 0.0500 2.7489 -0.1333 0.0667 2.7489 -0.1667 0.0833 2.7489 -0.2000 0.1000 2.7489 -0.2333 0.1167 2.7489 -0.2667 0.1333 2.7489 -0.3000 0.1500 2.7489 primID: 2 startangle_c: 7 endpose_c: 2 -1 7 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 2.7489 0.0111 -0.0056 2.7489 0.0222 -0.0111 2.7489 0.0333 -0.0167 2.7489 0.0444 -0.0222 2.7489 0.0556 -0.0278 2.7489 0.0667 -0.0333 2.7489 0.0778 -0.0389 2.7489 0.0889 -0.0444 2.7489 0.1000 -0.0500 2.7489 primID: 3 startangle_c: 7 endpose_c: -5 4 6 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0298 0.0184 2.7186 -0.0592 0.0379 2.6883 -0.0881 0.0583 2.6580 -0.1165 0.0796 2.6277 -0.1444 0.1019 2.5974 -0.1717 0.1251 2.5671 -0.1984 0.1492 2.5368 -0.2245 0.1742 2.5065 -0.2500 0.2000 2.4762 primID: 4 startangle_c: 7 endpose_c: -7 2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 2.7489 -0.0377 0.0156 2.7489 -0.0754 0.0312 2.7489 -0.1131 0.0468 2.7489 -0.1508 0.0623 2.7680 -0.1893 0.0758 2.8427 -0.2287 0.0863 2.9174 -0.2687 0.0939 2.9921 -0.3092 0.0985 3.0669 -0.3500 0.1000 3.1416 primID: 5 startangle_c: 7 endpose_c: 0 0 6 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7053 0.0000 0.0000 2.6616 0.0000 0.0000 2.6180 0.0000 0.0000 2.5744 0.0000 0.0000 2.5307 0.0000 0.0000 2.4871 0.0000 0.0000 2.4435 0.0000 0.0000 2.3998 0.0000 0.0000 2.3562 primID: 6 startangle_c: 7 endpose_c: 0 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 2.7489 0.0000 0.0000 2.7925 0.0000 0.0000 2.8362 0.0000 0.0000 2.8798 0.0000 0.0000 2.9234 0.0000 0.0000 2.9671 0.0000 0.0000 3.0107 0.0000 0.0000 3.0543 0.0000 0.0000 3.0980 0.0000 0.0000 3.1416 primID: 0 startangle_c: 8 endpose_c: -1 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0056 0.0000 3.1416 -0.0111 0.0000 3.1416 -0.0167 0.0000 3.1416 -0.0222 0.0000 3.1416 -0.0278 0.0000 3.1416 -0.0333 0.0000 3.1416 -0.0389 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0500 0.0000 3.1416 primID: 1 startangle_c: 8 endpose_c: -8 0 8 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0444 0.0000 3.1416 -0.0889 0.0000 3.1416 -0.1333 0.0000 3.1416 -0.1778 0.0000 3.1416 -0.2222 0.0000 3.1416 -0.2667 0.0000 3.1416 -0.3111 0.0000 3.1416 -0.3556 0.0000 3.1416 -0.4000 0.0000 3.1416 primID: 2 startangle_c: 8 endpose_c: 1 0 8 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 3.1416 0.0056 0.0000 3.1416 0.0111 0.0000 3.1416 0.0167 0.0000 3.1416 0.0222 0.0000 3.1416 0.0278 0.0000 3.1416 0.0333 0.0000 3.1416 0.0389 0.0000 3.1416 0.0444 0.0000 3.1416 0.0500 0.0000 3.1416 primID: 3 startangle_c: 8 endpose_c: -8 -1 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 -0.0008 3.1904 -0.2257 -0.0045 3.2592 -0.2703 -0.0114 3.3280 -0.3144 -0.0213 3.3967 -0.3577 -0.0342 3.4655 -0.4000 -0.0500 3.5343 primID: 4 startangle_c: 8 endpose_c: -8 1 7 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.1416 -0.0452 0.0000 3.1416 -0.0904 0.0000 3.1416 -0.1355 0.0000 3.1416 -0.1807 0.0008 3.0928 -0.2257 0.0045 3.0240 -0.2703 0.0114 2.9552 -0.3144 0.0213 2.8864 -0.3577 0.0342 2.8177 -0.4000 0.0500 2.7489 primID: 5 startangle_c: 8 endpose_c: 0 0 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.1852 0.0000 0.0000 3.2289 0.0000 0.0000 3.2725 0.0000 0.0000 3.3161 0.0000 0.0000 3.3598 0.0000 0.0000 3.4034 0.0000 0.0000 3.4470 0.0000 0.0000 3.4907 0.0000 0.0000 3.5343 primID: 6 startangle_c: 8 endpose_c: 0 0 7 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.1416 0.0000 0.0000 3.0980 0.0000 0.0000 3.0543 0.0000 0.0000 3.0107 0.0000 0.0000 2.9671 0.0000 0.0000 2.9234 0.0000 0.0000 2.8798 0.0000 0.0000 2.8362 0.0000 0.0000 2.7925 0.0000 0.0000 2.7489 primID: 0 startangle_c: 9 endpose_c: -2 -1 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0111 -0.0056 3.5343 -0.0222 -0.0111 3.5343 -0.0333 -0.0167 3.5343 -0.0444 -0.0222 3.5343 -0.0556 -0.0278 3.5343 -0.0667 -0.0333 3.5343 -0.0778 -0.0389 3.5343 -0.0889 -0.0444 3.5343 -0.1000 -0.0500 3.5343 primID: 1 startangle_c: 9 endpose_c: -6 -3 9 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0333 -0.0167 3.5343 -0.0667 -0.0333 3.5343 -0.1000 -0.0500 3.5343 -0.1333 -0.0667 3.5343 -0.1667 -0.0833 3.5343 -0.2000 -0.1000 3.5343 -0.2333 -0.1167 3.5343 -0.2667 -0.1333 3.5343 -0.3000 -0.1500 3.5343 primID: 2 startangle_c: 9 endpose_c: 2 1 9 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 3.5343 0.0111 0.0056 3.5343 0.0222 0.0111 3.5343 0.0333 0.0167 3.5343 0.0444 0.0222 3.5343 0.0556 0.0278 3.5343 0.0667 0.0333 3.5343 0.0778 0.0389 3.5343 0.0889 0.0444 3.5343 0.1000 0.0500 3.5343 primID: 3 startangle_c: 9 endpose_c: -5 -4 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0298 -0.0184 3.5646 -0.0592 -0.0379 3.5949 -0.0881 -0.0583 3.6252 -0.1165 -0.0796 3.6555 -0.1444 -0.1019 3.6858 -0.1717 -0.1251 3.7161 -0.1984 -0.1492 3.7464 -0.2245 -0.1742 3.7767 -0.2500 -0.2000 3.8070 primID: 4 startangle_c: 9 endpose_c: -7 -2 8 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.5343 -0.0377 -0.0156 3.5343 -0.0754 -0.0312 3.5343 -0.1131 -0.0468 3.5343 -0.1508 -0.0623 3.5152 -0.1893 -0.0758 3.4405 -0.2287 -0.0863 3.3658 -0.2687 -0.0939 3.2910 -0.3092 -0.0985 3.2163 -0.3500 -0.1000 3.1416 primID: 5 startangle_c: 9 endpose_c: 0 0 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.5779 0.0000 0.0000 3.6216 0.0000 0.0000 3.6652 0.0000 0.0000 3.7088 0.0000 0.0000 3.7525 0.0000 0.0000 3.7961 0.0000 0.0000 3.8397 0.0000 0.0000 3.8834 0.0000 0.0000 3.9270 primID: 6 startangle_c: 9 endpose_c: 0 0 8 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.5343 0.0000 0.0000 3.4907 0.0000 0.0000 3.4470 0.0000 0.0000 3.4034 0.0000 0.0000 3.3598 0.0000 0.0000 3.3161 0.0000 0.0000 3.2725 0.0000 0.0000 3.2289 0.0000 0.0000 3.1852 0.0000 0.0000 3.1416 primID: 0 startangle_c: 10 endpose_c: -1 -1 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0056 -0.0056 3.9270 -0.0111 -0.0111 3.9270 -0.0167 -0.0167 3.9270 -0.0222 -0.0222 3.9270 -0.0278 -0.0278 3.9270 -0.0333 -0.0333 3.9270 -0.0389 -0.0389 3.9270 -0.0444 -0.0444 3.9270 -0.0500 -0.0500 3.9270 primID: 1 startangle_c: 10 endpose_c: -6 -6 10 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0333 -0.0333 3.9270 -0.0667 -0.0667 3.9270 -0.1000 -0.1000 3.9270 -0.1333 -0.1333 3.9270 -0.1667 -0.1667 3.9270 -0.2000 -0.2000 3.9270 -0.2333 -0.2333 3.9270 -0.2667 -0.2667 3.9270 -0.3000 -0.3000 3.9270 primID: 2 startangle_c: 10 endpose_c: 1 1 10 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 3.9270 0.0056 0.0056 3.9270 0.0111 0.0111 3.9270 0.0167 0.0167 3.9270 0.0222 0.0222 3.9270 0.0278 0.0278 3.9270 0.0333 0.0333 3.9270 0.0389 0.0389 3.9270 0.0444 0.0444 3.9270 0.0500 0.0500 3.9270 primID: 3 startangle_c: 10 endpose_c: -5 -7 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0678 -0.0684 3.9567 -0.1000 -0.1043 4.0085 -0.1302 -0.1418 4.0604 -0.1584 -0.1809 4.1123 -0.1846 -0.2213 4.1641 -0.2086 -0.2631 4.2160 -0.2304 -0.3060 4.2678 -0.2500 -0.3500 4.3197 primID: 4 startangle_c: 10 endpose_c: -7 -5 9 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 3.9270 -0.0341 -0.0341 3.9270 -0.0684 -0.0678 3.8973 -0.1043 -0.1000 3.8455 -0.1418 -0.1302 3.7936 -0.1809 -0.1584 3.7417 -0.2213 -0.1846 3.6899 -0.2631 -0.2086 3.6380 -0.3060 -0.2304 3.5862 -0.3500 -0.2500 3.5343 primID: 5 startangle_c: 10 endpose_c: 0 0 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.9706 0.0000 0.0000 4.0143 0.0000 0.0000 4.0579 0.0000 0.0000 4.1015 0.0000 0.0000 4.1452 0.0000 0.0000 4.1888 0.0000 0.0000 4.2324 0.0000 0.0000 4.2761 0.0000 0.0000 4.3197 primID: 6 startangle_c: 10 endpose_c: 0 0 9 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 3.9270 0.0000 0.0000 3.8834 0.0000 0.0000 3.8397 0.0000 0.0000 3.7961 0.0000 0.0000 3.7525 0.0000 0.0000 3.7088 0.0000 0.0000 3.6652 0.0000 0.0000 3.6216 0.0000 0.0000 3.5779 0.0000 0.0000 3.5343 primID: 0 startangle_c: 11 endpose_c: -1 -2 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0056 -0.0111 4.3197 -0.0111 -0.0222 4.3197 -0.0167 -0.0333 4.3197 -0.0222 -0.0444 4.3197 -0.0278 -0.0556 4.3197 -0.0333 -0.0667 4.3197 -0.0389 -0.0778 4.3197 -0.0444 -0.0889 4.3197 -0.0500 -0.1000 4.3197 primID: 1 startangle_c: 11 endpose_c: -3 -6 11 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0167 -0.0333 4.3197 -0.0333 -0.0667 4.3197 -0.0500 -0.1000 4.3197 -0.0667 -0.1333 4.3197 -0.0833 -0.1667 4.3197 -0.1000 -0.2000 4.3197 -0.1167 -0.2333 4.3197 -0.1333 -0.2667 4.3197 -0.1500 -0.3000 4.3197 primID: 2 startangle_c: 11 endpose_c: 1 2 11 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 4.3197 0.0056 0.0111 4.3197 0.0111 0.0222 4.3197 0.0167 0.0333 4.3197 0.0222 0.0444 4.3197 0.0278 0.0556 4.3197 0.0333 0.0667 4.3197 0.0389 0.0778 4.3197 0.0444 0.0889 4.3197 0.0500 0.1000 4.3197 primID: 3 startangle_c: 11 endpose_c: -4 -5 10 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0184 -0.0298 4.2894 -0.0379 -0.0592 4.2591 -0.0583 -0.0881 4.2288 -0.0796 -0.1165 4.1985 -0.1019 -0.1444 4.1682 -0.1251 -0.1717 4.1379 -0.1492 -0.1984 4.1076 -0.1742 -0.2245 4.0773 -0.2000 -0.2500 4.0470 primID: 4 startangle_c: 11 endpose_c: -2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.3197 -0.0156 -0.0377 4.3197 -0.0312 -0.0754 4.3197 -0.0468 -0.1131 4.3197 -0.0623 -0.1508 4.3388 -0.0758 -0.1893 4.4135 -0.0863 -0.2287 4.4882 -0.0939 -0.2687 4.5629 -0.0985 -0.3092 4.6377 -0.1000 -0.3500 4.7124 primID: 5 startangle_c: 11 endpose_c: 0 0 10 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.2761 0.0000 0.0000 4.2324 0.0000 0.0000 4.1888 0.0000 0.0000 4.1452 0.0000 0.0000 4.1015 0.0000 0.0000 4.0579 0.0000 0.0000 4.0143 0.0000 0.0000 3.9706 0.0000 0.0000 3.9270 primID: 6 startangle_c: 11 endpose_c: 0 0 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.3197 0.0000 0.0000 4.3633 0.0000 0.0000 4.4070 0.0000 0.0000 4.4506 0.0000 0.0000 4.4942 0.0000 0.0000 4.5379 0.0000 0.0000 4.5815 0.0000 0.0000 4.6251 0.0000 0.0000 4.6688 0.0000 0.0000 4.7124 primID: 0 startangle_c: 12 endpose_c: 0 -1 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0056 4.7124 0.0000 -0.0111 4.7124 0.0000 -0.0167 4.7124 0.0000 -0.0222 4.7124 0.0000 -0.0278 4.7124 0.0000 -0.0333 4.7124 0.0000 -0.0389 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0500 4.7124 primID: 1 startangle_c: 12 endpose_c: 0 -8 12 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0444 4.7124 0.0000 -0.0889 4.7124 0.0000 -0.1333 4.7124 0.0000 -0.1778 4.7124 0.0000 -0.2222 4.7124 0.0000 -0.2667 4.7124 0.0000 -0.3111 4.7124 0.0000 -0.3556 4.7124 0.0000 -0.4000 4.7124 primID: 2 startangle_c: 12 endpose_c: 0 1 12 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0056 4.7124 0.0000 0.0111 4.7124 0.0000 0.0167 4.7124 0.0000 0.0222 4.7124 0.0000 0.0278 4.7124 0.0000 0.0333 4.7124 0.0000 0.0389 4.7124 0.0000 0.0444 4.7124 0.0000 0.0500 4.7124 primID: 3 startangle_c: 12 endpose_c: 1 -8 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 -0.0452 4.7124 0.0000 -0.0904 4.7124 0.0000 -0.1355 4.7124 0.0008 -0.1807 4.7612 0.0045 -0.2257 4.8300 0.0114 -0.2703 4.8988 0.0213 -0.3144 4.9675 0.0342 -0.3577 5.0363 0.0500 -0.4000 5.1051 primID: 4 startangle_c: 12 endpose_c: -1 -8 11 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 4.7124 -0.0000 -0.0452 4.7124 -0.0000 -0.0904 4.7124 -0.0000 -0.1355 4.7124 -0.0008 -0.1807 4.6636 -0.0045 -0.2257 4.5948 -0.0114 -0.2703 4.5260 -0.0213 -0.3144 4.4572 -0.0342 -0.3577 4.3885 -0.0500 -0.4000 4.3197 primID: 5 startangle_c: 12 endpose_c: 0 0 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.7560 0.0000 0.0000 4.7997 0.0000 0.0000 4.8433 0.0000 0.0000 4.8869 0.0000 0.0000 4.9306 0.0000 0.0000 4.9742 0.0000 0.0000 5.0178 0.0000 0.0000 5.0615 0.0000 0.0000 5.1051 primID: 6 startangle_c: 12 endpose_c: 0 0 11 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 4.7124 0.0000 0.0000 4.6688 0.0000 0.0000 4.6251 0.0000 0.0000 4.5815 0.0000 0.0000 4.5379 0.0000 0.0000 4.4942 0.0000 0.0000 4.4506 0.0000 0.0000 4.4070 0.0000 0.0000 4.3633 0.0000 0.0000 4.3197 primID: 0 startangle_c: 13 endpose_c: 1 -2 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0056 -0.0111 5.1051 0.0111 -0.0222 5.1051 0.0167 -0.0333 5.1051 0.0222 -0.0444 5.1051 0.0278 -0.0556 5.1051 0.0333 -0.0667 5.1051 0.0389 -0.0778 5.1051 0.0444 -0.0889 5.1051 0.0500 -0.1000 5.1051 primID: 1 startangle_c: 13 endpose_c: 3 -6 13 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.1051 0.0167 -0.0333 5.1051 0.0333 -0.0667 5.1051 0.0500 -0.1000 5.1051 0.0667 -0.1333 5.1051 0.0833 -0.1667 5.1051 0.1000 -0.2000 5.1051 0.1167 -0.2333 5.1051 0.1333 -0.2667 5.1051 0.1500 -0.3000 5.1051 primID: 2 startangle_c: 13 endpose_c: -1 2 13 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 5.1051 -0.0056 0.0111 5.1051 -0.0111 0.0222 5.1051 -0.0167 0.0333 5.1051 -0.0222 0.0444 5.1051 -0.0278 0.0556 5.1051 -0.0333 0.0667 5.1051 -0.0389 0.0778 5.1051 -0.0444 0.0889 5.1051 -0.0500 0.1000 5.1051 primID: 3 startangle_c: 13 endpose_c: 4 -5 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0184 -0.0298 5.1354 0.0379 -0.0592 5.1657 0.0583 -0.0881 5.1960 0.0796 -0.1165 5.2263 0.1019 -0.1444 5.2566 0.1251 -0.1717 5.2869 0.1492 -0.1984 5.3172 0.1742 -0.2245 5.3475 0.2000 -0.2500 5.3778 primID: 4 startangle_c: 13 endpose_c: 2 -7 12 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.1051 0.0156 -0.0377 5.1051 0.0312 -0.0754 5.1051 0.0468 -0.1131 5.1051 0.0623 -0.1508 5.0860 0.0758 -0.1893 5.0113 0.0863 -0.2287 4.9366 0.0939 -0.2687 4.8618 0.0985 -0.3092 4.7871 0.1000 -0.3500 4.7124 primID: 5 startangle_c: 13 endpose_c: 0 0 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.1487 0.0000 0.0000 5.1924 0.0000 0.0000 5.2360 0.0000 0.0000 5.2796 0.0000 0.0000 5.3233 0.0000 0.0000 5.3669 0.0000 0.0000 5.4105 0.0000 0.0000 5.4542 0.0000 0.0000 5.4978 primID: 6 startangle_c: 13 endpose_c: 0 0 12 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.1051 0.0000 0.0000 5.0615 0.0000 0.0000 5.0178 0.0000 0.0000 4.9742 0.0000 0.0000 4.9306 0.0000 0.0000 4.8869 0.0000 0.0000 4.8433 0.0000 0.0000 4.7997 0.0000 0.0000 4.7560 0.0000 0.0000 4.7124 primID: 0 startangle_c: 14 endpose_c: 1 -1 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0056 -0.0056 5.4978 0.0111 -0.0111 5.4978 0.0167 -0.0167 5.4978 0.0222 -0.0222 5.4978 0.0278 -0.0278 5.4978 0.0333 -0.0333 5.4978 0.0389 -0.0389 5.4978 0.0444 -0.0444 5.4978 0.0500 -0.0500 5.4978 primID: 1 startangle_c: 14 endpose_c: 6 -6 14 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.4978 0.0333 -0.0333 5.4978 0.0667 -0.0667 5.4978 0.1000 -0.1000 5.4978 0.1333 -0.1333 5.4978 0.1667 -0.1667 5.4978 0.2000 -0.2000 5.4978 0.2333 -0.2333 5.4978 0.2667 -0.2667 5.4978 0.3000 -0.3000 5.4978 primID: 2 startangle_c: 14 endpose_c: -1 1 14 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 5.4978 -0.0056 0.0056 5.4978 -0.0111 0.0111 5.4978 -0.0167 0.0167 5.4978 -0.0222 0.0222 5.4978 -0.0278 0.0278 5.4978 -0.0333 0.0333 5.4978 -0.0389 0.0389 5.4978 -0.0444 0.0444 5.4978 -0.0500 0.0500 5.4978 primID: 3 startangle_c: 14 endpose_c: 7 -5 15 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0684 -0.0678 5.5275 0.1043 -0.1000 5.5793 0.1418 -0.1302 5.6312 0.1809 -0.1584 5.6830 0.2213 -0.1846 5.7349 0.2631 -0.2086 5.7868 0.3060 -0.2304 5.8386 0.3500 -0.2500 5.8905 primID: 4 startangle_c: 14 endpose_c: 5 -7 13 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.4978 0.0341 -0.0341 5.4978 0.0678 -0.0684 5.4681 0.1000 -0.1043 5.4162 0.1302 -0.1418 5.3644 0.1584 -0.1809 5.3125 0.1846 -0.2213 5.2607 0.2086 -0.2631 5.2088 0.2304 -0.3060 5.1569 0.2500 -0.3500 5.1051 primID: 5 startangle_c: 14 endpose_c: 0 0 15 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.5414 0.0000 0.0000 5.5851 0.0000 0.0000 5.6287 0.0000 0.0000 5.6723 0.0000 0.0000 5.7160 0.0000 0.0000 5.7596 0.0000 0.0000 5.8032 0.0000 0.0000 5.8469 0.0000 0.0000 5.8905 primID: 6 startangle_c: 14 endpose_c: 0 0 13 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.4978 0.0000 0.0000 5.4542 0.0000 0.0000 5.4105 0.0000 0.0000 5.3669 0.0000 0.0000 5.3233 0.0000 0.0000 5.2796 0.0000 0.0000 5.2360 0.0000 0.0000 5.1924 0.0000 0.0000 5.1487 0.0000 0.0000 5.1051 primID: 0 startangle_c: 15 endpose_c: 2 -1 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0111 -0.0056 5.8905 0.0222 -0.0111 5.8905 0.0333 -0.0167 5.8905 0.0444 -0.0222 5.8905 0.0556 -0.0278 5.8905 0.0667 -0.0333 5.8905 0.0778 -0.0389 5.8905 0.0889 -0.0444 5.8905 0.1000 -0.0500 5.8905 primID: 1 startangle_c: 15 endpose_c: 6 -3 15 additionalactioncostmult: 1 intermediateposes: 10 0.0000 0.0000 5.8905 0.0333 -0.0167 5.8905 0.0667 -0.0333 5.8905 0.1000 -0.0500 5.8905 0.1333 -0.0667 5.8905 0.1667 -0.0833 5.8905 0.2000 -0.1000 5.8905 0.2333 -0.1167 5.8905 0.2667 -0.1333 5.8905 0.3000 -0.1500 5.8905 primID: 2 startangle_c: 15 endpose_c: -2 1 15 additionalactioncostmult: 40 intermediateposes: 10 0.0000 0.0000 5.8905 -0.0111 0.0056 5.8905 -0.0222 0.0111 5.8905 -0.0333 0.0167 5.8905 -0.0444 0.0222 5.8905 -0.0556 0.0278 5.8905 -0.0667 0.0333 5.8905 -0.0778 0.0389 5.8905 -0.0889 0.0444 5.8905 -0.1000 0.0500 5.8905 primID: 3 startangle_c: 15 endpose_c: 5 -4 14 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0298 -0.0184 5.8602 0.0592 -0.0379 5.8299 0.0881 -0.0583 5.7996 0.1165 -0.0796 5.7693 0.1444 -0.1019 5.7390 0.1717 -0.1251 5.7087 0.1984 -0.1492 5.6784 0.2245 -0.1742 5.6481 0.2500 -0.2000 5.6178 primID: 4 startangle_c: 15 endpose_c: 7 -2 0 additionalactioncostmult: 2 intermediateposes: 10 0.0000 0.0000 5.8905 0.0377 -0.0156 5.8905 0.0754 -0.0312 5.8905 0.1131 -0.0468 5.8905 0.1508 -0.0623 5.9096 0.1893 -0.0758 5.9843 0.2287 -0.0863 6.0590 0.2687 -0.0939 6.1337 0.3092 -0.0985 6.2085 0.3500 -0.1000 6.2832 primID: 5 startangle_c: 15 endpose_c: 0 0 14 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.8469 0.0000 0.0000 5.8032 0.0000 0.0000 5.7596 0.0000 0.0000 5.7160 0.0000 0.0000 5.6723 0.0000 0.0000 5.6287 0.0000 0.0000 5.5851 0.0000 0.0000 5.5414 0.0000 0.0000 5.4978 primID: 6 startangle_c: 15 endpose_c: 0 0 0 additionalactioncostmult: 20 intermediateposes: 10 0.0000 0.0000 5.8905 0.0000 0.0000 5.9341 0.0000 0.0000 5.9778 0.0000 0.0000 6.0214 0.0000 0.0000 6.0650 0.0000 0.0000 6.1087 0.0000 0.0000 6.1523 0.0000 0.0000 6.1959 0.0000 0.0000 6.2396 0.0000 0.0000 0.0000 ================================================ FILE: mir_navigation/nodes/acc_finder.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry LIN_MAX = 1.0 ANG_MAX = 1.5 # adjust this value to the rough maximum angular velocity state = 'stopped' start = rospy.Time(0) def odom_cb(msg): global state twist = msg.twist.twist t = (rospy.Time.now() - start).to_sec() if state == 'wait_for_stop': if -0.05 < twist.linear.x < 0.05 and -0.1 < twist.angular.z < 0.1: state = 'stopped' rospy.loginfo('state transition --> %s', state) return if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX: rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t) elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX: rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t) elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX: rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t) elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX: rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t) else: return state = 'wait_for_stop' rospy.loginfo('state transition --> %s', state) def cmd_vel_cb(msg): global state, start if state != 'stopped': return if msg.linear.x <= -LIN_MAX: start = rospy.Time.now() state = 'backward' elif msg.linear.x >= LIN_MAX: start = rospy.Time.now() state = 'forward' elif msg.angular.z <= -ANG_MAX: start = rospy.Time.now() state = 'turning_clockwise' elif msg.angular.z >= ANG_MAX: start = rospy.Time.now() state = 'turning_counter_clockwise' else: return rospy.loginfo('state transition --> %s', state) def main(): rospy.init_node('acc_finder', anonymous=True) rospy.Subscriber('odom', Odometry, odom_cb) rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb) rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!') rospy.spin() if __name__ == '__main__': main() ================================================ FILE: mir_navigation/nodes/min_max_finder.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import rospy from nav_msgs.msg import Odometry lin_min = 0.0 lin_max = 0.0 ang_min = 0.0 ang_max = 0.0 def odom_cb(msg): global lin_min, lin_max, ang_min, ang_max if lin_min > msg.twist.twist.linear.x: lin_min = msg.twist.twist.linear.x if lin_max < msg.twist.twist.linear.x: lin_max = msg.twist.twist.linear.x if ang_min > msg.twist.twist.angular.z: ang_min = msg.twist.twist.angular.z if ang_max < msg.twist.twist.angular.z: ang_max = msg.twist.twist.angular.z rospy.loginfo('linear: [%f, %f] angular: [%f, %f]', lin_min, lin_max, ang_min, ang_max) def main(): rospy.init_node('min_max_finder', anonymous=True) rospy.Subscriber('odom', Odometry, odom_cb) rospy.loginfo('min_max_finde node ready and listening. now use teleop to move your robot to the limits!') rospy.spin() if __name__ == '__main__': main() ================================================ FILE: mir_navigation/package.xml ================================================ mir_navigation 1.1.8 Launch and configuration files for move_base, localization etc. on the MiR robot. Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin roslaunch amcl base_local_planner dwa_local_planner dwb_critics dwb_local_planner dwb_plugins hector_mapping map_server mir_driver mir_dwb_critics mir_gazebo move_base nav_core_adapter python3-matplotlib sbpl_lattice_planner teb_local_planner ================================================ FILE: mir_navigation/rviz/navigation.rviz ================================================ Panels: - Class: rviz/Displays Help Height: 81 Name: Displays Property Tree Widget: Expanded: - /Grid1 - /Grid1/Offset1 - /TF1/Frames1 - /TF1/Tree1 - /Local Map1/DWB Markers1/Namespaces1 Splitter Ratio: 0.5 Tree Height: 575 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties Expanded: - /2D Pose Estimate1 - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.588679016 - Class: rviz/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time Experimental: false Name: Time SyncMode: 0 SyncSource: LaserScan Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.0299999993 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 25 Y: 25 Z: 0 Plane: XY Plane Cell Count: 50 Reference Frame: Value: true - Alpha: 1 Class: rviz/RobotModel Collision Enabled: false Enabled: true Links: All Links Enabled: true Expand Joint Details: false Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order back_laser_link: Alpha: 1 Show Axes: false Show Trail: false Value: true base_footprint: Alpha: 1 Show Axes: false Show Trail: false base_link: Alpha: 1 Show Axes: false Show Trail: false Value: true bl_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true bl_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true br_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true br_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fl_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fl_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fr_caster_rotation_link: Alpha: 1 Show Axes: false Show Trail: false Value: true fr_caster_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true front_laser_link: Alpha: 1 Show Axes: false Show Trail: false Value: true imu_frame: Alpha: 1 Show Axes: false Show Trail: false imu_link: Alpha: 1 Show Axes: false Show Trail: false left_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true right_wheel_link: Alpha: 1 Show Axes: false Show Trail: false Value: true surface: Alpha: 1 Show Axes: false Show Trail: false us_1_frame: Alpha: 1 Show Axes: false Show Trail: false us_2_frame: Alpha: 1 Show Axes: false Show Trail: false Name: RobotModel Robot Description: robot_description TF Prefix: "" Update Interval: 0 Value: true Visual Enabled: true - Class: rviz/TF Enabled: false Frame Timeout: 15 Frames: All Enabled: false Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: false Tree: {} Update Interval: 0 Value: false - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/LaserScan Color: 255; 255; 255 Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 0 Min Color: 0; 0; 0 Min Intensity: 0 Name: LaserScan Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0500000007 Style: Squares Topic: scan Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz/PointCloud2 Color: 255; 0; 0 Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 Min Color: 0; 0; 0 Min Intensity: 0 Name: Bumper Hit Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0799999982 Style: Spheres Topic: mobile_base/sensors/bumper_pointcloud Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Alpha: 0.699999988 Class: rviz/Map Color Scheme: map Draw Behind: false Enabled: true Name: Map Topic: /map Unreliable: false Use Timestamp: false Value: true - Class: rviz/Group Displays: - Alpha: 0.699999988 Class: rviz/Map Color Scheme: costmap Draw Behind: true Enabled: true Name: Costmap Topic: move_base_node/global_costmap/costmap Unreliable: false Use Timestamp: false Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 255; 0; 0 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Billboards Line Width: 0.0500000007 Name: Global Plan (DWB) Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: move_base_node/DWBLocalPlanner/transformed_global_plan Unreliable: false Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 25; 255; 0 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Billboards Line Width: 0.0500000007 Name: Full Plan Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: move_base_node/SBPLLatticePlanner/plan Unreliable: false Value: true - Alpha: 1 Class: rviz/Polygon Color: 255; 0; 0 Enabled: true Name: Footprint Topic: move_base_node/global_costmap/footprint Unreliable: false Value: true Enabled: true Name: Global Map - Class: rviz/Group Displays: - Alpha: 0.699999988 Class: rviz/Map Color Scheme: costmap Draw Behind: false Enabled: true Name: Costmap Topic: move_base_node/local_costmap/costmap Unreliable: false Use Timestamp: false Value: true - Alpha: 1 Class: rviz/GridCells Color: 25; 255; 0 Enabled: true Name: Costmap (MiR) Topic: move_base_node/local_costmap/obstacles Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 12; 255 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Billboards Line Width: 0.0500000007 Name: Local Plan (DWB) Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: move_base_node/DWBLocalPlanner/local_plan Unreliable: false Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 0; 12; 255 Enabled: true Head Diameter: 0.300000012 Head Length: 0.200000003 Length: 0.300000012 Line Style: Billboards Line Width: 0.0500000007 Name: Local Plan (MiR) Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Radius: 0.0299999993 Shaft Diameter: 0.100000001 Shaft Length: 0.100000001 Topic: move_base_node/MIRPlannerROS/local_plan Unreliable: false Value: true - Alpha: 1 Class: rviz/Polygon Color: 25; 255; 0 Enabled: true Name: Footprint Topic: move_base_node/local_costmap/footprint Unreliable: false Value: true - Alpha: 0.300000012 Autocompute Intensity Bounds: false Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: total_cost Class: rviz/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 40 Min Color: 0; 0; 0 Min Intensity: 0 Name: Cost Cloud Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.0399999991 Style: Flat Squares Topic: move_base_node/DWBLocalPlanner/cost_cloud Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz/MarkerArray Enabled: true Marker Topic: move_base_node/DWBLocalPlanner/markers Name: DWB Markers Namespaces: InvalidTrajectories: true ValidTrajectories: true Queue Size: 100 Value: true Enabled: true Name: Local Map - Alpha: 1 Arrow Length: 0.200000003 Axes Length: 0.300000012 Axes Radius: 0.00999999978 Class: rviz/PoseArray Color: 0; 192; 0 Enabled: true Head Length: 0.0700000003 Head Radius: 0.0299999993 Name: Amcl Particle Swarm Shaft Length: 0.230000004 Shaft Radius: 0.00999999978 Shape: Arrow (Flat) Topic: particlecloud Unreliable: false Value: false - Class: rviz/Group Displays: - Alpha: 1 Buffer Length: 1 Class: rviz/Path Color: 114; 159; 207 Enabled: true Head Diameter: 0.30000001192092896 Head Length: 0.20000000298023224 Length: 0.30000001192092896 Line Style: Billboards Line Width: 0.05000000074505806 Name: Lookahead Collision Arc (RPP) Offset: X: 0 Y: 0 Z: 0 Pose Color: 255; 85; 255 Pose Style: None Queue Size: 10 Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 Topic: /move_base_node/RegulatedPurePursuitController/lookahead_collision_arc Unreliable: false Value: true - Alpha: 1 Class: rviz/PointStamped Color: 204; 41; 204 Enabled: true History Length: 1 Name: Lookahead Point (RPP) Queue Size: 10 Radius: 0.05000000074505806 Topic: /move_base_node/RegulatedPurePursuitController/lookahead_point Unreliable: false Value: true Enabled: true Name: RPP Enabled: true Global Options: Background Color: 48; 48; 48 Default Light: true Fixed Frame: map Frame Rate: 30 Name: root Tools: - Class: rviz/MoveCamera - Class: rviz/Interact Hide Inactive Objects: true - Class: rviz/Select - Class: rviz/SetInitialPose Topic: initialpose - Class: rviz/SetGoal Topic: move_base_simple/goal - Class: rviz/Measure - Class: rviz/PublishPoint Single click: true Topic: clicked_point Value: true Views: Current: Angle: 0 Class: rviz/TopDownOrtho Enable Stereo Rendering: Stereo Eye Separation: 0.0599999987 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Invert Z Axis: false Name: Current View Near Clip Distance: 0.00999999978 Scale: 68.8703232 Target Frame: Value: TopDownOrtho (rviz) X: 13.2673092 Y: 16.1651554 Saved: ~ Window Geometry: Displays: collapsed: false Height: 818 Hide Left Dock: false Hide Right Dock: false QMainWindow State: 000000ff00000000fd00000004000000000000016a000002d1fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006700fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000043000002d1000000e300ffffff000000010000010f000002d1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000043000002d1000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000022300fffffffb0000000800540069006d006501000000000000045000000000000000000000034b000002d100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1488 X: 254 Y: 36 ================================================ FILE: mir_navigation/scripts/plot_mprim.py ================================================ #!/usr/bin/env python3 # Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # # * Neither the name of the copyright holder nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: Martin Günther import matplotlib.pyplot as plt import numpy as np import sys def get_value(strline, name): if strline.find(name) < 0: raise Exception("File format not matching the parser expectation", name) return strline.replace(name, "", 1) def get_pose(line): ss = line.split() return np.array([float(ss[0]), float(ss[1]), float(ss[2])]) class MPrim: def __init__(self, f): self.primID = int(get_value(f.readline(), "primID:")) self.startAngle = int(get_value(f.readline(), "startangle_c:")) self.endPose = get_pose(get_value(f.readline(), "endpose_c:")) self.cost = float(get_value(f.readline(), "additionalactioncostmult:")) self.nrPoses = int(get_value(f.readline(), "intermediateposes:")) poses = [] for _ in range(self.nrPoses): poses.append(f.readline()) self.poses = np.loadtxt(poses, delimiter=" ") self.cmap = plt.get_cmap("nipy_spectral") def plot(self, nr_angles): plt.plot(self.poses[:, 0], self.poses[:, 1], c=self.cmap(float(self.startAngle) / nr_angles)) class MPrims: def __init__(self, filename): f = open(filename, "r") self.resolution = float(get_value(f.readline(), "resolution_m:")) self.nrAngles = int(get_value(f.readline(), "numberofangles:")) self.nrPrims = int(get_value(f.readline(), "totalnumberofprimitives:")) self.prims = [] for _ in range(self.nrPrims): self.prims.append(MPrim(f)) f.close() def plot(self): fig = plt.figure() ax = fig.add_subplot(111) ax.set_xticks(np.arange(-1, 1, self.resolution)) ax.set_yticks(np.arange(-1, 1, self.resolution)) for prim in self.prims: prim.plot(self.nrAngles) plt.grid() plt.show() prims = MPrims(sys.argv[1]) prims.plot() ================================================ FILE: mir_robot/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package mir_robot ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ 1.1.6 (2022-06-02) ------------------ * Rename mir_100 -> mir This is in preparation of mir_250 support. * Contributors: Martin Günther 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Set cmake_policy CMP0048 to fix warning * Add sdc21x0 dependency to mir_robot meta package * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ 1.0.4 (2019-05-06) ------------------ 1.0.3 (2019-03-04) ------------------ * Add package: mir_dwb_critics * Contributors: Martin Günther 1.0.2 (2018-07-30) ------------------ * Add metapackage * Contributors: Martin Günther 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ ================================================ FILE: mir_robot/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(mir_robot) find_package(catkin REQUIRED) catkin_metapackage() ================================================ FILE: mir_robot/package.xml ================================================ mir_robot 1.1.8 URDF description, Gazebo simulation, navigation, bringup launch files, message and action descriptions for the MiR robot. Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin mir_actions mir_description mir_driver mir_dwb_critics mir_gazebo mir_msgs mir_navigation sdc21x0 ================================================ FILE: pyproject.toml ================================================ [tool.black] line-length = 120 target-version = ['py38'] skip-string-normalization = true ================================================ FILE: sdc21x0/CHANGELOG.rst ================================================ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package sdc21x0 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.1.8 (2025-05-13) ------------------ * package.xml: Use SPDX license declaration * Move repo to DFKI-NI * Contributors: Martin Günther 1.1.7 (2023-01-20) ------------------ * Don't set cmake_policy CMP0048 * Contributors: Martin Günther 1.1.6 (2022-06-02) ------------------ 1.1.5 (2022-02-11) ------------------ 1.1.4 (2021-12-10) ------------------ 1.1.3 (2021-06-11) ------------------ 1.1.2 (2021-05-12) ------------------ 1.1.1 (2021-02-11) ------------------ * Contributors: Martin Günther 1.1.0 (2020-06-30) ------------------ * Initial release into noetic * Contributors: Martin Günther 1.0.6 (2020-06-30) ------------------ * Set cmake_policy CMP0048 to fix warning * Contributors: Martin Günther 1.0.5 (2020-05-01) ------------------ * Add sdc21x0 package, MC/currents topic * Contributors: Martin Günther * Add sdc21x0 package, MC/currents topic * Contributors: Martin Günther 1.0.4 (2019-05-06) ------------------ 1.0.3 (2019-03-04) ------------------ 1.0.2 (2018-07-30) ------------------ 1.0.1 (2018-07-17) ------------------ 1.0.0 (2018-07-12) ------------------ ================================================ FILE: sdc21x0/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.5.1) project(sdc21x0) find_package(catkin REQUIRED COMPONENTS message_generation std_msgs ) ################################################ ## Declare ROS messages, services and actions ## ################################################ # Generate messages in the 'msg' folder add_message_files( FILES Encoders.msg MotorCurrents.msg StampedEncoders.msg ) # Generate services in the 'srv' folder add_service_files( FILES Flags.srv ) # Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs ) ################################### ## catkin specific configuration ## ################################### catkin_package( CATKIN_DEPENDS message_runtime std_msgs ) ================================================ FILE: sdc21x0/msg/Encoders.msg ================================================ float32 time_delta # Time since last encoder update. int32 left_wheel # Encoder counts (absolute or relative) int32 right_wheel # Encoder counts (absolute or relative) ================================================ FILE: sdc21x0/msg/MotorCurrents.msg ================================================ float32 left_motor float32 right_motor ================================================ FILE: sdc21x0/msg/StampedEncoders.msg ================================================ Header header Encoders encoders ================================================ FILE: sdc21x0/package.xml ================================================ sdc21x0 1.1.8 Message definitions for the sdc21x0 motor controller Martin Günther Martin Günther BSD-3-Clause https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot https://github.com/DFKI-NI/mir_robot/issues catkin std_msgs message_generation message_runtime ================================================ FILE: sdc21x0/srv/Flags.srv ================================================ int32 digitalPort --- bool response