Full Code of dfki-ric/mir_robot for AI

noetic c08dfad93be5 cached
187 files
677.4 KB
303.0k tokens
75 symbols
1 requests
Download .txt
Showing preview only (728K chars total). Download the full file or copy to clipboard to get everything.
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 <your catkin workspace>
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 @@
       <remap from="$(arg namespace)/mobile_base_controller/cmd_vel" to="$(arg namespace)/cmd_vel" />
       <remap from="$(arg namespace)/mobile_base_controller/odom"    to="$(arg namespace)/odom" />

+      <remap from="mir2/joint_states"                   to="mir2/mir/joint_states" />
+      <remap from="mir2/mobile_base_controller/cmd_vel" to="mir2/cmd_vel" />
+      <remap from="mir2/mobile_base_controller/odom"    to="mir2/odom" />
+
       <include file="$(find gazebo_ros)/launch/empty_world.launch">
         <arg name="world_name" value="$(arg world_name)"/>
         <arg name="paused" value="true" />
```

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 <https://github.com/DFKI-NI/mir_robot/issues/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
================================================
<?xml version="1.0"?>
<package format="2">
  <name>mir_actions</name>
  <version>1.1.8</version>
  <description>Action definitions for the MiR robot</description>

  <maintainer email="martin.guenther@dfki.de">Martin Günther</maintainer>
  <author email="martin.guenther@dfki.de">Martin Günther</author>

  <license>BSD-3-Clause</license>

  <url type="website">https://github.com/DFKI-NI/mir_robot</url>
  <url type="repository">https://github.com/DFKI-NI/mir_robot</url>
  <url type="bugtracker">https://github.com/DFKI-NI/mir_robot/issues</url>

  <buildtool_depend>catkin</buildtool_depend>

  <depend>actionlib</depend>
  <depend>geometry_msgs</depend>
  <depend>mir_msgs</depend>
  <depend>nav_msgs</depend>

  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend>
</package>


================================================
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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/1>`_
  `#32 <https://github.com/DFKI-NI/mir_robot/issues/32>`_
  `#46 <https://github.com/DFKI-NI/mir_robot/issues/46>`_
  `#52 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/19>`_)
* Contributors: Martin Günther, niniemann

1.0.3 (2019-03-04)
------------------
* Merge pull request `#16 <https://github.com/DFKI-NI/mir_robot/issues/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
================================================
<?xml version="1.0" ?>

<launch>
  <arg name="mir_type" default="mir_100" doc="The MiR variant. Can be 'mir_100' or 'mir_250' for now." />
  <arg name="gui" default="true" />

  <!-- load MiR URDF -->
  <include file="$(find mir_description)/launch/upload_mir_urdf.launch">
    <arg name="mir_type" value="$(arg mir_type)" />
  </include>

  <node if="$(arg gui)"     name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
  <node unless="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher"     type="joint_state_publisher" />

  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find mir_description)/rviz/mir_description.rviz" required="true" />
</launch>


================================================
FILE: mir_description/launch/upload_mir_urdf.launch
================================================
<?xml version="1.0" ?>
<launch>
  <arg name="mir_type"  default="mir_100" doc="The MiR variant. Can be 'mir_100' or 'mir_250' for now." />
  <arg name="tf_prefix" default="" doc="TF prefix to use for all of the MiR's TF frames"/>

  <param name="robot_description" command="$(find xacro)/xacro $(find mir_description)/urdf/mir.urdf.xacro mir_type:=$(arg mir_type) tf_prefix:=$(arg tf_prefix)" />
</launch>


================================================
FILE: mir_description/package.xml
================================================
<?xml version="1.0"?>
<package format="2">
  <name>mir_description</name>
  <version>1.1.8</version>
  <description>URDF description of the MiR robot</description>

  <maintainer email="martin.guenther@dfki.de">Martin Günther</maintainer>
  <author email="martin.guenther@dfki.de">Martin Günther</author>

  <license>BSD-3-Clause</license>

  <url type="website">https://github.com/DFKI-NI/mir_robot</url>
  <url type="repository">https://github.com/DFKI-NI/mir_robot</url>
  <url type="bugtracker">https://github.com/DFKI-NI/mir_robot/issues</url>

  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>roslaunch</build_depend>

  <exec_depend>diff_drive_controller</exec_depend>
  <exec_depend>gazebo_plugins</exec_depend>
  <exec_depend>gazebo_ros_control</exec_depend>
  <exec_depend>hector_gazebo_plugins</exec_depend>
  <exec_depend>joint_state_controller</exec_depend>
  <exec_depend>joint_state_publisher</exec_depend>
  <exec_depend>joint_state_publisher_gui</exec_depend>
  <exec_depend>position_controllers</exec_depend>
  <exec_depend>robot_state_publisher</exec_depend>
  <exec_depend>rviz</exec_depend>
  <exec_depend>urdf</exec_depend>
  <exec_depend>xacro</exec_depend>
</package>


================================================
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: <Fixed 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: <Fixed 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
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:macro name="controller_plugin_gazebo" params="robot_namespace">
    <gazebo>
      <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <xacro:unless value="${robot_namespace == ''}">
          <robotNamespace>${robot_namespace}</robotNamespace>
        </xacro:unless>
        <controlPeriod>0.001</controlPeriod>
        <legacyModeNS>false</legacyModeNS>
      </plugin>
    </gazebo>
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/common_properties.urdf.xacro
================================================
<?xml version="1.0" ?>
<!--
  Various useful properties such as constants and materials
 -->
<robot name="xacro_properties" xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- #################### RViz materials #################### -->
  <xacro:property name="material_white">
    <material name="white">
      <color rgba="1 1 1 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_yellow">
    <material name="yellow">
      <color rgba="${255/255} ${226/255} ${0/255} 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_almost_white">
    <material name="almost_white">
      <color rgba="0.9 0.9 0.9 1" />
    </material>
  </xacro:property>
  <xacro:property name="material_grey">
    <material name="grey">
      <color rgba="0.5 0.5 0.5 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_light_grey">
    <material name="light_grey">
      <color rgba="0.6 0.6 0.6 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_dark_grey">
    <material name="dark_grey">
      <color rgba="0.3 0.3 0.3 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_black">
    <material name="black">
      <color rgba="0.1 0.1 0.1 1"/>
    </material>
  </xacro:property>
  <xacro:property name="material_aluminum">
    <material name="aluminum">
      <color rgba="0.8 0.8 0.8 1" />
    </material>
  </xacro:property>
  <xacro:property name="material_silver">
    <material name="silver">
      <color rgba="0.79 0.82 0.93 1" />
    </material>
  </xacro:property>

  <!-- #################### inertials with origin #################### -->
  <!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->
  <xacro:macro name="sphere_inertial" params="radius mass *origin">
    <inertial>
      <mass value="${mass}" />
      <xacro:insert_block name="origin" />
      <inertia ixx="${0.4 * mass * radius * radius}" ixy="0.0" ixz="0.0"
        iyy="${0.4 * mass * radius * radius}" iyz="0.0"
        izz="${0.4 * mass * radius * radius}" />
    </inertial>
  </xacro:macro>

  <xacro:macro name="cylinder_inertial" params="radius length mass *origin">
    <inertial>
      <mass value="${mass}" />
      <xacro:insert_block name="origin" />
      <inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
        iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
        izz="${0.5 * mass * radius * radius}" />
    </inertial>
  </xacro:macro>

  <xacro:macro name="box_inertial" params="x y z mass *origin">
    <inertial>
      <mass value="${mass}" />
      <xacro:insert_block name="origin" />
      <inertia ixx="${0.0833333 * mass * (y*y + z*z)}" ixy="0.0" ixz="0.0"
        iyy="${0.0833333 * mass * (x*x + z*z)}" iyz="0.0"
        izz="${0.0833333 * mass * (x*x + y*y)}" />
    </inertial>
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/imu.gazebo.urdf.xacro
================================================
<?xml version="1.0"?>

<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- If tf_prefix is given, use "frame tf_prefix/imu_frame", else "imu_frame" -->
  <xacro:arg name="tf_prefix" default="" />
  <xacro:property name="tf_prefix" value="$(arg tf_prefix)" />
  <xacro:if value="${tf_prefix == ''}">
      <xacro:property name="imu_frame" value="imu_frame" />
  </xacro:if>
  <xacro:unless value="${tf_prefix == ''}">
      <xacro:property name="imu_frame" value="$(arg tf_prefix)/imu_frame" />
  </xacro:unless>


  <xacro:macro name="imu_gazebo" params="link imu_topic update_rate">
    <gazebo>
      <plugin name="imu_plugin" filename="libhector_gazebo_ros_imu.so">
        <updateRate>${update_rate}</updateRate>
        <bodyName>${link}</bodyName>
        <frameId>${imu_frame}</frameId>  <!-- from real MiR -->
        <topicName>${imu_topic}</topicName>
        <accelDrift>0.0 0.0 0.0</accelDrift>
        <accelGaussianNoise>${sqrt(5e-05)} ${sqrt(0.0001)} ${sqrt(0.00013)}</accelGaussianNoise>    <!-- real MiR linear_acceleration_covariance: [5e-05, 0.0, 0.0, 0.0, 0.0001, 0.0, 0.0, 0.0, 0.00013] -->
        <rateDrift>0.0 0.0 0.0</rateDrift>
        <rateGaussianNoise>${sqrt(8e-06)} ${sqrt(8e-06)} ${sqrt(3e-07)}</rateGaussianNoise>         <!-- real MiR angular_velocity_covariance: [8e-06, 0.0, 0.0, 0.0, 8e-06, 0.0, 0.0, 0.0, 3e-07] -->
        <yawDrift>0.0</yawDrift>
        <yawGaussianNoise>${sqrt(0.1)}</yawGaussianNoise>                                           <!-- real MiR orientation_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1] -->
      </plugin>
    </gazebo>
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/mir.gazebo.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:macro name="diff_controller_plugin_gazebo" params="prefix left_wheel_joint right_wheel_joint wheel_separation wheel_radius">
    <gazebo>
      <plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">
        <legacyMode>false</legacyMode>
        <alwaysOn>true</alwaysOn>
        <updateRate>1000.0</updateRate>
        <leftJoint>${left_wheel_joint}</leftJoint>
        <rightJoint>${right_wheel_joint}</rightJoint>
        <wheelSeparation>${wheel_separation}</wheelSeparation>
        <wheelDiameter>${2*wheel_radius}</wheelDiameter>
        <wheelTorque>10</wheelTorque>
        <publishTf>1</publishTf>
        <odometryFrame>map</odometryFrame>
        <commandTopic>mobile_base_controller/cmd_vel</commandTopic>
        <odometryTopic>mobile_base_controller/odom</odometryTopic>
        <robotBaseFrame>base_footprint</robotBaseFrame>
        <wheelAcceleration>2.8</wheelAcceleration>
        <publishWheelJointState>true</publishWheelJointState>
        <publishWheelTF>false</publishWheelTF>
        <odometrySource>world</odometrySource>
        <rosDebugLevel>Debug</rosDebugLevel>
      </plugin>
    </gazebo>
  </xacro:macro>

  <xacro:macro name="set_wheel_friction" params="link friction">
    <gazebo reference="${link}">
      <mu1 value="${friction}"/>
      <mu2 value="${friction}"/>
      <kp value="10000000.0"/>
      <kd value="1.0"/>
      <minDepth>0.01</minDepth>
    </gazebo>
  </xacro:macro>

  <xacro:macro name="set_all_wheel_frictions" params="prefix">
    <xacro:set_wheel_friction link="${prefix}left_wheel_link" friction="200"/>
    <xacro:set_wheel_friction link="${prefix}right_wheel_link" friction="200"/>
    <xacro:set_wheel_friction link="${prefix}fl_caster_wheel_link" friction="1"/>
    <xacro:set_wheel_friction link="${prefix}fr_caster_wheel_link" friction="1"/>
    <xacro:set_wheel_friction link="${prefix}bl_caster_wheel_link" friction="1"/>
    <xacro:set_wheel_friction link="${prefix}br_caster_wheel_link" friction="1"/>
  </xacro:macro>

  <xacro:macro name="p3d_base_controller" params="prefix">
    <gazebo>
      <plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>50.0</updateRate>
        <bodyName>${prefix}base_footprint</bodyName>
        <topicName>base_pose_ground_truth</topicName>
        <gaussianNoise>0.01</gaussianNoise>
        <frameName>map</frameName>
        <xyzOffsets>0 0 0</xyzOffsets>
        <rpyOffsets>0 0 0</rpyOffsets>
      </plugin>
    </gazebo>
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/mir.transmission.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:macro name="mir_wheel_transmission" params="prefix locationprefix">
    <transmission name="${prefix}${locationprefix}_wheel_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${prefix}${locationprefix}_wheel_joint">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
      </joint>
      <actuator name="${prefix}${locationprefix}_wheel_motor">
        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
  </xacro:macro>

  <xacro:macro name="mir_wheel_transmissions" params="prefix">
    <xacro:mir_wheel_transmission prefix="${prefix}" locationprefix="left"/>
    <xacro:mir_wheel_transmission prefix="${prefix}" locationprefix="right"/>
  </xacro:macro>

</robot>


================================================
FILE: mir_description/urdf/include/mir_100_v1.urdf.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
       name="mir_100" >

  <!-- This file is only for backward compatibility before the "mir_100" to "mir" rename. -->

  <xacro:include filename="$(find mir_description)/urdf/include/mir_v1.urdf.xacro" />

  <xacro:macro name="mir_100" params="prefix">
    <xacro:mir prefix="${prefix}" />
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/mir_v1.urdf.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:arg name="mir_type" default="mir_100" />      <!-- The MiR variant. Can be "mir_100" or "mir_250" for now.-->
  <xacro:property name="mir_type" value="$(arg mir_type)" />  <!-- necessary because args cannot be accessed inside ${} expressions -->

  <xacro:include filename="$(find mir_description)/urdf/include/common_properties.urdf.xacro" />
  <xacro:include filename="$(find mir_description)/urdf/include/imu.gazebo.urdf.xacro" />
  <xacro:include filename="$(find mir_description)/urdf/include/mir.gazebo.xacro" />
  <xacro:include filename="$(find mir_description)/urdf/include/mir.transmission.xacro" />
  <xacro:include filename="$(find mir_description)/urdf/include/sick_s300.urdf.xacro" />

  <xacro:property name="deg_to_rad" value="0.017453293" />

  <!-- The inertia for the MiR platform is intentionally chosen to be smaller than
       the bounding box and also shifted a bit to the back, because most of the mass
       is in the lower center back (because of the batteries). -->
  <xacro:property name="mir_base_inertial_x" value="-0.05" />
  <xacro:property name="mir_base_inertial_y" value="0.0" />
  <xacro:property name="mir_base_inertial_z" value="0.15" />
  <xacro:property name="mir_base_inertial_x_length" value="0.50" />
  <xacro:property name="mir_base_inertial_y_length" value="0.30" />
  <xacro:property name="mir_base_inertial_z_length" value="0.20" />

  <xacro:if value="${mir_type == 'mir_100'}">
    <xacro:property name="mir_base_mass" value="77.0" />
    <xacro:property name="mir_act_wheel_radius" value="0.0625" />
    <xacro:property name="mir_act_wheel_width" value="0.032" />
    <xacro:property name="mir_act_wheel_mass" value="1.0" />
    <xacro:property name="mir_act_wheel_dx" value="0.037646" />
    <xacro:property name="mir_act_wheel_dy" value="0.222604" />
  </xacro:if>

  <xacro:if value="${mir_type == 'mir_250'}">
    <xacro:property name="mir_base_mass" value="97.0" />
    <xacro:property name="mir_act_wheel_radius" value="0.100" />
    <xacro:property name="mir_act_wheel_width" value="0.038" />
    <xacro:property name="mir_act_wheel_mass" value="1.0" />
    <xacro:property name="mir_act_wheel_dx" value="-0.004485" />
    <xacro:property name="mir_act_wheel_dy" value="0.2015" />
  </xacro:if>

  <xacro:property name="mir_caster_wheel_radius" value="0.0625" />
  <xacro:property name="mir_caster_wheel_width" value="0.032" />
  <xacro:property name="mir_caster_wheel_mass" value="1.0" />
  <xacro:property name="mir_caster_wheel_dx" value="-0.0382" />
  <xacro:property name="mir_caster_wheel_dy" value="0" />
  <xacro:property name="mir_caster_wheel_dz" value="-0.094" />
  <xacro:property name="mir_front_caster_wheel_base_dx" value="0.3037" />
  <xacro:if value="${mir_type == 'mir_100'}">
    <xacro:property name="mir_back_caster_wheel_base_dx"  value="0.3078" />
    <xacro:property name="mir_caster_wheel_base_dy" value="0.203" />
  </xacro:if>

  <xacro:if value="${mir_type == 'mir_250'}">
    <xacro:property name="mir_back_caster_wheel_base_dx"  value="0.296" />
    <xacro:property name="mir_caster_wheel_base_dy" value="0.188" />
  </xacro:if>
  <xacro:property name="mir_caster_wheel_base_dz" value="${mir_caster_wheel_radius - mir_caster_wheel_dz}" />

  <!-- from visually matching up the meshes of the MiR and the laser scanner -->
  <xacro:if value="${mir_type == 'mir_100'}">
    <xacro:property name="laser_dx" value="0.392" />
    <xacro:property name="laser_dy" value="0.2358" />
  </xacro:if>

  <xacro:if value="${mir_type == 'mir_250'}">
    <xacro:property name="laser_dx" value="0.315" />
    <xacro:property name="laser_dy" value="0.205" />
  </xacro:if>
  <xacro:property name="laser_dz" value="0.1914" />

  <xacro:macro name="actuated_wheel" params="prefix locationprefix locationright">
    <joint name="${prefix}${locationprefix}_wheel_joint" type="continuous">
      <origin xyz="0.0 ${-mir_act_wheel_dy * locationright} ${mir_act_wheel_radius}" rpy="0 0 0" />
      <parent link="${prefix}base_link" />
      <child link="${prefix}${locationprefix}_wheel_link" />
      <axis xyz="0 1 0" />
      <limit effort="100" velocity="20.0" />
    </joint>

    <link name="${prefix}${locationprefix}_wheel_link">
      <xacro:cylinder_inertial mass="${mir_act_wheel_mass}" radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}">
        <origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
      </xacro:cylinder_inertial>
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0" />
        <geometry>
          <cylinder radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}" />
        </geometry>
        <xacro:insert_block name="material_black" />
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0" />
        <geometry>
          <cylinder radius="${mir_act_wheel_radius}" length="${mir_act_wheel_width}" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="${prefix}${locationprefix}_wheel_link">
      <material>Gazebo/FlatBlack</material>
    </gazebo>
  </xacro:macro>

  <xacro:macro name="caster_wheel" params="prefix locationprefix locationright wheel_base_dx">
    <!-- caster hub -->
    <joint name="${prefix}${locationprefix}_caster_rotation_joint" type="continuous">
      <origin xyz="${wheel_base_dx} ${-mir_caster_wheel_base_dy * locationright} ${mir_caster_wheel_base_dz}" rpy="0 0 0" />
      <parent link="${prefix}base_link" />
      <child link="${prefix}${locationprefix}_caster_rotation_link" />
      <axis xyz="0 0 1" />
      <dynamics damping="0.01" friction="0.0"/>
    </joint>

    <link name="${prefix}${locationprefix}_caster_rotation_link">
      <inertial>
        <!-- <origin xyz="0 0 -0.042500000044" rpy="${0.5 * pi} ${24 * deg_to_rad} ${1.5 * pi}" /> -->
        <origin xyz="0 0 -0.042500000044" rpy="${24 * deg_to_rad} 0 ${0.5 * pi} " />
        <mass value="0.3097539019" />
        <inertia
          ixx="0.0005844517978"
          ixy="0"
          ixz="0"
          iyy="0.00052872551237"
          iyz="0"
          izz="0.00017923555074" />
      </inertial>
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/visual/caster_wheel_base.stl" />
        </geometry>
        <xacro:if value="${mir_type == 'mir_100'}">
          <xacro:insert_block name="material_silver" />
        </xacro:if>
        <xacro:if value="${mir_type == 'mir_250'}">
          <xacro:insert_block name="material_black" />
        </xacro:if>
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/collision/caster_wheel_base.stl" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="${prefix}${locationprefix}_caster_rotation_link">
      <xacro:if value="${mir_type == 'mir_100'}">
        <material>Gazebo/Grey</material>
      </xacro:if>
      <xacro:if value="${mir_type == 'mir_250'}">
        <material>Gazebo/FlatBlack</material>
      </xacro:if>
    </gazebo>

    <!-- caster wheel -->
    <joint name="${prefix}${locationprefix}_caster_wheel_joint" type="continuous">
      <origin xyz="${mir_caster_wheel_dx} ${-mir_caster_wheel_dy * locationright} ${mir_caster_wheel_dz}" rpy="0 0 0" />
      <parent link="${prefix}${locationprefix}_caster_rotation_link" />
      <child link="${prefix}${locationprefix}_caster_wheel_link" />
      <axis xyz="0 1 0" />
    </joint>

    <link name="${prefix}${locationprefix}_caster_wheel_link">
      <xacro:cylinder_inertial mass="${mir_caster_wheel_mass}" radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}">
        <origin xyz="0 0 0" rpy="${0.5 * pi} 0 0" />
      </xacro:cylinder_inertial>
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0" />
        <geometry>
          <cylinder radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}" />
        </geometry>
        <xacro:insert_block name="material_black" />
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0" />
        <geometry>
          <cylinder radius="${mir_caster_wheel_radius}" length="${mir_caster_wheel_width}" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="${prefix}${locationprefix}_caster_wheel_link">
      <material>Gazebo/FlatBlack</material>
    </gazebo>
  </xacro:macro>

  <xacro:macro name="mir" params="prefix">
    <link name="${prefix}base_footprint" />

    <joint name="${prefix}base_joint" type="fixed">
      <parent link="${prefix}base_footprint" />
      <child link="${prefix}base_link" />
      <origin xyz="0 0 0" rpy="0 0 0" />
    </joint>

    <link name="${prefix}base_link">
      <xacro:box_inertial mass="${mir_base_mass}" x="${mir_base_inertial_x_length}" y="${mir_base_inertial_y_length}" z="${mir_base_inertial_z_length}">
        <origin xyz="${mir_base_inertial_x + mir_act_wheel_dx} ${mir_base_inertial_y} ${mir_base_inertial_z}" rpy="0 0 0" />
      </xacro:box_inertial>
      <visual>
        <origin xyz="${mir_act_wheel_dx} 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/visual/${mir_type}_base.stl" />
        </geometry>
        <xacro:if value="${mir_type == 'mir_100'}">
          <xacro:insert_block name="material_white" />
        </xacro:if>
        <xacro:if value="${mir_type == 'mir_250'}">
          <xacro:insert_block name="material_dark_grey" />
        </xacro:if>
      </visual>
      <collision>
        <origin xyz="${mir_act_wheel_dx} 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/collision/${mir_type}_base.stl" />
        </geometry>
      </collision>
    </link>
    <gazebo reference="${prefix}base_link">
      <xacro:if value="${mir_type == 'mir_100'}">
        <material>Gazebo/White</material>
      </xacro:if>
      <xacro:if value="${mir_type == 'mir_250'}">
        <material>Gazebo/DarkGrey</material>
      </xacro:if>
    </gazebo>

    <!-- IMU -->
    <joint name="${prefix}base_link_to_imu_joint" type="fixed">
      <parent link="${prefix}base_link" />
      <child link="${prefix}imu_link" />
      <origin xyz="0.0 0.0 0.25" rpy="0 0 0" />  <!-- same as real MiR -->
    </joint>

    <link name="${prefix}imu_link" />

    <xacro:imu_gazebo link="${prefix}imu_link" imu_topic="imu_data" update_rate="50.0" />

    <!-- Create an alias for imu_link. This is necessary because the real MiR's
         TF has imu_link, but the imu_data topic is published in the imu_frame
         frame. -->
    <joint name="${prefix}imu_link_to_imu_frame_joint" type="fixed">
      <parent link="${prefix}imu_link" />
      <child link="${prefix}imu_frame" />
      <origin xyz="0 0 0" rpy="0 0 0" />
    </joint>

    <link name="${prefix}imu_frame" />

    <!-- Laser scanners -->
    <joint name="${prefix}base_link_to_front_laser_joint" type="fixed">
      <parent link="${prefix}base_link" />
      <child link="${prefix}front_laser_link" />
      <origin xyz="${laser_dx + mir_act_wheel_dx} ${laser_dy} ${laser_dz}" rpy="0.0 0.0 ${0.25 * pi}" />
    </joint>
    <xacro:sick_s300 prefix="${prefix}" link="front_laser_link" topic="f_scan" />

    <joint name="${prefix}base_link_to_back_laser_joint" type="fixed">
      <parent link="${prefix}base_link" />
      <child link="${prefix}back_laser_link" />
      <origin xyz="${-laser_dx + mir_act_wheel_dx} ${-laser_dy} ${laser_dz}" rpy="0.0 0.0 ${-0.75 * pi}" />
    </joint>

    <xacro:sick_s300 prefix="${prefix}" link="back_laser_link" topic="b_scan" />

    <!-- Ultrasound sensors -->
    <joint name="${prefix}us_1_joint" type="fixed">   <!-- right ultrasound -->
      <parent link="${prefix}base_link" />
      <child link="${prefix}us_1_frame" />
      <origin xyz="0.45 -0.12 0.16 " rpy="0 0 0" />  <!-- from visually matching to the mesh of the MiR -->
    </joint>

    <link name="${prefix}us_1_frame" />

    <joint name="${prefix}us_2_joint" type="fixed">   <!-- left ultrasound -->
      <parent link="${prefix}base_link" />
      <child link="${prefix}us_2_frame" />
      <origin xyz="0.45 0.12 0.16 " rpy="0 0 0" />  <!-- from visually matching to the mesh of the MiR -->
    </joint>

    <link name="${prefix}us_2_frame" />

    <!-- wheels -->
    <xacro:actuated_wheel prefix="${prefix}" locationprefix="left" locationright="-1"/>
    <xacro:actuated_wheel prefix="${prefix}" locationprefix="right" locationright="1"/>
    <xacro:caster_wheel prefix="${prefix}" locationprefix="fl" locationright="-1" wheel_base_dx="${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}"/>
    <xacro:caster_wheel prefix="${prefix}" locationprefix="fr" locationright="1" wheel_base_dx="${mir_front_caster_wheel_base_dx + mir_act_wheel_dx}"/>
    <xacro:caster_wheel prefix="${prefix}" locationprefix="bl" locationright="-1" wheel_base_dx="${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}"/>
    <xacro:caster_wheel prefix="${prefix}" locationprefix="br" locationright="1" wheel_base_dx="${-mir_back_caster_wheel_base_dx + mir_act_wheel_dx}"/>

    <joint name="${prefix}base_link_surface_joint" type="fixed">
      <origin xyz="${mir_act_wheel_dx} 0 0.352" rpy="0 0 0" />
      <parent link="${prefix}base_link" />
      <child link="${prefix}surface" />
      <axis xyz="0 0 1" />
    </joint>

    <link name="${prefix}surface"/>

    <xacro:mir_wheel_transmissions prefix="${prefix}"/>

    <!-- set the gazebo friction parameters for the wheels -->
    <xacro:set_all_wheel_frictions prefix="${prefix}"/>

    <xacro:p3d_base_controller prefix="${prefix}" />
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/include/sick_s300.urdf.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:include filename="$(find mir_description)/urdf/include/common_properties.urdf.xacro" />

  <xacro:property name="laser_x" value="0.156" />
  <xacro:property name="laser_y" value="0.155" />
  <xacro:property name="laser_z" value="0.185" />
  <xacro:property name="laser_mass" value="1.2" />

  <xacro:macro name="sick_s300" params="link topic prefix">
    <link name="${prefix}${link}">
      <visual>
        <origin xyz="0.0 0.0 0.0" rpy="${pi} 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/visual/sick_lms-100.stl" />
        </geometry>
        <!-- <xacro:insert_block name="material_yellow" /> -->
        <xacro:insert_block name="material_black" />
      </visual>
      <collision>
        <origin xyz="0.0 0.0 0.0" rpy="${pi} 0 0" />
        <geometry>
          <mesh filename="package://mir_description/meshes/visual/sick_lms-100.stl" />
        </geometry>
      </collision>
      <xacro:box_inertial x="${laser_x}" y="${laser_y}" z="${laser_z}" mass="${laser_mass}">
        <origin xyz="0 0 0" />
      </xacro:box_inertial>
    </link>

    <gazebo reference="${prefix}${link}">
      <!-- <material value="Gazebo/Yellow" /> -->
      <material value="Gazebo/FlatBlack" />

      <sensor type="ray" name="${prefix}${link}">
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <update_rate>12.5</update_rate>
        <ray>
          <scan>
            <horizontal>
              <samples>541</samples>
              <resolution>1</resolution>  <!-- has to be 1; actual resolution will be computed from number of samples + min_angle/max_angle -->
              <min_angle>-2.35619449615</min_angle>
              <max_angle>2.35619449615</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.05</min>
            <max>29.0</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <!-- Noise parameters based on published spec for S300 achieving
                 "+-29mm" accuracy at range < 3m (~0.01 of the range) at
                 1 sigma. -->
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="gazebo_ros_${link}_controller" filename="libgazebo_ros_laser.so">
          <frameName>${prefix}${link}</frameName>
          <topicName>${topic}</topicName>
        </plugin>
      </sensor>
    </gazebo>
  </xacro:macro>
</robot>


================================================
FILE: mir_description/urdf/mir.urdf.xacro
================================================
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
       name="mir" >

  <!-- MiR base -->
  <xacro:include filename="$(find mir_description)/urdf/include/mir_v1.urdf.xacro" />
  <xacro:include filename="$(find mir_description)/urdf/include/common.gazebo.xacro" />

  <xacro:arg name="tf_prefix" default="" />
  <xacro:property name="tf_prefix_" value="$(arg tf_prefix)" />
  <xacro:if value="${tf_prefix_ == ''}">
    <xacro:property name="prefix" value="" />
  </xacro:if>
  <xacro:unless value="${tf_prefix_ == ''}">
    <xacro:property name="prefix" value="${tf_prefix_}/" />
  </xacro:unless>

  <xacro:mir prefix="${prefix}" />
  <xacro:controller_plugin_gazebo robot_namespace=""/>

  <!-- instead of the controller_plugin_gazebo, you can use the diffdrive controller like this:
    <xacro:diff_controller_plugin_gazebo prefix=""
      left_wheel_joint="left_wheel_joint"
      right_wheel_joint="right_wheel_joint"
      wheel_separation="${2*mir_act_wheel_dy}"
      wheel_radius="${mir_act_wheel_radius}"/>
  -->
</robot>


================================================
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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/62>`_)
  At least MIR software version 2.8 does not react properly to move_base_simple/goal messages. This implements a workaround.
  Closes `#60 <https://github.com/DFKI-NI/mir_robot/issues/60>`_.
* Fix: Adds subscription to "tf_static". (`#58 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/57>`_)
* Fix: Add missing dict_filter keyword argument for cmd_vel msgs (`#56 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/45>`_.
* Adjust cmd_vel topic to TwistStamped (MiR >= 2.7)
  See `#45 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/5>`_.
* mir_driver: Optionally disable the map topic + TF frame (`#6 <https://github.com/DFKI-NI/mir_robot/issues/6>`_)
  This is useful when running one's own SLAM / localization nodes.
  Fixes `#5 <https://github.com/DFKI-NI/mir_robot/issues/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
================================================
<launch>
  <arg name="mir_type" default="mir_100" doc="The MiR variant. Can be 'mir_100' or 'mir_250' for now." />

  <arg name="tf_prefix" default="" doc="TF prefix to use for all of MiR's TF frames"/>

  <arg name="mir_hostname" default="192.168.12.20" />

  <arg name="disable_map" default="false" doc="Disable the map topic and map -> odom TF transform from the MiR" />

  <param name="tf_prefix" type="string" value="$(arg tf_prefix)"/>

  <!-- URDF -->
  <include file="$(find mir_description)/launch/upload_mir_urdf.launch">
    <arg name="mir_type" value="$(arg mir_type)" />
  </include>

  <!-- Robot state publisher -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
    <remap from="/tf"        to="tf_rss" />
    <remap from="/tf_static" to="tf_static_rss" />
  </node>

  <!-- remove those TFs that are also published by the MiR to avoid conflicts -->
  <node name="tf_remove_state_publisher_frames" pkg="mir_driver" type="tf_remove_child_frames.py" output="screen">
    <remap from="tf_in"         to="tf_rss" />
    <remap from="tf_out"        to="/tf" />
    <remap from="tf_static_in"  to="tf_static_rss" />
    <remap from="tf_static_out" to="/tf_static" />
    <rosparam param="remove_frames">
      - 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
    </rosparam>
  </node>

  <!-- MiR base -->
  <group if="$(arg disable_map)">
    <node name="mir_bridge" pkg="mir_driver" type="mir_bridge.py" output="screen">
      <param name="hostname" value="$(arg mir_hostname)" />
      <param name="tf_prefix" value="$(arg tf_prefix)" />
      <remap from="map" to="map_mir" />
      <remap from="map_metadata" to="map_metadata_mir" />
      <remap from="rosout" to="/rosout" />
      <remap from="rosout_agg" to="/rosout_agg" />
      <remap from="tf" to="tf_mir" />
    </node>

    <!-- remove the map -> odom TF transform -->
    <node name="tf_remove_mir_map_frame" pkg="mir_driver" type="tf_remove_child_frames.py" output="screen">
      <remap from="tf_in"         to="tf_mir" />
      <remap from="tf_out"        to="/tf" />
      <rosparam param="remove_frames">
        - odom
      </rosparam>
    </node>
  </group>
  <group unless="$(arg disable_map)">
    <node name="mir_bridge" pkg="mir_driver" type="mir_bridge.py" output="screen">
      <param name="hostname" value="$(arg mir_hostname)" />
      <param name="tf_prefix" value="$(arg tf_prefix)" />
      <remap from="map" to="/map" />
      <remap from="map_metadata" to="/map_metadata" />
      <remap from="rosout" to="/rosout" />
      <remap from="rosout_agg" to="/rosout_agg" />
      <remap from="tf" to="/tf" />
    </node>
  </group>

  <node name="b_rep117_laser_filter" pkg="mir_driver" type="rep117_filter.py" output="screen">
    <remap from="scan" to="b_scan" />
    <remap from="scan_filtered" to="b_scan_rep117" />
  </node>

  <node name="f_rep117_laser_filter" pkg="mir_driver" type="rep117_filter.py" output="screen">
    <remap from="scan" to="f_scan" />
    <remap from="scan_filtered" to="f_scan_rep117" />
  </node>

  <node name="fake_mir_joint_publisher" pkg="mir_driver" type="fake_mir_joint_publisher.py" output="screen" />
</launch>


================================================
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
================================================
<?xml version="1.0"?>
<package format="2">
  <name>mir_driver</name>
  <version>1.1.8</version>
  <description>A reverse ROS bridge for the MiR robot</description>

  <maintainer email="martin.guenther@dfki.de">Martin Günther</maintainer>
  <author email="martin.guenther@dfki.de">Martin Günther</author>

  <license>BSD-3-Clause</license>
  <license>Apache-2.0</license>

  <url type="website">https://github.com/DFKI-NI/mir_robot</url>
  <url type="repository">https://github.com/DFKI-NI/mir_robot</url>
  <url type="bugtracker">https://github.com/DFKI-NI/mir_robot/issues</url>

  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>roslaunch</build_depend>

  <depend>actionlib</depend>
  <depend>actionlib_msgs</depend>
  <depend>diagnostic_msgs</depend>
  <depend>dynamic_reconfigure</depend>
  <depend>geometry_msgs</depend>
  <depend>mir_actions</depend>
  <depend>mir_msgs</depend>
  <depend>move_base_msgs</depend>
  <depend>nav_msgs</depend>
  <depend>python3-websocket</depend>
  <depend>rosgraph_msgs</depend>
  <depend>rospy</depend>
  <depend>rospy_message_converter</depend>
  <depend>sdc21x0</depend>
  <depend>sensor_msgs</depend>
  <depend>std_msgs</depend>
  <depend>tf2_msgs</depend>
  <depend>tf</depend>
  <depend>visualization_msgs</depend>

  <exec_depend>mir_description</exec_depend>
  <exec_depend>robot_state_publisher</exec_depend>
</package>


================================================
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 <https://github.com/DFKI-NI/mir_robot/issues/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
================================================
<class_libraries>
  <library path="lib/libmir_dwb_critics">
    <class type="mir_dwb_critics::PathProgressCritic" base_class_type="dwb_local_planner::TrajectoryCritic">
      <description>Scores trajectories based on how far along the global path they end up.</description>
    </class>
    <class type="mir_dwb_critics::PathAngleCritic" base_class_type="dwb_local_planner::TrajectoryCritic">
      <description>Scores trajectories based on the difference between the path's current angle and the trajectory's angle</description>
    </class>
    <class type="mir_dwb_critics::PathDistPrunedCritic" base_class_type="dwb_local_planner::TrajectoryCritic">
      <description>Scores trajectories based on the distance to the global path, only taking the parts into account that are still ahead of the robot.</description>
    </class>
  </library>
</class_libraries>


================================================
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 <dwb_local_planner/trajectory_critic.h>
#include <vector>

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 <dwb_critics/path_dist.h>
#include <vector>

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 <dwb_critics/map_grid.h>
#include <vector>

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<geometry_msgs::Pose2D>& plan, unsigned int start_index,
                            unsigned int last_valid_index) const;

  double xy_local_goal_tolerance_;
  double angle_threshold_;
  double heading_scale_;

  std::vector<geometry_msgs::Pose2D> 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
================================================
<?xml version="1.0"?>
<package format="2">
  <name>mir_dwb_critics</name>
  <version>1.1.8</version>
  <description>
    Trajectory critics for the dwb_local_planner that work well together with the SBPL global planner on the MiR robot
  </description>

  <maintainer email="martin.guenther@dfki.de">Martin Günther</maintainer>
  <author email="martin.guenther@dfki.de">Martin Günther</author>

  <license>BSD-3-Clause</license>

  <url type="website">https://github.com/DFKI-NI/mir_robot</url>
  <url type="repository">https://github.com/DFKI-NI/mir_robot</url>
  <url type="bugtracker">https://github.com/DFKI-NI/mir_robot/issues</url>

  <buildtool_depend>catkin</buildtool_depend>

  <depend>angles</depend>
  <depend>costmap_queue</depend>
  <depend>dwb_critics</depend>
  <depend>dwb_local_planner</depend>
  <depend>geometry_msgs</depend>
  <depend>nav_2d_msgs</depend>
  <depend>nav_2d_utils</depend>
  <depend>nav_core2</depend>
  <depend>nav_grid_iterators</depend>
  <depend>pluginlib</depend>
  <depend>roscpp</depend>
  <depend>sensor_msgs</depend>

  <exec_depend>python3-matplotlib</exec_depend>

  <export>
    <dwb_local_planner plugin="${prefix}/default_critics.xml"/>
  </export>
</package>


================================================
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 <mir_dwb_critics/path_angle.h>
#include <pluginlib/class_list_macros.h>
#include <nav_2d_utils/path_ops.h>
#include <nav_grid/coordinate_conversion.h>
#include <vector>

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<double>::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 <nav_2d_utils/path_ops.h>
#include <pluginlib/class_list_macros.h>

#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<double>::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<geometry_msgs::Pose2D>(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 <mir_dwb_critics/path_progress.h>
#include <nav_grid/coordinate_conversion.h>
#include <pluginlib/class_list_macros.h>
#include <nav_2d_utils/path_ops.h>
#include <vector>

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<geometry_msgs::Pose2D> 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<double>::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<geometry_msgs::Pose2D>& 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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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 <https://github.com/DFKI-NI/mir_robot/issues/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
Download .txt
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
Download .txt
SYMBOL INDEX (75 symbols across 17 files)

FILE: mir_driver/nodes/fake_mir_joint_publisher.py
  function fake_mir_joint_publisher (line 36) | def fake_mir_joint_publisher():

FILE: mir_driver/nodes/mir_bridge.py
  class TopicConfig (line 63) | class TopicConfig(object):
    method __init__ (line 64) | def __init__(self, topic, topic_type, latch=False, dict_filter=None):
  function _move_base_goal_dict_filter (line 72) | def _move_base_goal_dict_filter(msg_dict):
  function _move_base_feedback_dict_filter (line 80) | def _move_base_feedback_dict_filter(msg_dict):
  function _move_base_result_dict_filter (line 90) | def _move_base_result_dict_filter(msg_dict):
  function _cmd_vel_dict_filter (line 96) | def _cmd_vel_dict_filter(msg_dict):
  function _tf_dict_filter (line 112) | def _tf_dict_filter(msg_dict):
  function _tf_static_dict_filter (line 119) | def _tf_static_dict_filter(msg_dict):
  function _prepend_tf_prefix_dict_filter (line 159) | def _prepend_tf_prefix_dict_filter(msg_dict):
  function _remove_tf_prefix_dict_filter (line 186) | def _remove_tf_prefix_dict_filter(msg_dict):
  class PublisherWrapper (line 363) | class PublisherWrapper(rospy.SubscribeListener):
    method __init__ (line 364) | def __init__(self, topic_config, robot):
    method peer_subscribe (line 383) | def peer_subscribe(self, topic_name, topic_publish, peer_publish):
    method peer_unsubscribe (line 390) | def peer_unsubscribe(self, topic_name, num_peers):
    method callback (line 399) | def callback(self, msg_dict):
  class SubscriberWrapper (line 407) | class SubscriberWrapper(object):
    method __init__ (line 408) | def __init__(self, topic_config, robot):
    method callback (line 419) | def callback(self, msg):
  class MiRBridge (line 428) | class MiRBridge(object):
    method __init__ (line 429) | def __init__(self):
    method get_topics (line 479) | def get_topics(self):
    method _move_base_simple_goal_callback (line 508) | def _move_base_simple_goal_callback(self, msg):
  function main (line 519) | def main():

FILE: mir_driver/nodes/rep117_filter.py
  function callback (line 39) | def callback(msg):
  function main (line 63) | def main():

FILE: mir_driver/nodes/tf_remove_child_frames.py
  function main (line 23) | def main():

FILE: mir_driver/src/mir_driver/rosbridge.py
  class RosbridgeSetup (line 40) | class RosbridgeSetup:
    method __init__ (line 41) | def __init__(self, host, port):
    method publish (line 48) | def publish(self, topic, obj):
    method subscribe (line 52) | def subscribe(self, topic, callback, throttle_rate=-1):
    method unhook (line 60) | def unhook(self, callback):
    method unsubscribe (line 74) | def unsubscribe(self, topic):
    method callService (line 78) | def callService(self, serviceName, callback=None, msg=None):
    method send (line 103) | def send(self, obj):
    method generate_id (line 110) | def generate_id(self, chars=16):
    method addServiceCallback (line 113) | def addServiceCallback(self, id, callback):
    method addCallback (line 116) | def addCallback(self, topic, callback):
    method is_connected (line 124) | def is_connected(self):
    method is_errored (line 127) | def is_errored(self):
    method onMessageReceived (line 130) | def onMessageReceived(self, message):
  class RosbridgeWSConnection (line 174) | class RosbridgeWSConnection:
    method __init__ (line 175) | def __init__(self, host, port):
    method on_open (line 186) | def on_open(self):
    method sendString (line 190) | def sendString(self, message):
    method on_error (line 197) | def on_error(self, error):
    method on_close (line 201) | def on_close(self):
    method run (line 205) | def run(self, *args):
    method on_message (line 208) | def on_message(self, message):
    method registerCallback (line 213) | def registerCallback(self, callback):

FILE: mir_dwb_critics/include/mir_dwb_critics/path_angle.h
  function namespace (line 40) | namespace mir_dwb_critics

FILE: mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h
  function namespace (line 40) | namespace mir_dwb_critics

FILE: mir_dwb_critics/include/mir_dwb_critics/path_progress.h
  function namespace (line 40) | namespace mir_dwb_critics

FILE: mir_dwb_critics/nodes/plot_dwb_scores.py
  function eval_cb (line 45) | def eval_cb(msg):
  function main (line 85) | def main():

FILE: mir_dwb_critics/nodes/print_dwb_scores.py
  function eval_cb (line 37) | def eval_cb(msg):
  function main (line 49) | def main():

FILE: mir_dwb_critics/src/path_angle.cpp
  type mir_dwb_critics (line 41) | namespace mir_dwb_critics

FILE: mir_dwb_critics/src/path_dist_pruned.cpp
  type mir_dwb_critics (line 39) | namespace mir_dwb_critics

FILE: mir_dwb_critics/src/path_progress.cpp
  type mir_dwb_critics (line 40) | namespace mir_dwb_critics

FILE: mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py
  function matrix_size (line 46) | def matrix_size(mat, elem=None):
  function genmprim_unicycle (line 53) | def genmprim_unicycle(outfilename, visualize=False, separate_plots=False):

FILE: mir_navigation/nodes/acc_finder.py
  function odom_cb (line 44) | def odom_cb(msg):
  function cmd_vel_cb (line 71) | def cmd_vel_cb(msg):
  function main (line 95) | def main():

FILE: mir_navigation/nodes/min_max_finder.py
  function odom_cb (line 42) | def odom_cb(msg):
  function main (line 56) | def main():

FILE: mir_navigation/scripts/plot_mprim.py
  function get_value (line 37) | def get_value(strline, name):
  function get_pose (line 44) | def get_pose(line):
  class MPrim (line 49) | class MPrim:
    method __init__ (line 50) | def __init__(self, f):
    method plot (line 62) | def plot(self, nr_angles):
  class MPrims (line 66) | class MPrims:
    method __init__ (line 67) | def __init__(self, filename):
    method plot (line 80) | def plot(self):
Condensed preview — 187 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (733K chars).
[
  {
    "path": ".clang-format",
    "chars": 1928,
    "preview": "---\nBasedOnStyle:  Google\nColumnLimit:    120\nMaxEmptyLinesToKeep: 1\nSortIncludes: false\n\nStandard:        Auto\nIndentWi"
  },
  {
    "path": ".dockerfilelintrc",
    "chars": 45,
    "preview": "rules:\n  apt-get-update_require_install: off\n"
  },
  {
    "path": ".flake8",
    "chars": 232,
    "preview": "[flake8]\n# The line length here has to match the black config in pyproject.toml\nmax-line-length = 120\nexclude =\n    .git"
  },
  {
    "path": ".github/workflows/github-actions.yml",
    "chars": 1856,
    "preview": "name: Build and run ROS tests\non:\n  push:\n  pull_request:\n  workflow_dispatch:\n    inputs:\n      debug_enabled:\n        "
  },
  {
    "path": ".gitignore",
    "chars": 6,
    "preview": "*.pyc\n"
  },
  {
    "path": ".markdownlint.yaml",
    "chars": 11031,
    "preview": "## Default state for all rules\n#default: true\n\n## Path to configuration file to extend\n#extends: null\n\n## MD001/heading-"
  },
  {
    "path": ".pre-commit-config.yaml",
    "chars": 3052,
    "preview": "# To use:\n#\n#     pre-commit run -a\n#\n# Or:\n#\n#     pre-commit install  # (runs every time you commit in git)\n#\n# To upd"
  },
  {
    "path": "Dockerfile-noetic",
    "chars": 1289,
    "preview": "FROM ros:noetic-ros-core\n\nRUN apt-get update \\\n    && apt-get install -y --no-install-recommends build-essential python3"
  },
  {
    "path": "LICENSE",
    "chars": 1529,
    "preview": "Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n\nRedistribution and use in source and binary forms,"
  },
  {
    "path": "README.md",
    "chars": 21507,
    "preview": "mir_robot\n=========\n\nThis repo contains a ROS driver and ROS configuration files (URDF description,\nGazebo launch files,"
  },
  {
    "path": "mir_actions/CHANGELOG.rst",
    "chars": 1612,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_actions\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13"
  },
  {
    "path": "mir_actions/CMakeLists.txt",
    "chars": 791,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_actions)\n\nfind_package(catkin REQUIRED COMPONENTS\n  actionlib\n  geomet"
  },
  {
    "path": "mir_actions/action/MirMoveBase.action",
    "chars": 2618,
    "preview": "#goal definition\n#move type\nint16 BASE_MOVE = 0\nint16 GLOBAL_MOVE = 1\nint16 RELATIVE_MOVE = 2\nint16 RELATIVE_MARKER_MOVE"
  },
  {
    "path": "mir_actions/package.xml",
    "chars": 821,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_actions</name>\n  <version>1.1.8</version>\n  <description>Action d"
  },
  {
    "path": "mir_description/CHANGELOG.rst",
    "chars": 5061,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_description\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8"
  },
  {
    "path": "mir_description/CMakeLists.txt",
    "chars": 546,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_description)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n#"
  },
  {
    "path": "mir_description/config/diffdrive_controller.yaml",
    "chars": 1896,
    "preview": "# -----------------------------------\nmobile_base_controller:\n  type        : \"diff_drive_controller/DiffDriveController"
  },
  {
    "path": "mir_description/config/joint_state_controller.yaml",
    "chars": 158,
    "preview": "# Publish all joint states -----------------------------------\njoint_state_controller:\n  type: joint_state_controller/Jo"
  },
  {
    "path": "mir_description/launch/mir_debug_urdf.launch",
    "chars": 817,
    "preview": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir"
  },
  {
    "path": "mir_description/launch/upload_mir_urdf.launch",
    "chars": 406,
    "preview": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"mir_type\"  default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir"
  },
  {
    "path": "mir_description/package.xml",
    "chars": 1206,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_description</name>\n  <version>1.1.8</version>\n  <description>URDF"
  },
  {
    "path": "mir_description/rviz/mir_description.rviz",
    "chars": 6395,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 81\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n      "
  },
  {
    "path": "mir_description/urdf/include/common.gazebo.xacro",
    "chars": 520,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"controller_plugin_gazebo\" pa"
  },
  {
    "path": "mir_description/urdf/include/common_properties.urdf.xacro",
    "chars": 2919,
    "preview": "<?xml version=\"1.0\" ?>\n<!--\n  Various useful properties such as constants and materials\n -->\n<robot name=\"xacro_properti"
  },
  {
    "path": "mir_description/urdf/include/imu.gazebo.urdf.xacro",
    "chars": 1634,
    "preview": "<?xml version=\"1.0\"?>\n\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <!-- If tf_prefix is given, use \"frame tf_prefi"
  },
  {
    "path": "mir_description/urdf/include/mir.gazebo.xacro",
    "chars": 2633,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"diff_controller_plugin_gazeb"
  },
  {
    "path": "mir_description/urdf/include/mir.transmission.xacro",
    "chars": 944,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"mir_wheel_transmission\" para"
  },
  {
    "path": "mir_description/urdf/include/mir_100_v1.urdf.xacro",
    "chars": 386,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\"\n       name=\"mir_100\" >\n\n  <!-- This file is only f"
  },
  {
    "path": "mir_description/urdf/include/mir_v1.urdf.xacro",
    "chars": 13727,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <xacro:arg name=\"mir_type\" default=\"mir_100\" /> "
  },
  {
    "path": "mir_description/urdf/include/sick_s300.urdf.xacro",
    "chars": 2572,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:include filename=\"$(find mir_description"
  },
  {
    "path": "mir_description/urdf/mir.urdf.xacro",
    "chars": 1051,
    "preview": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\"\n       name=\"mir\" >\n\n  <!-- MiR base -->\n  <xacro:i"
  },
  {
    "path": "mir_driver/CHANGELOG.rst",
    "chars": 5544,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_driver\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n-"
  },
  {
    "path": "mir_driver/CMakeLists.txt",
    "chars": 1294,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_driver)\n\nfind_package(catkin REQUIRED COMPONENTS\n  actionlib\n  actionl"
  },
  {
    "path": "mir_driver/launch/mir.launch",
    "chars": 3349,
    "preview": "<launch>\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR variant. Can be 'mir_100' or 'mir_250' for now.\" />\n\n  <a"
  },
  {
    "path": "mir_driver/nodes/fake_mir_joint_publisher.py",
    "chars": 2799,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_driver/nodes/mir_bridge.py",
    "chars": 27274,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_driver/nodes/rep117_filter.py",
    "chars": 2686,
    "preview": "#!/usr/bin/env python3\n\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and us"
  },
  {
    "path": "mir_driver/nodes/tf_remove_child_frames.py",
    "chars": 1610,
    "preview": "#!/usr/bin/env python3\n# -*- coding: utf-8 -*-\n\n# Copyright 2016 The Cartographer Authors\n# Copyright 2018 DFKI GmbH\n#\n#"
  },
  {
    "path": "mir_driver/package.xml",
    "chars": 1382,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_driver</name>\n  <version>1.1.8</version>\n  <description>A reverse"
  },
  {
    "path": "mir_driver/setup.py",
    "chars": 298,
    "preview": "# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD\n\nfrom distutils.core import setup\nfrom catkin_pkg.python_se"
  },
  {
    "path": "mir_driver/src/mir_driver/__init__.py",
    "chars": 0,
    "preview": ""
  },
  {
    "path": "mir_driver/src/mir_driver/rosbridge.py",
    "chars": 7449,
    "preview": "# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use in source and binary f"
  },
  {
    "path": "mir_dwb_critics/CHANGELOG.rst",
    "chars": 2289,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_dwb_critics\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8"
  },
  {
    "path": "mir_dwb_critics/CMakeLists.txt",
    "chars": 1376,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_dwb_critics)\n\nset_directory_properties(PROPERTIES COMPILE_OPTIONS \"-Wa"
  },
  {
    "path": "mir_dwb_critics/default_critics.xml",
    "chars": 864,
    "preview": "<class_libraries>\n  <library path=\"lib/libmir_dwb_critics\">\n    <class type=\"mir_dwb_critics::PathProgressCritic\" base_c"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_angle.h",
    "chars": 3456,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h",
    "chars": 2412,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_dwb_critics/include/mir_dwb_critics/path_progress.h",
    "chars": 3219,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_dwb_critics/nodes/plot_dwb_scores.py",
    "chars": 3267,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_dwb_critics/nodes/print_dwb_scores.py",
    "chars": 2624,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_dwb_critics/package.xml",
    "chars": 1210,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_dwb_critics</name>\n  <version>1.1.8</version>\n  <description>\n   "
  },
  {
    "path": "mir_dwb_critics/src/path_angle.cpp",
    "chars": 3985,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_dwb_critics/src/path_dist_pruned.cpp",
    "chars": 4247,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_dwb_critics/src/path_progress.cpp",
    "chars": 9323,
    "preview": "/*\n * Software License Agreement (BSD License)\n *\n *  Copyright (c) 2019, DFKI GmbH\n *  All rights reserved.\n *\n *  Redi"
  },
  {
    "path": "mir_gazebo/CHANGELOG.rst",
    "chars": 3587,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_gazebo\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n-"
  },
  {
    "path": "mir_gazebo/CMakeLists.txt",
    "chars": 531,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_gazebo)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n######"
  },
  {
    "path": "mir_gazebo/config/ekf.yaml",
    "chars": 16906,
    "preview": "# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin\n# compu"
  },
  {
    "path": "mir_gazebo/launch/fake_localization.launch",
    "chars": 674,
    "preview": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"delta_x\" default=\"0.0\" />\n  <arg name=\"delta_y\" default=\"0.0\" />\n  <arg na"
  },
  {
    "path": "mir_gazebo/launch/includes/ekf.launch.xml",
    "chars": 310,
    "preview": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"tf_prefix\" default=\"\" />\n  <node pkg=\"robot_localization\" type=\"ekf_localiza"
  },
  {
    "path": "mir_gazebo/launch/includes/spawn_maze.launch.xml",
    "chars": 199,
    "preview": "<?xml version=\"1.0\"?>\n<launch>\n    <node name=\"spawn_maze\" pkg=\"gazebo_ros\" type=\"spawn_model\" args=\"-sdf\n      -file $("
  },
  {
    "path": "mir_gazebo/launch/mir_empty_world.launch",
    "chars": 2898,
    "preview": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"gui\" default=\"true\" />\n  <arg name=\"world_name\" default=\"worlds/empty.world"
  },
  {
    "path": "mir_gazebo/launch/mir_gazebo_common.launch",
    "chars": 3251,
    "preview": "<?xml version=\"1.0\" ?>\n<launch>\n  <arg name=\"robot_x\"   default=\"0.0\" />\n  <arg name=\"robot_y\"   default=\"0.0\" />\n  <arg"
  },
  {
    "path": "mir_gazebo/launch/mir_maze_world.launch",
    "chars": 604,
    "preview": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"gui\" default=\"true\" />\n  <arg name=\"mir_type\" default=\"mir_100\" doc=\"The MiR"
  },
  {
    "path": "mir_gazebo/maps/maze.yaml",
    "chars": 108,
    "preview": "image: maze.png\nresolution: 0.05\norigin: [0.0, 0.0, 0.0]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n"
  },
  {
    "path": "mir_gazebo/maps/maze_virtual_walls.yaml",
    "chars": 122,
    "preview": "image: maze_virtual_walls.png\nresolution: 0.05\norigin: [0.0, 0.0, 0.0]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.19"
  },
  {
    "path": "mir_gazebo/package.xml",
    "chars": 1178,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_gazebo</name>\n  <version>1.1.8</version>\n  <description>Simulatio"
  },
  {
    "path": "mir_gazebo/sdf/maze/model.config",
    "chars": 270,
    "preview": "<?xml version=\"1.0\" ?>\n<model>\n    <name>maze</name>\n    <version>1.0</version>\n    <sdf version=\"1.6\">model.sdf</sdf>\n "
  },
  {
    "path": "mir_gazebo/sdf/maze/model.sdf",
    "chars": 9791,
    "preview": "<?xml version='1.0'?>\n<sdf version='1.6'>\n  <model name='maze'>\n    <pose frame=''>-0.078283 0.098984 0 0 -0 0</pose>\n  "
  },
  {
    "path": "mir_msgs/CHANGELOG.rst",
    "chars": 3384,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_msgs\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n-------"
  },
  {
    "path": "mir_msgs/CMakeLists.txt",
    "chars": 1834,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_msgs)\n\nfind_package(catkin REQUIRED COMPONENTS\n  geometry_msgs\n  messa"
  },
  {
    "path": "mir_msgs/msg/AngleMeasurment.msg",
    "chars": 38,
    "preview": "float64 angle #radians\ntime timestamp\n"
  },
  {
    "path": "mir_msgs/msg/BMSData.msg",
    "chars": 4545,
    "preview": "float64 pack_voltage\nfloat64 charge_current\nfloat64 discharge_current\nfloat64 state_of_charge\nfloat64 remaining_time_to_"
  },
  {
    "path": "mir_msgs/msg/BatteryCurrents.msg",
    "chars": 50,
    "preview": "float64 battery1_current\nfloat64 battery2_current\n"
  },
  {
    "path": "mir_msgs/msg/BrakeState.msg",
    "chars": 167,
    "preview": "uint8 UNKNOWN = 0\nuint8 INITIALIZING = 1\nuint8 HOMING = 2\nuint8 ACTIVE = 3\nuint8 INACTIVE = 4\nuint8 ACTIVATING = 5\nuint8"
  },
  {
    "path": "mir_msgs/msg/ChargingState.msg",
    "chars": 199,
    "preview": "bool charging_relay\nfloat64 charging_current\nuint32 charging_current_raw\nfloat64 last_time_current\n\nfloat64 charging_vol"
  },
  {
    "path": "mir_msgs/msg/Device.msg",
    "chars": 26,
    "preview": "string name\nstring serial\n"
  },
  {
    "path": "mir_msgs/msg/Devices.msg",
    "chars": 26,
    "preview": "mir_msgs/Device[] devices\n"
  },
  {
    "path": "mir_msgs/msg/EncoderTestEntry.msg",
    "chars": 136,
    "preview": "float64 command_velocity\nfloat64 command_distance\nfloat64 left_dist\nfloat64 right_dist\nstring suggested_direction\nstring"
  },
  {
    "path": "mir_msgs/msg/Encoders.msg",
    "chars": 169,
    "preview": "float32 time_delta # Time since last encoder update.\nint32 left_wheel  # Encoder counts (absolute or relative)\nint32 rig"
  },
  {
    "path": "mir_msgs/msg/Error.msg",
    "chars": 1024,
    "preview": "# Definition of offsets indicating what type an error is\nint32 HARDWARE_ERROR = 0\nint32 CPU_LOAD_ERROR = 100\nint32 MEMOR"
  },
  {
    "path": "mir_msgs/msg/Event.msg",
    "chars": 402,
    "preview": "uint32 EV_SPEED=1\nuint32 EV_BLINK=2\nuint32 EV_SOUND=3\nuint32 EV_DOOR=4\nuint32 EV_AMCLOFF=5\nuint32 EV_FWDDIST=6\nuint32 EV"
  },
  {
    "path": "mir_msgs/msg/Events.msg",
    "chars": 29,
    "preview": "Header header\nEvent[] events\n"
  },
  {
    "path": "mir_msgs/msg/ExternalRobot.msg",
    "chars": 267,
    "preview": "Header header\nuint32 id\nuint32 MIR100=1\nuint32 MIR500=3\nuint32 type_id\nstring name\nfloat64 robot_length\nfloat64 robot_wi"
  },
  {
    "path": "mir_msgs/msg/ExternalRobots.msg",
    "chars": 46,
    "preview": "Header header\nmir_msgs/ExternalRobot[] robots\n"
  },
  {
    "path": "mir_msgs/msg/Gpio.msg",
    "chars": 193,
    "preview": "uint8 POWERBOARD_GPIO = 0\nuint8 POWERBOARD_RESET_SWITCH_LED = 1\nuint8 PENDANT_INPUT = 5\nuint8 AUTO_MODE_SWITCH = 10\nuint"
  },
  {
    "path": "mir_msgs/msg/GripperState.msg",
    "chars": 167,
    "preview": "uint8 LOCK_UNKNOWN = 0\nuint8 LOCK_HOMING = 1\nuint8 LOCK_OPEN = 2\nuint8 LOCK_OPENING = 3\nuint8 LOCK_CLOSED = 4\nuint8 LOCK"
  },
  {
    "path": "mir_msgs/msg/HeightState.msg",
    "chars": 133,
    "preview": "uint8 HEIGHT_UNKNOWN = 0\nuint8 HEIGHT_HOMING = 1\nuint8 HEIGHT_IDLE = 2\nuint8 HEIGHT_CHANGING = 3\nuint8 HEIGHT_ERROR = 4\n"
  },
  {
    "path": "mir_msgs/msg/HookData.msg",
    "chars": 109,
    "preview": "AngleMeasurment angle\nfloat64 height\nfloat64 length\nuint8 brake_state\nuint8 gripper_state\nuint8 height_state\n"
  },
  {
    "path": "mir_msgs/msg/HookExtendedStatus.msg",
    "chars": 113,
    "preview": "bool available\n\nBrakeState brake\n\nGripperState gripper\n\nHeightState height\n\nfloat32 angle\n\nstring qr_marker_name\n"
  },
  {
    "path": "mir_msgs/msg/HookStatus.msg",
    "chars": 110,
    "preview": "bool available\nfloat32 length\nfloat32 height\nfloat32 angle\nbool braked\n\nbool trolley_attached\nTrolley trolley\n"
  },
  {
    "path": "mir_msgs/msg/IOs.msg",
    "chars": 185,
    "preview": "string module_guid\nbool connected\nuint8 DONE=0\nuint8 STARTED=1\nuint8 ERROR=3\nuint8 status\nint8 num_inputs\nbool[] input_s"
  },
  {
    "path": "mir_msgs/msg/JoystickVel.msg",
    "chars": 56,
    "preview": "string joystick_token\ngeometry_msgs/Twist speed_command\n"
  },
  {
    "path": "mir_msgs/msg/LocalMapStat.msg",
    "chars": 29,
    "preview": "int32  idx\nint32  x\nint32  y\n"
  },
  {
    "path": "mir_msgs/msg/MirExtra.msg",
    "chars": 263,
    "preview": "# MirExtra - to publish data on a topic\nHeader header\nfloat32 time_delta # Time since last encoder update.\nfloat32 r_rpm"
  },
  {
    "path": "mir_msgs/msg/MirLocalPlannerPathTypes.msg",
    "chars": 112,
    "preview": "uint8 REVERSE_TROLLEY_STANDARD=1\nuint8 REVERSE_TROLLEY_FAST=2\nuint8 REVERSE_TROLLEY_COMPACT=3\n\n\nuint8 path_type\n"
  },
  {
    "path": "mir_msgs/msg/MissionCtrlCommand.msg",
    "chars": 179,
    "preview": "uint8 CMD_GET_STATUS = 0\nuint8 CMD_WAIT_POS_LOCK = 1\nuint8 CMD_WAIT_AREA_LOCK = 2\nuint8 CMD_CONTINUE = 3\nuint8 CMD_LOAD_"
  },
  {
    "path": "mir_msgs/msg/MissionCtrlState.msg",
    "chars": 268,
    "preview": "uint8 STATE_IDLE = 0\nuint8 STATE_WAIT_POS_LOCK = 1\nuint8 STATE_WAIT_AREA_LOCK = 2\nuint8 STATE_WAIT_MAP_TRANSITION = 10\nu"
  },
  {
    "path": "mir_msgs/msg/MovingState.msg",
    "chars": 119,
    "preview": "uint8 UNKNOWN=0\nuint8 MOVING=1\nuint8 STOPPED=2\nuint8 STANDING_STILL=3\n\nuint8 moving_state\t# Current robot moving state\n"
  },
  {
    "path": "mir_msgs/msg/PalletLifterStatus.msg",
    "chars": 165,
    "preview": "uint8 PALLET_LIFT_STATE_DISABLED = 0\nuint8 PALLET_LIFT_STATE_MOVING = 1\nuint8 PALLET_LIFT_STATE_DOWN = 2\nuint8 PALLET_LI"
  },
  {
    "path": "mir_msgs/msg/Path.msg",
    "chars": 38,
    "preview": "Header header\nmir_msgs/Pose2D[] poses\n"
  },
  {
    "path": "mir_msgs/msg/Pendant.msg",
    "chars": 44,
    "preview": "float32   x\nfloat32   y\nuint8     gpio_bits\n"
  },
  {
    "path": "mir_msgs/msg/PlanSegment.msg",
    "chars": 109,
    "preview": "bool forward_motion\nint32 start_idx\nfloat64 length\nfloat64 remaining_length\ngeometry_msgs/PoseStamped[] path\n"
  },
  {
    "path": "mir_msgs/msg/PlanSegments.msg",
    "chars": 34,
    "preview": "mir_msgs/PlanSegment[] p_segments\n"
  },
  {
    "path": "mir_msgs/msg/Pose2D.msg",
    "chars": 40,
    "preview": "float32 x\nfloat32 y\nfloat32 orientation\n"
  },
  {
    "path": "mir_msgs/msg/PowerBoardMotorStatus.msg",
    "chars": 1197,
    "preview": "uint16 LeftMotor_CtrlWord\nint32 LeftMotor_Speed\nint32 LeftMotor_Encoder\nuint16 LeftMotor_Status\nuint8 LeftMotor_Error\nui"
  },
  {
    "path": "mir_msgs/msg/PrecisionDockingStatus.msg",
    "chars": 87,
    "preview": "bool connected\nbool motor_forward\nbool motor_back\nbool left_docking\nbool right_docking\n"
  },
  {
    "path": "mir_msgs/msg/Proximity.msg",
    "chars": 30,
    "preview": "Header header\nuint16[] ranges\n"
  },
  {
    "path": "mir_msgs/msg/ResourceState.msg",
    "chars": 739,
    "preview": "string[] assigned # A list of IPs of all assigned robots (Areas can have more than one robot assigned at a time)\nuint32 "
  },
  {
    "path": "mir_msgs/msg/ResourcesAcquisition.msg",
    "chars": 81,
    "preview": "Header header\ngeometry_msgs/PoseStamped[] path\nstring position_guid\nstring token\n"
  },
  {
    "path": "mir_msgs/msg/ResourcesState.msg",
    "chars": 53,
    "preview": "Header header\nResourceState[] resources\nstring token\n"
  },
  {
    "path": "mir_msgs/msg/RobotMode.msg",
    "chars": 449,
    "preview": "# The robot operates in different mode\nuint8 ROBOT_MODE_NONE = 0\t\t# start mode\nuint8 ROBOT_MODE_MAPPING = 3\t\t# in mappin"
  },
  {
    "path": "mir_msgs/msg/RobotState.msg",
    "chars": 758,
    "preview": "# The robot has to be in a predefined state\nuint8 ROBOT_STATE_NONE = 0\nuint8 ROBOT_STATE_STARTING = 1\nuint8 ROBOT_STATE_"
  },
  {
    "path": "mir_msgs/msg/RobotStatus.msg",
    "chars": 614,
    "preview": "Header header\nfloat32 battery_percentage\nint32 battery_time_remaining\nfloat32 battery_voltage\nfloat32 distance_to_next_t"
  },
  {
    "path": "mir_msgs/msg/SafetyStatus.msg",
    "chars": 835,
    "preview": "bool is_connected\n\nbool is_firmware_ok\nint32 firmware_version\n\nbool in_protective_stop\nbool in_emergency_stop\nbool sto_f"
  },
  {
    "path": "mir_msgs/msg/Serial.msg",
    "chars": 26,
    "preview": "Header header\nstring data\n"
  },
  {
    "path": "mir_msgs/msg/ServiceResponseHeader.msg",
    "chars": 26,
    "preview": "bool success\nstring error\n"
  },
  {
    "path": "mir_msgs/msg/SkidDetectionDiff.msg",
    "chars": 188,
    "preview": "time time_stamp\nfloat64 enc_acc_x\nfloat64 enc_acc_y\nfloat64 enc_rot_th\n\n\nfloat64 imu_acc_x\nfloat64 imu_acc_y\nfloat64 imu"
  },
  {
    "path": "mir_msgs/msg/SkidDetectionStampedFloat.msg",
    "chars": 30,
    "preview": "time time_stamp\nfloat64 value\n"
  },
  {
    "path": "mir_msgs/msg/SoundEvent.msg",
    "chars": 200,
    "preview": "time time_stamp\nstring sound_guid\nstring message\n\nuint8 START=0\nuint8 STOP =1\nuint8 MUTE=2\nuint8 UNMUTE=3\nuint8 PAUSE=4\n"
  },
  {
    "path": "mir_msgs/msg/StampedEncoders.msg",
    "chars": 32,
    "preview": "Header header\nEncoders encoders\n"
  },
  {
    "path": "mir_msgs/msg/TimeDebug.msg",
    "chars": 44,
    "preview": "string[] description\nfloat64[] time_elapsed\n"
  },
  {
    "path": "mir_msgs/msg/Trolley.msg",
    "chars": 82,
    "preview": "int32 id\nfloat32 length\nfloat32 width\nfloat32 height\nfloat32 offset_locked_wheels\n"
  },
  {
    "path": "mir_msgs/msg/Twist2D.msg",
    "chars": 31,
    "preview": "float32 linear\nfloat32 angular\n"
  },
  {
    "path": "mir_msgs/msg/UserPrompt.msg",
    "chars": 97,
    "preview": "bool has_request\nstring guid\nstring user_group\nstring question\nstring[] options\nduration timeout\n"
  },
  {
    "path": "mir_msgs/msg/WebPath.msg",
    "chars": 34,
    "preview": "int32 seq\nfloat32[] x\nfloat32[] y\n"
  },
  {
    "path": "mir_msgs/msg/WorldMap.msg",
    "chars": 108,
    "preview": "mir_msgs/ResourcesState positions\nmir_msgs/ResourcesState areas\nmir_msgs/ExternalRobots robots\nint32 map_id\n"
  },
  {
    "path": "mir_msgs/msg/WorldModel.msg",
    "chars": 109,
    "preview": "Header header\nmir_msgs/WorldMap[] world_map # world model for a particular map\nbool enable_resource_tracking\n"
  },
  {
    "path": "mir_msgs/package.xml",
    "chars": 734,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_msgs</name>\n  <version>1.1.8</version>\n  <description>Message def"
  },
  {
    "path": "mir_navigation/CHANGELOG.rst",
    "chars": 8515,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_navigation\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2"
  },
  {
    "path": "mir_navigation/CMakeLists.txt",
    "chars": 1768,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_navigation)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roslaunch\n)\n\n##"
  },
  {
    "path": "mir_navigation/config/base_local_planner_params.yaml",
    "chars": 973,
    "preview": "base_local_planner: base_local_planner/TrajectoryPlannerROS\nTrajectoryPlannerROS:\n  # Robot configuration\n  acc_lim_x: 1"
  },
  {
    "path": "mir_navigation/config/costmap_common_params.yaml",
    "chars": 1165,
    "preview": "robot_base_frame: $(arg prefix)base_footprint\ntransform_tolerance: 0.4\nupdate_frequency: 5.0\npublish_frequency: 1.0\nobst"
  },
  {
    "path": "mir_navigation/config/costmap_global_params.yaml",
    "chars": 610,
    "preview": "global_costmap:\n    global_frame: map\n    update_frequency: 1.0\n    publish_frequency: 1.0\n    raytrace_range: 2.0\n    r"
  },
  {
    "path": "mir_navigation/config/costmap_global_params_plugins_no_virtual_walls.yaml",
    "chars": 224,
    "preview": "global_costmap:\n    plugins:\n        - {name: navigation_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obstacl"
  },
  {
    "path": "mir_navigation/config/costmap_global_params_plugins_virtual_walls.yaml",
    "chars": 294,
    "preview": "global_costmap:\n    plugins:\n        - {name: navigation_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obstacl"
  },
  {
    "path": "mir_navigation/config/costmap_local_params.yaml",
    "chars": 661,
    "preview": "local_costmap:\n    global_frame: $(arg prefix)odom\n    rolling_window: true\n    raytrace_range: 6.0\n    resolution: 0.05"
  },
  {
    "path": "mir_navigation/config/costmap_local_params_plugins_no_virtual_walls.yaml",
    "chars": 156,
    "preview": "local_costmap:\n    plugins:\n        - {name: obstacles,  type: \"costmap_2d::VoxelLayer\" }\n        - {name: inflation,  t"
  },
  {
    "path": "mir_navigation/config/costmap_local_params_plugins_virtual_walls.yaml",
    "chars": 226,
    "preview": "local_costmap:\n    plugins:\n        - {name: virtual_walls_map, type: \"costmap_2d::StaticLayer\" }\n        - {name: obsta"
  },
  {
    "path": "mir_navigation/config/dwa_local_planner_params.yaml",
    "chars": 2550,
    "preview": "base_local_planner: dwa_local_planner/DWAPlannerROS\nDWAPlannerROS:\n  # Robot configuration\n  max_vel_x:  0.8\n  min_vel_x"
  },
  {
    "path": "mir_navigation/config/dwb_local_planner_params.yaml",
    "chars": 3787,
    "preview": "base_local_planner: nav_core_adapter::LocalPlannerAdapter\nLocalPlannerAdapter:\n  planner_name: dwb_local_planner::DWBLoc"
  },
  {
    "path": "mir_navigation/config/eband_local_planner_params.yaml",
    "chars": 3389,
    "preview": "base_local_planner: eband_local_planner/EBandPlannerROS\nEBandPlannerROS:\n  # Robot configuration\n  max_vel_lin: 0.8     "
  },
  {
    "path": "mir_navigation/config/mir_local_planner_params.yaml",
    "chars": 3493,
    "preview": "base_local_planner: mirLocalPlanner/MIRPlannerROS\nMIRPlannerROS:\n  # Robot configuration\n  max_vel_x: 0.8\n  min_vel_x: -"
  },
  {
    "path": "mir_navigation/config/move_base_common_params.yaml",
    "chars": 964,
    "preview": "### footprint\nfootprint: [[0.488,-0.293],[0.488,0.293],[-0.412,0.293],[-0.412,-0.293]]\n\n### replanning\ncontroller_freque"
  },
  {
    "path": "mir_navigation/config/pose_local_planner_params.yaml",
    "chars": 1587,
    "preview": "base_local_planner: pose_follower/PoseFollower\nPoseFollower:\n    k_trans: 2.0\n    k_rot: 1.0\n\n    # within this distance"
  },
  {
    "path": "mir_navigation/config/rpp_local_planner_params.yaml",
    "chars": 4482,
    "preview": "# requires https://github.com/JohnTGZ/regulated_pure_pursuit_controller\n#\n# known bugs:\n# - ignores local costmap (will "
  },
  {
    "path": "mir_navigation/config/sbpl_global_params.yaml",
    "chars": 271,
    "preview": "base_global_planner: SBPLLatticePlanner\nSBPLLatticePlanner:\n  environment_type: XYThetaLattice\n  planner_type: ARAPlanne"
  },
  {
    "path": "mir_navigation/config/teb_local_planner_params.yaml",
    "chars": 12810,
    "preview": "# NOTE: When using the teb_local_planner, make sure to set the local costmap\n# resolution high (for example 0.1 m), othe"
  },
  {
    "path": "mir_navigation/launch/amcl.launch",
    "chars": 6146,
    "preview": "<?xml version=\"1.0\" ?>\n\n<launch>\n  <arg name=\"tf_prefix\" default=\"\" />\n  <arg name=\"namespace\" default=\"$(arg tf_prefix)"
  },
  {
    "path": "mir_navigation/launch/hector_mapping.launch",
    "chars": 2975,
    "preview": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"tf_map_scanmatch_transform_frame_name\" default=\"scanmatcher_frame\"/>\n  <arg "
  },
  {
    "path": "mir_navigation/launch/move_base.xml",
    "chars": 2402,
    "preview": "<launch>\n    <!--node ns=\"local_costmap\" name=\"voxel_grid_throttle\" pkg=\"topic_tools\" type=\"throttle\" args=\"messages vox"
  },
  {
    "path": "mir_navigation/launch/start_maps.launch",
    "chars": 733,
    "preview": "<launch>\n  <arg name=\"map_file\" default=\"$(find mir_gazebo)/maps/maze.yaml\" doc=\"Path to a map .yaml file (required).\" /"
  },
  {
    "path": "mir_navigation/launch/start_planner.launch",
    "chars": 1976,
    "preview": "<launch>\n  <arg name=\"local_planner\"          default=\"dwb\"             doc=\"Local planner can be either dwa, dwb, eband"
  },
  {
    "path": "mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m",
    "chars": 12995,
    "preview": "% /*\n%  * Copyright (c) 2008, Maxim Likhachev\n%  * All rights reserved.\n%  *\n%  * Redistribution and use in source and b"
  },
  {
    "path": "mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py",
    "chars": 21055,
    "preview": "#!/usr/bin/env python3\n#\n# Copyright (c) 2016, David Conner (Christopher Newport University)\n# Based on genmprim_unicycl"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm.mprim",
    "chars": 25116,
    "preview": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 80\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditio"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim",
    "chars": 34873,
    "preview": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim",
    "chars": 34985,
    "preview": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim",
    "chars": 50203,
    "preview": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 160\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_10cm.mprim",
    "chars": 34993,
    "preview": "resolution_m: 0.100000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_1cm.mprim",
    "chars": 35069,
    "preview": "resolution_m: 0.010000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_2_5cm.mprim",
    "chars": 35045,
    "preview": "resolution_m: 0.025000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_2cm.mprim",
    "chars": 35061,
    "preview": "resolution_m: 0.020000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/mprim/unicycle_highcost_5cm.mprim",
    "chars": 34889,
    "preview": "resolution_m: 0.050000\nnumberofangles: 16\ntotalnumberofprimitives: 112\nprimID: 0\nstartangle_c: 0\nendpose_c: 1 0 0\nadditi"
  },
  {
    "path": "mir_navigation/nodes/acc_finder.py",
    "chars": 3810,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_navigation/nodes/min_max_finder.py",
    "chars": 2526,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_navigation/package.xml",
    "chars": 1632,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_navigation</name>\n  <version>1.1.8</version>\n  <description>Launc"
  },
  {
    "path": "mir_navigation/rviz/navigation.rviz",
    "chars": 15268,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 81\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n      "
  },
  {
    "path": "mir_navigation/scripts/plot_mprim.py",
    "chars": 3496,
    "preview": "#!/usr/bin/env python3\n# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors\n#\n# Redistribution and use"
  },
  {
    "path": "mir_robot/CHANGELOG.rst",
    "chars": 1245,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package mir_robot\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n----"
  },
  {
    "path": "mir_robot/CMakeLists.txt",
    "chars": 108,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(mir_robot)\nfind_package(catkin REQUIRED)\ncatkin_metapackage()\n"
  },
  {
    "path": "mir_robot/package.xml",
    "chars": 1071,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>mir_robot</name>\n  <version>1.1.8</version>\n  <description>\n    URDF "
  },
  {
    "path": "pyproject.toml",
    "chars": 90,
    "preview": "[tool.black]\nline-length = 120\ntarget-version = ['py38']\nskip-string-normalization = true\n"
  },
  {
    "path": "sdc21x0/CHANGELOG.rst",
    "chars": 1186,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sdc21x0\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.1.8 (2025-05-13)\n----------"
  },
  {
    "path": "sdc21x0/CMakeLists.txt",
    "chars": 787,
    "preview": "cmake_minimum_required(VERSION 3.5.1)\nproject(sdc21x0)\n\nfind_package(catkin REQUIRED COMPONENTS\n  message_generation\n  s"
  },
  {
    "path": "sdc21x0/msg/Encoders.msg",
    "chars": 169,
    "preview": "float32 time_delta # Time since last encoder update.\nint32 left_wheel  # Encoder counts (absolute or relative)\nint32 rig"
  },
  {
    "path": "sdc21x0/msg/MotorCurrents.msg",
    "chars": 39,
    "preview": "float32 left_motor\nfloat32 right_motor\n"
  },
  {
    "path": "sdc21x0/msg/StampedEncoders.msg",
    "chars": 32,
    "preview": "Header header\nEncoders encoders\n"
  },
  {
    "path": "sdc21x0/package.xml",
    "chars": 743,
    "preview": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sdc21x0</name>\n  <version>1.1.8</version>\n  <description>Message defi"
  },
  {
    "path": "sdc21x0/srv/Flags.srv",
    "chars": 36,
    "preview": "int32 digitalPort\n---\nbool response\n"
  }
]

// ... and 8 more files (download for full content)

About this extraction

This page contains the full source code of the dfki-ric/mir_robot GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 187 files (677.4 KB), approximately 303.0k tokens, and a symbol index with 75 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.

Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.

Copied to clipboard!