[
  {
    "path": ".codespell-ignore-words.txt",
    "content": "ba\n"
  },
  {
    "path": ".github/workflows/CI.yaml",
    "content": "name: Noetic Continuous Integration\n\non:\n  push:\n  pull_request:\n\njobs:\n  CI:\n    runs-on: ubuntu-latest\n    container: osrf/ros:noetic-desktop\n    steps:\n      - uses: actions/checkout@v1\n        with:\n          path: src/SMACC\n\n      - shell: bash\n        run: |\n         source /opt/ros/noetic/setup.bash\n         apt update\n         rosdep update\n         rosdep install --from-paths . --ignore-src -r -y\n         cd ../../\n         catkin_make -DCMAKE_BUILD_TYPE=Debug\n"
  },
  {
    "path": ".github/workflows/bloom_release.yml",
    "content": "name: bloom-release\n\non:\n  push:\n    paths:\n      - package.xml\n      - '*/package.xml'\n      - '.github/workflows/bloom_release.yml'\n    branches: noetic-devel\n\njobs:\n  bloom-release:\n    runs-on: ubuntu-latest\n    env:\n      ROS_DISTRO: noetic\n      PRERELEASE: true\n      BASEDIR: ${{ github.workspace }}/.work\n\n    steps:\n      - name: checkout\n        uses: actions/checkout@v2\n\n      # BASIC CODE QUALITY\n      - run: |\n          sudo apt-get update\n          sudo apt-get install -y clang-format-12\n\n      - uses: actions/setup-python@v3\n        with:\n          python-version: 3.9\n\n      - name: code quality check\n        uses: pre-commit/action@v3.0.0\n\n      # BLOOM PRERELEASE CHECK\n      # - name: industrial_ci prerelease check\n      #   uses: ros-industrial/industrial_ci@master\n\n      # BLOOM RELEASE\n      - name: bloom release\n        uses: pabloinigoblasco/bloom-release-action@master\n        with:\n          ros_distro: ${{ env.ROS_DISTRO }}\n          github_token_bloom: ${{ secrets.GITTOKEN_BLOOM }}\n          github_user: pabloinigoblasco\n          git_user: pabloinigoblasco\n          git_email: pablo@ibrobotics.com\n          release_repository_push_url: https://github.com/robosoft-ai/SMACC-release\n          tag_and_release: true\n          #open_pr: true\n"
  },
  {
    "path": ".github/workflows/code_quality.yml",
    "content": "name: Code Format & Quality\n\non:\n  pull_request:\n  push:\n\njobs:\n  pre-commit:\n    runs-on: ubuntu-latest\n    steps:\n    - run: |\n        sudo apt-get update\n        sudo apt-get install -y clang-format-12\n    - uses: actions/checkout@v3\n    - uses: actions/setup-python@v3\n      with:\n        python-version: 3.9\n    - uses: pre-commit/action@v3.0.0\n"
  },
  {
    "path": ".github/workflows/doxygen.yml",
    "content": "name: Doxygen\n\non:\n  push:\n    branches: [noetic-devel]\n\njobs:\n  doxygen:\n    runs-on: ubuntu-20.04\n    steps:\n      - uses: actions/checkout@v1\n\n      - uses: mattnotmitt/doxygen-action@v1\n        with:\n          doxyfile-path: 'smacc_ci/Doxyfile'\n\n      - uses: peaceiris/actions-gh-pages@v3\n        with:\n          deploy_key: ${{ secrets.ACTION_DEPLOY_KEY }}\n          external_repository:  robosoft-ai/smacc_doxygen\n          publish_branch: gh-pages\n          publish_dir: docs/\n          destination_dir: noetic\n          commit_message: ${{ github.event.head_commit.message }}\n"
  },
  {
    "path": ".gitignore",
    "content": "build\ninstall\nlog\nbin\n"
  },
  {
    "path": ".pre-commit-config.yaml",
    "content": "# To use:\n#\n#     pre-commit run -a\n#\n# Or:\n#\n#     pre-commit install  # (runs every time you commit in git)\n#\n# To update this file:\n#\n#     pre-commit autoupdate\n#\n# See https://github.com/pre-commit/pre-commit\n\nrepos:\n  # Standard hooks\n  - repo: https://github.com/pre-commit/pre-commit-hooks\n    rev: v4.1.0\n    hooks:\n      - id: check-added-large-files\n      - id: check-ast\n      - id: check-case-conflict\n      - id: check-docstring-first\n      - id: check-merge-conflict\n      - id: check-symlinks\n      - id: check-xml\n      #- id: check-yaml\n      - id: debug-statements\n      - id: end-of-file-fixer\n      - id: mixed-line-ending\n      - id: trailing-whitespace\n      - id: fix-byte-order-marker\n\n  # Python hooks\n  - repo: https://github.com/asottile/pyupgrade\n    rev: v2.31.0\n    hooks:\n    -   id: pyupgrade\n        args: [--py36-plus]\n\n  - repo: https://github.com/psf/black\n    rev: 22.3.0\n    hooks:\n      - id: black\n        args: [\"--line-length=99\"]\n\n  # PEP 257\n  - repo: https://github.com/FalconSocial/pre-commit-mirrors-pep257\n    rev: v0.3.3\n    hooks:\n    - id: pep257\n      args: [\"--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404\"]\n\n  - repo: https://github.com/pycqa/flake8\n    rev: 4.0.1\n    hooks:\n    - id: flake8\n      args: [\"--ignore=E501,W503,E203\"]\n\n  # CPP hooks\n  - repo: local\n    hooks:\n      - id: clang-format\n        name: clang-format\n        description: Format files with ClangFormat.\n        entry: clang-format\n        language: system\n        files: \\.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$\n        args: ['-fallback-style=none', '-i']\n        # exclude: smacc2_sm_reference_library/\n\n\n  # Docs - RestructuredText hooks\n  - repo: https://github.com/PyCQA/doc8\n    rev: 0.10.1\n    hooks:\n      - id: doc8\n        args: ['--max-line-length=100', '--ignore=D001']\n        exclude: CHANGELOG\\.rst$\n\n  - repo: https://github.com/pre-commit/pygrep-hooks\n    rev: v1.9.0\n    hooks:\n      - id: rst-backticks\n        exclude: CHANGELOG\\.rst$\n      - id: rst-directive-colons\n      - id: rst-inline-touching-normal\n\n  # Spellcheck in comments and docs\n  # skipping of *.svg files is not working...\n  - repo: https://github.com/codespell-project/codespell\n    rev: v2.1.0\n    hooks:\n      - id: codespell\n        name: codespell\n        description: Checks for common misspellings in text files.\n        entry: codespell\n        language: python\n        types: [text]\n        args: ['--ignore-words=.codespell-ignore-words.txt', '--write-changes']\n        exclude: \\.(svg|pyc)$\n"
  },
  {
    "path": ".vscode/launch.json",
    "content": "{\n    // Use IntelliSense to learn about possible attributes.\n    // Hover to view descriptions of existing attributes.\n    // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387\n    \"version\": \"0.2.0\",\n    \"configurations\": [\n    {\n        \"name\": \"(gdb) sm_fetch\",\n        \"type\": \"cppdbg\",\n        \"request\": \"launch\",\n        \"program\": \"${workspaceFolder}/devel/lib/sm_fetch_six_table_pick_n_sort_1/sm_fetch_six_table_pick_n_sort_1_node\",\n        \"args\": [\"__name:=sm_fetch_six_table_pick_n_sort_1_node\"],\n        \"stopAtEntry\": false,\n        \"cwd\": \"${workspaceFolder}\",\n        \"environment\": [],\n        \"console\": \"externalTerminal\",\n        \"MIMode\": \"gdb\",\n        \"setupCommands\": [\n            {\n                \"description\": \"Enable pretty-printing for gdb\",\n                \"text\": \"-enable-pretty-printing\",\n                \"ignoreFailures\": true\n            }\n        ]\n    },\n    {\n        \"name\": \"(gdb) sm_atomic_mode_states\",\n        \"type\": \"cppdbg\",\n        \"request\": \"launch\",\n        \"program\": \"${workspaceFolder}/../../devel/lib/sm_atomic_mode_states/sm_atomic_mode_states_node\",\n        \"args\": [\"__name:=sm_fetch_six_table_pick_n_sort_1_node\"],\n        \"stopAtEntry\": false,\n        \"cwd\": \"${workspaceFolder}\",\n        \"environment\": [],\n        \"console\": \"externalTerminal\",\n        \"MIMode\": \"gdb\",\n        \"setupCommands\": [\n            {\n                \"description\": \"Enable pretty-printing for gdb\",\n                \"text\": \"-enable-pretty-printing\",\n                \"ignoreFailures\": true\n            }\n        ]\n    },\n    {\n        \"name\": \"(gdb) smacc_rta\",\n        \"type\": \"cppdbg\",\n        \"request\": \"launch\",\n        \"program\": \"${workspaceFolder}/../build/smacc_rta/smacc_rta\",\n        \"args\": [\"__name:=smacc_rta\"],\n        \"stopAtEntry\": false,\n        \"cwd\": \"${workspaceFolder}\",\n        \"environment\": [],\n        \"console\": \"externalTerminal\",\n        \"MIMode\": \"gdb\",\n        \"setupCommands\": [\n            {\n                \"description\": \"Enable pretty-printing for gdb\",\n                \"text\": \"-enable-pretty-printing\",\n                \"ignoreFailures\": true\n            }\n        ]\n    },\n        {\n            \"name\": \"Smacc Viewer\",\n            \"type\": \"python\",\n            \"request\": \"launch\",\n            \"program\": \"${workspaceFolder}/src/SMACC_Viewer/smacc_viewer/scripts/smacc_viewer_node.py\",\n            \"console\": \"integratedTerminal\"\n        }\n    ]\n}\n"
  },
  {
    "path": "LICENSE.txt",
    "content": "BSD 3-Clause License\n\nCopyright (c) Reelrobotix, Inc.\nAll rights reserved.\n\nRedistribution and use in source and binary forms, with or without\nmodification, are permitted provided that the following conditions are met:\n\n* Redistributions of source code must retain the above copyright notice, this\n  list of conditions and the following disclaimer.\n\n* Redistributions in binary form must reproduce the above copyright notice,\n  this list of conditions and the following disclaimer in the documentation\n  and/or other materials provided with the distribution.\n\n* Neither the name of the copyright holder nor the names of its\n  contributors may be used to endorse or promote products derived from\n  this software without specific prior written permission.\n\nTHIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\nAND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\nDISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE\nFOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\nDAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\nSERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\nCAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\nOR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\nOF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "README.md",
    "content": "\n## Continuous Integration:\n\n\n| ROS Distro  | Code Format & Quality | Documentation | Binary Packages |\n| :-----------: | :-----------: | :-----------: | :-----------: |\n| Melodic  | [![Code Format & Quality](https://github.com/robosoft-ai/SMACC/actions/workflows/code_quality.yml/badge.svg?branch=melodic-devel)](https://github.com/robosoft-ai/SMACC/actions/workflows/code_quality.yml) | [![Doxygen](https://github.com/robosoft-ai/SMACC/actions/workflows/doxygen.yml/badge.svg?branch=melodic-devel)](https://github.com/robosoft-ai/SMACC/actions/workflows/doxygen.yml) <br/> <a href=\"https://robosoft-ai.github.io/smacc_doxygen/melodic/html/namespaces.html\">doxygen</a>|[![Build Status](https://build.ros.org/job/Mdev__smacc__ubuntu_bionic_amd64/badge/icon?subject=ros-buildfarm)](https://build.ros.org/job/Mdev__smacc__ubuntu_bionic_amd64/)<br/>[![bloom-release](https://build.ros2.org/job/Hdev__SMACC2__ubuntu_jammy_amd64/badge/icon?style=plastic&subject=bloom-release&status=E.O.L&color=lightgray)](http://wiki.ros.org/Distributions)<br/>[SMACC](https://index.ros.org/p/smacc/github-robosoft-ai-smacc/#melodic)|\n| Noetic  | [![Code Format & Quality](https://github.com/robosoft-ai/SMACC/actions/workflows/code_quality.yml/badge.svg?branch=noetic-devel)](https://github.com/robosoft-ai/SMACC/actions/workflows/code_quality.yml) | [![Doxygen](https://github.com/robosoft-ai/SMACC/actions/workflows/doxygen.yml/badge.svg?branch=noetic-devel)](https://github.com/robosoft-ai/SMACC/actions/workflows/doxygen.yml) <br/> <a href=\"https://robosoft-ai.github.io/smacc_doxygen/noetic/html/namespaces.html\">doxygen</a>|  [![Build Status](https://build.ros.org/job/Ndev__smacc__ubuntu_focal_amd64/badge/icon?subject=ros-buildfarm)](https://build.ros.org/job/Ndev__smacc__ubuntu_focal_amd64/)<br/>[![bloom-release](https://github.com/robosoft-ai/SMACC/actions/workflows/bloom_release.yml/badge.svg?branch=noetic-devel)](https://github.com/robosoft-ai/smacc/actions/workflows/bloom_release.yml) <br/>[SMACC](https://index.ros.org/p/smacc/github-robosoft-ai-smacc/#noetic)|\n\n## Docker Containers\n\n[![Docker Automated build](https://img.shields.io/docker/automated/pabloinigoblasco/smacc.svg?maxAge=2592000)](https://hub.docker.com/r/pabloinigoblasco/smacc/) [![Docker Pulls](https://img.shields.io/docker/pulls/pabloinigoblasco/smacc.svg?maxAge=2592000)](https://hub.docker.com/r/pabloinigoblasco/smacc/) [![Docker Stars](https://img.shields.io/docker/stars/pabloinigoblasco/smacc.svg)](https://registry.hub.docker.com/pabloinigoblasco/smacc/)\n\n\n# <img src=\"http://smacc.dev/wp-content/uploads/2019/07/SMACC-Logo-Pixelate-4-copy.png\" width=\"30\" align=\"left\"/> SMACC\n\nSMACC is an event-driven, asynchronous, behavioral state machine library for real-time ROS (Robotic Operating System) applications written in C++, designed to allow programmers to build robot control applications for multicomponent robots, in an intuitive and systematic manner.\n\nSMACC was inspired by Harel's statecharts and the [SMACH ROS package](http://wiki.ros.org/smach). SMACC is built on top of the [Boost StateChart library](https://www.boost.org/doc/libs/1_53_0/libs/statechart/doc/index.html).\n\n\n## Features\n *  ***Powered by ROS:*** SMACC has been developed specifically to work with ROS. It supports ROS topics, services and actions, right out of the box.\n *   ***Written in C++:*** Until now, ROS has lacked a library to develop task-level behavioral state machines in C++. Although libraries have been developed in scripting languages such as python, these are unsuitable for real-world industrial environments where real-time requirements are demanded.\n *   ***Orthogonals:*** Originally conceived by David Harel in 1987, orthogonality is absolutely crucial to developing state machines for complex robotic systems. This is because complex robots are always a collection of hardware devices which require communication protocols, start-up determinism, etc. With orthogonals, it is an intuitive and relatively straight forward exercise (at least conceptually;) to code a state machine for a robot comprising a mobile base, a robotic arm, a gripper, two lidar sensors, a gps transceiver and an imu, for instance.\n *  ***Static State Machine Checking:*** One of the features that SMACC inherits from Boost Statechart is that you get compile time validation checking. This benefits developers in that the amount of runtime testing necessary to ship quality software that is both stable and safe is dramatically reduced. Our philosophy is \"Wherever possible, let the compiler do it\".\n *  ***State Machine Reference Library:*** With a constantly growing library of out-of-the-box reference state machines, (found in the folder [sm_reference_library](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library)) guaranteed to compile and run, you can jumpstart your development efforts by choosing a reference machine that is closest to your needs, and then customize and extend to meet the specific requirements of your robotic application. All the while knowing that the library supports advanced functionalities that are practically universal among actual working robots.\n *  ***SMACC Client Library:*** SMACC also features a constantly growing library of [clients](https://github.com/robosoft-ai/SMACC/tree/master/smacc_client_library) that support ROS Action Servers, Service Servers and other nodes right out-of-the box. The clients within the SMACC Client library have been built utilizing a component based architecture that allows for developer to build powerful clients of their own. Current clients of note include MoveBaseZ, a full featured Action Client built to integrate with the ROS Navigation stack, the ros_timer_client, the multi_role_sensor_client, and a keyboard_client used extensively for state machine drafting & debugging.\n  *  ***Extensive Documentation:*** Although many ROS users are familiar with doxygen, our development team has spent a lot of time researching the more advanced features of doxygen such as uml style class diagrams and call graphs, and we've used them to document the SMACC library. Have a look to [our doxygen sites](https://robosoft-ai.github.io/smacc_doxygen/master/html/namespaces.html) and we think you'll be blown away at what Doxygen looks like when [it's done right](https://robosoft-ai.github.io/smacc_doxygen/master/html/classsmacc_1_1ISmaccStateMachine.html) and it becomes a powerful tool to research a codebase.\n  *  ***SMACC1 Runtime Analyzer:*** The SMACC library for ROS1 works out of the box with the SMACC1 RTA. This allows developers to visualize and runtime debug the state machines they are working on. The SMACC1 RTA is closed source, but is free for individual and academic use. It can be found [here](https://robosoft.ai/product-category/smacc1-runtime-analyzer/), along with installation instructions which can be found [here](https://robosoft.ai/smacc1_rta-installation/).\n\n\n## SMACC applications\nFrom it's inception, SMACC was written to support the programming of multi-component, complex robots. If your project involves small, solar-powered insect robots, that simply navigate towards a light source, then SMACC might not be the right choice for you. But if you are trying to program a robot with a mobile base, a robotic arm, a gripper, two lidar sensors, a gps transceiver and an imu, then you've come to the right place.\n\n\n## Getting Started\nThe easiest way to get started is by selecting one of the state machines in our [reference library](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library), and then hacking it to meet your needs.\n\nEach state machine in the reference library comes with it's own README.md file, which contains the appropriate operating instructions, so that all you have to do is simply copy & paste some commands into your terminal.\n\n\n  *  If you are looking for a minimal example, we recommend [sm_atomic](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library/sm_atomic).\n\n  *  If you are looking for a slightly more complicated, but still very simple example, try [sm_calendar_week](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library/sm_calendar_week).\n\n  *  If you are looking for a minimal example but with a looping superstate, try [sm_three_some](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library/sm_three_some).\n\n  *  If you want to get started with the ROS Navigation stack right away, try [sm_dance_bot](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library/sm_dance_bot).\n\n  *  If you want to get started with ROS Navigation and exploring the orthogonal read-write cycle, then try [sm_dance_bot_strikes_back](https://github.com/robosoft-ai/SMACC/tree/master/smacc_sm_reference_library/sm_dance_bot_strikes_back).\n\n\nOperating instructions can be found in each reference state machines readme file.\nHappy Coding.\n\n## Support\nIf you are interested in getting involved or need a little support, feel free to contact us by emailing brett@robosoft.ai\n"
  },
  {
    "path": "smacc/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package smacc\n^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Progressing on transition log\n* dynamic behavior\n* progress on viewer, modestates and history mode\n* smacc megastate example\n* missing changes on previous commit\n* more improvements on status message on the viewer and the smacc core\n* some stable version of the viewer, code cleaning, fixes on dancebot\n* progress in the viewer, creating a new concept of transition tag\n* progress in the viewer\n* SMACC improvements on the viewer and loop branching funcionality\n* progressing in the smacc viewer\n* fixing logic units event source information\n* progressing in viewer and metainformation\n* progressing in the viewer and adding more metaknoledge about triggering events of logic units\n* progress in the viewer and examples\n* fixing eveng aggregator compilation issue\n* more fixings and progressing to the smacc_viewer\n* recurrent pattern for sensors and substate behaviors\n* template recurrent pattern, string type walker, showing string for smacc viewer\n* adding transition file\n* moving behavior creation of sm_dance_bot to static staticConfigure\n* action client moving to event convention Ev<TSource>\n* logic units, better output of the state machine knowledge at the startup\n* StateTransition info structure\n* creating static staticConfigure functionality\n* removing obsolete state funcionality\n* broken build orthogonal fix\n* changes on architecture, orthogonal role, client role and component role changes, fixing all examples\n* adding service client\n* smacc_msgs dependencies\n* smacc_msgs dependencies\n* gh-pages travis\n* ff pattern and spattern first implementation\n* fixing build\n* testing status message, creation of rviz display plugin, refactoring of sm_dance_bot.launch to make it lightweight, readme.md for launching\n* adding SmaccStatus message funcionality\n* PackML inspired funcionalities for SM: stop, estop, reset\n* several improvements: adding topicPublisherClient, fixing install build, further testing of sm_dance_bot on install workspace\n* adding publisher client\n* working on fixing travis build\n* working on fixing travis\n* superstates improving the viewer for the dance_bot\n* many core fixes and refactorings, substate behavior destroying, dance_bot keyboard separated in two files, topic sensor separated in two files too for the client and the substate behavior\n* progressing on keyboard\n* introducing the client concept and moving smacc topic subscriber to the smacc 'core' package\n* ClMultiroleSensor and TopicSubscriber\n* detaching substatebehaviors from component and renaming class refactoring\n* making smacc_viewer run and also refactoring smacc_state_info headers\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* minor changes\n* Minor commenting edits\n* more improvements on sensor topics keyboard events, and architecture improvements\n* refactoring smacc substate behaviors and states\n* changes on code\n* better rosout and some progress on sm_dance_bot and fixing travis build\n* runtime testing of examples\n* hard renaming - namming convention - initial integration of smach_viewer\n* Folder Renaming\n* SMACC building\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* fixing smacc for melodic\n* c++11 for indigo in some projects\n* Merge branch 'master' into indigo-devel\n* removing boost demangle dependency to make build indigo\n* makin build SMACC for indigo\n* Merge branch 'master' into indigo-devel\n* merge on melodic\n* updating backward and forward local planners\n* Merge remote-tracking branch 'origin/master' into melodic-devel\n* Merge branch 'master' into indigo-devel\n* updating cmakelists\n* Merge branch 'master' of https://github.com/pabloinigoblasco/SMACC\n* Merge pull request `#1 <https://github.com/robosoft-ai/SMACC/issues/1>`_ from robosoft-ai/master\n  merging\n* smacc improvements\n* minor\n* navigation improvements and syntax improvements in example\n* final waypoints tests\n* progress on waypoints\n* renaming getglobalData setGlobalData\n* authory in code files and more in documentation\n* important refactoring and fixes, and the creation of the radial_motion example\n* syntax improvement to remove the context from smacc code\n* adapting to the smacc requiresComponent method refactoring\n* refactoring smacc to support other kind of plugins beyond actionclients, such as the odom tracker, also ading a custom radial_motion_example independent to the reel\n* refactoring SMACC to contain navigation plugins\n* adding planners to SMACC\n* package version\n* package.xml format\n* adding feedback message information to feedback events\n* syntax improvement for better action result reaction\n* some refactoring on smacc code\n* more on documentation\n* fixing ros parameters\n* Tool orthogonal line and wiki documentation\n* cleaning and refactoring smacc library\n* adding tool orthogonal line\n* Adapting to smacc feedback message improvemnts. Now, the transitions reacts on these action feedback messages, instead of action results\n* minor changes on radial motion sample\n* feedback message support\n* refactoring, renamings, documenting smacc\n* some more on style\n* more comments and style\n* some more comments\n* large refactoring of the smacc example code and comments\n* minor\n* initial version of radial motion example\n* going forward to radial example\n* minor to show some example\n* going forward to smacc\n* minor fixes\n* initials on smacc\n* Moved SMACC to it's own repo..\n* Contributors: Pablo Inigo Blasco, Pablo Iñigo Blasco, brett2@robosoft-ai.com, brettpac, travis\n"
  },
  {
    "path": "smacc/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(smacc)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED COMPONENTS\n  actionlib\n  roscpp\n  pluginlib\n  smacc_msgs\n  controller_manager_msgs\n)\n\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n###################################\n## catkin specific configuration ##\n###################################\n\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES smacc\n  CATKIN_DEPENDS actionlib roscpp smacc_msgs controller_manager_msgs smacc_msgs message_runtime\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n  include\n  ${catkin_INCLUDE_DIRS}\n)\n\nfile(GLOB_RECURSE ${PROJECT_NAME}_IncludeFilesPaths \"*.h\")\nadd_custom_target(${PROJECT_NAME}_IncludeFilesTarget SOURCES ${${PROJECT_NAME}_IncludeFilesPaths})\n\n# sources\nfile(GLOB_RECURSE SRC_FILES \"src/smacc/*.cpp\" \"src/smacc/introspection/*.cpp\" \"src/smacc/state_reactors/*.cpp\") # opcionalmente GLOB\n\nadd_library(${PROJECT_NAME} ${SRC_FILES})\n\n## Add cmake target dependencies of the executable\n## same as for the library above\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n#############\n## Testing ##\n#############\n"
  },
  {
    "path": "smacc/include/smacc/callback_counter_semaphore.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <iostream>\n#include <boost/signals2.hpp>\n#include <thread>\n#include <condition_variable>\n#include <mutex>\n#include <boost/signals2.hpp>\n#include <ros/ros.h>\n\nnamespace smacc\n{\nclass CallbackCounterSemaphore {\npublic:\n    CallbackCounterSemaphore(std::string name, int count = 0);\n    bool acquire();\n\n    void release();\n\n    void finalize();\n\n    void addConnection(boost::signals2::connection conn);\n\nprivate:\n    int count_;\n    std::mutex mutex_;\n    std::condition_variable cv_;\n    std::vector<boost::signals2::connection> connections_;\n    bool finalized = false;\n    std::string name_;\n};\n}\n"
  },
  {
    "path": "smacc/include/smacc/client_base_components/cp_ros_control_interface.h",
    "content": "#pragma once\n#include <smacc/component.h>\n#include <controller_manager_msgs/ControllerState.h>\n\nnamespace smacc\n{\nnamespace components\n{\nstruct ControllerTypeInfo\n{\n    std::string type;\n    std::string baseClass;\n};\n\nenum Strictness\n{\n    BEST_EFFORT = 1,\n    STRICT = 2\n};\n\nclass CpRosControlInterface : public smacc::ISmaccComponent\n{\npublic:\n    CpRosControlInterface();\n\n    virtual ~CpRosControlInterface();\n\n    virtual void onInitialize() override;\n\n    // template <typename TOrthogonal, typename TSourceObject>\n    // void onOrthogonalAllocation() {}\n\n    std::vector<ControllerTypeInfo> listControllerTypes();\n\n    std::vector<controller_manager_msgs::ControllerState> listControllers();\n\n    bool loadController(std::string name);\n\n    bool unloadController(std::string name);\n\n    bool reloadControllerLibraries(bool forceKill);\n\n    bool switchControllers(std::vector<std::string> start_controllers,\n                           std::vector<std::string> stop_controllers,\n                           Strictness strictness);\n\n    boost::optional<std::string> serviceName_;\n\nprivate:\n    ros::NodeHandle nh_;\n\n    ros::ServiceClient srvListControllers;\n    ros::ServiceClient srvListControllersTypes;\n    ros::ServiceClient srvLoadController;\n    ros::ServiceClient srvReloadControllerLibraries;\n    ros::ServiceClient srvSwitchControllers;\n    ros::ServiceClient srvUnloadController;\n};\n}\n}\n"
  },
  {
    "path": "smacc/include/smacc/client_base_components/cp_topic_subscriber.h",
    "content": "#pragma once\n#include <smacc/component.h>\n#include <smacc/smacc_signal.h>\n#include <boost/optional/optional_io.hpp>\n#include <smacc/client_bases/smacc_subscriber_client.h>\n\nnamespace smacc\n{\nnamespace components\n{\n\nusing namespace smacc::default_events;\n\ntemplate <typename MessageType>\nclass CpTopicSubscriber : public smacc::ISmaccComponent\n{\npublic:\n    boost::optional<std::string> topicName;\n    boost::optional<int> queueSize;\n\n    typedef MessageType TMessageType;\n\n    CpTopicSubscriber()\n    {\n        initialized_ = false;\n    }\n\n    CpTopicSubscriber(std::string topicname)\n    {\n        topicName = topicname;\n    }\n\n    virtual ~CpTopicSubscriber()\n    {\n        sub_.shutdown();\n    }\n\n    smacc::SmaccSignal<void(const MessageType &)> onFirstMessageReceived_;\n    smacc::SmaccSignal<void(const MessageType &)> onMessageReceived_;\n\n    std::function<void(const MessageType &)> postMessageEvent;\n    std::function<void(const MessageType &)> postInitialMessageEvent;\n\n    template <typename T>\n    boost::signals2::connection onMessageReceived(void (T::*callback)(const MessageType &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onMessageReceived_, callback, object);\n    }\n\n    template <typename T>\n    boost::signals2::connection onFirstMessageReceived(void (T::*callback)(const MessageType &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onFirstMessageReceived_, callback, object);\n    }\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        this->postMessageEvent = [=](auto msg) {\n            auto event = new EvTopicMessage<TSourceObject, TOrthogonal>();\n            event->msgData = msg;\n            this->postEvent(event);\n        };\n\n        this->postInitialMessageEvent = [=](auto msg) {\n            auto event = new EvTopicInitialMessage<TSourceObject, TOrthogonal>();\n            event->msgData = msg;\n            this->postEvent(event);\n        };\n    }\n\n    virtual void initialize()\n    {\n        if (!initialized_)\n        {\n            firstMessage_ = true;\n\n            if (!queueSize)\n                queueSize = 1;\n\n            if (!topicName)\n            {\n                ROS_ERROR(\"topic client with no topic name set. Skipping subscribing\");\n            }\n            else\n            {\n                ROS_INFO_STREAM(\"[\" << this->getName() << \"] Subscribing to topic: \" << topicName);\n\n                sub_ = nh_.subscribe(*topicName, *queueSize, &CpTopicSubscriber<MessageType>::messageCallback, this);\n                this->initialized_ = true;\n            }\n        }\n    }\n\nprotected:\n    ros::NodeHandle nh_;\n\nprivate:\n    ros::Subscriber sub_;\n    bool firstMessage_;\n    bool initialized_;\n\n    void messageCallback(const MessageType &msg)\n    {\n        if (firstMessage_)\n        {\n            postInitialMessageEvent(msg);\n            onFirstMessageReceived_(msg);\n            firstMessage_ = false;\n        }\n\n        postMessageEvent(msg);\n        onMessageReceived_(msg);\n    }\n};\n}\n}\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_action_client.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_client.h>\n#include <smacc/smacc_state_machine.h>\n#include <actionlib/client/simple_action_client.h>\n\nnamespace smacc\n{\nnamespace client_bases\n{\n    using namespace actionlib;\n\n    // This class interface shows the basic set of methods that\n    // a SMACC \"resource\" or \"plugin\" Action Client has\n    class ISmaccActionClient : public ISmaccClient\n    {\n    public:\n        ISmaccActionClient();\n\n        // The destructor. This is called when the object is not\n        // referenced anymore by its owner\n        virtual ~ISmaccActionClient();\n\n        // Gets the ros path of the action...\n        inline std::string getNamespace() const\n        {\n            return name_;\n        }\n\n        virtual void cancelGoal() = 0;\n\n        virtual SimpleClientGoalState getState() = 0;\n\n    protected:\n        // The ros path where the action server is located\n        std::string name_;\n    };\n} // namespace smacc\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_action_client_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/client_bases/smacc_action_client.h>\n#include <smacc/smacc_signal.h>\n\n#include <boost/optional/optional_io.hpp>\n\nnamespace smacc\n{\nnamespace client_bases\n{\nusing namespace smacc::default_events;\n\ntemplate <typename ActionType>\nclass SmaccActionClientBase : public ISmaccActionClient\n{\npublic:\n    // Inside this macro you can find the typedefs for Goal and other types\n    ACTION_DEFINITION(ActionType);\n    typedef actionlib::SimpleActionClient<ActionType> ActionClient;\n    typedef actionlib::SimpleActionClient<ActionType> GoalHandle;\n\n    typedef typename ActionClient::SimpleDoneCallback SimpleDoneCallback;\n    typedef typename ActionClient::SimpleActiveCallback SimpleActiveCallback;\n    typedef typename ActionClient::SimpleFeedbackCallback SimpleFeedbackCallback;\n\n    SmaccActionClientBase(std::string actionServerName)\n        : ISmaccActionClient(),\n          name_(actionServerName)\n    {\n    }\n\n    SmaccActionClientBase()\n        : ISmaccActionClient(),\n          name_(\"\")\n    {\n    }\n\n    static std::string getEventLabel()\n    {\n        auto type = TypeInfo::getTypeInfoFromType<ActionType>();\n        return type->getNonTemplatedTypeName();\n    }\n\n    virtual ~SmaccActionClientBase()\n    {\n    }\n\n    /// rosnamespace path\n    std::string name_;\n\n    virtual void initialize() override\n    {\n        client_ = std::make_shared<ActionClient>(name_);\n    }\n\n    smacc::SmaccSignal<void(const ResultConstPtr &)> onSucceeded_;\n    smacc::SmaccSignal<void(const ResultConstPtr &)> onAborted_;\n    smacc::SmaccSignal<void(const ResultConstPtr &)> onPreempted_;\n    smacc::SmaccSignal<void(const ResultConstPtr &)> onRejected_;\n\n    // event creation/posting factory functions\n    std::function<void(ResultConstPtr)> postSuccessEvent;\n    std::function<void(ResultConstPtr)> postAbortedEvent;\n    std::function<void(ResultConstPtr)> postPreemptedEvent;\n    std::function<void(ResultConstPtr)> postRejectedEvent;\n\n    std::function<void(FeedbackConstPtr)> postFeedbackEvent;\n\n    SimpleDoneCallback done_cb;\n    SimpleActiveCallback active_cb;\n    SimpleFeedbackCallback feedback_cb;\n\n    template <typename EvType>\n    void postResultEvent(ResultConstPtr result)\n    {\n        auto *ev = new EvType();\n        //ev->client = this;\n        ev->resultMessage = *result;\n        ROS_INFO(\"Posting EVENT %s\", demangleSymbol(typeid(ev).name()).c_str());\n        this->postEvent(ev);\n    }\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        // we create here all the event factory functions capturing the TOrthogonal\n        postSuccessEvent = [=](auto msg) { this->postResultEvent<EvActionSucceeded<TSourceObject, TOrthogonal>>(msg); };\n        postAbortedEvent = [=](auto msg) { this->postResultEvent<EvActionAborted<TSourceObject, TOrthogonal>>(msg); };\n        postPreemptedEvent = [=](auto msg) { this->postResultEvent<EvActionPreempted<TSourceObject, TOrthogonal>>(msg); };\n        postRejectedEvent = [=](auto msg) { this->postResultEvent<EvActionRejected<TSourceObject, TOrthogonal>>(msg); };\n        postFeedbackEvent = [=](auto msg) {\n            auto actionFeedbackEvent = new EvActionFeedback<Feedback, TOrthogonal>();\n            actionFeedbackEvent->client = this;\n            actionFeedbackEvent->feedbackMessage = *msg;\n            this->postEvent(actionFeedbackEvent);\n            ROS_DEBUG(\"[%s] FEEDBACK EVENT\", demangleType(typeid(*this)).c_str());\n        };\n\n        done_cb = boost::bind(&SmaccActionClientBase<ActionType>::onResult, this, _1, _2);\n        //active_cb;\n        feedback_cb = boost::bind(&SmaccActionClientBase<ActionType>::onFeedback, this, _1);\n    }\n\n    template <typename T>\n    boost::signals2::connection onSucceeded(void (T::*callback)(ResultConstPtr &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onSucceeded_, callback, object);\n    }\n\n    template <typename T>\n    boost::signals2::connection onSucceeded(std::function<void(ResultConstPtr &)> callback)\n    {\n        return this->getStateMachine()->createSignalConnection(onSucceeded_, callback);\n    }\n\n    template <typename T>\n    boost::signals2::connection onAborted(void (T::*callback)(ResultConstPtr &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onAborted_, callback, object);\n    }\n\n    template <typename T>\n    boost::signals2::connection onAborted(std::function<void(ResultConstPtr &)> callback)\n    {\n        return this->getStateMachine()->createSignalConnection(onAborted_, callback);\n    }\n\n    template <typename T>\n    boost::signals2::connection onPreempted(void (T::*callback)(ResultConstPtr &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onPreempted_, callback, object);\n    }\n\n    template <typename T>\n    boost::signals2::connection onPreempted(std::function<void(ResultConstPtr &)> callback)\n    {\n        return this->getStateMachine()->createSignalConnection(onPreempted_, callback);\n    }\n\n    template <typename T>\n    boost::signals2::connection onRejected(void (T::*callback)(ResultConstPtr &), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onRejected_, callback, object);\n    }\n\n    template <typename T>\n    boost::signals2::connection onRejected(std::function<void(ResultConstPtr &)> callback)\n    {\n        return this->getStateMachine()->createSignalConnection(onRejected_, callback);\n    }\n\n    virtual void cancelGoal() override\n    {\n        if (client_->isServerConnected())\n        {\n            ROS_INFO(\"Cancelling goal of %s\", this->getName().c_str());\n            client_->cancelGoal();\n        }\n        else\n        {\n            ROS_ERROR(\"%s [at %s]: not connected with actionserver, skipping cancel goal ...\", getName().c_str(), getNamespace().c_str());\n        }\n    }\n\n    virtual SimpleClientGoalState getState() override\n    {\n        return client_->getState();\n    }\n\n    void sendGoal(Goal &goal)\n    {\n        ROS_INFO_STREAM(\"[ActionClient<\"<< demangledTypeName<ActionType>() <<\">] Sending goal to actionserver located in \" << this->name_ << \"\\\"\");\n\n        if (client_->isServerConnected())\n        {\n            ROS_INFO_STREAM(getName() << \": Goal Value: \" << std::endl\n                                      << goal);\n            client_->sendGoal(goal, done_cb, active_cb, feedback_cb);\n        }\n        else\n        {\n            ROS_ERROR(\"%s [at %s]: not connected with actionserver, skipping goal request ...\", getName().c_str(), getNamespace().c_str());\n            //client_->waitForServer();\n        }\n    }\n\nprotected:\n    std::shared_ptr<ActionClient> client_;\n\n    void onFeedback(const FeedbackConstPtr &feedback_msg)\n    {\n        postFeedbackEvent(feedback_msg);\n    }\n\n    void onResult(const SimpleClientGoalState &state, const ResultConstPtr &result_msg)\n    {\n        // auto *actionResultEvent = new EvActionResult<TDerived>();\n        // actionResultEvent->client = this;\n        // actionResultEvent->resultMessage = *result_msg;\n\n        const auto &resultType = this->getState();\n        ROS_INFO(\"[%s] request result: %s\", this->getName().c_str(), resultType.toString().c_str());\n\n        if (resultType == actionlib::SimpleClientGoalState::SUCCEEDED)\n        {\n            ROS_INFO(\"[%s] request result: Success\", this->getName().c_str());\n            onSucceeded_(result_msg);\n            postSuccessEvent(result_msg);\n        }\n        else if (resultType == actionlib::SimpleClientGoalState::ABORTED)\n        {\n            ROS_INFO(\"[%s] request result: Aborted\", this->getName().c_str());\n            onAborted_(result_msg);\n            postAbortedEvent(result_msg);\n        }\n        else if (resultType == actionlib::SimpleClientGoalState::REJECTED)\n        {\n            ROS_INFO(\"[%s] request result: Rejected\", this->getName().c_str());\n            onRejected_(result_msg);\n            postRejectedEvent(result_msg);\n        }\n        else if (resultType == actionlib::SimpleClientGoalState::PREEMPTED)\n        {\n            ROS_INFO(\"[%s] request result: Preempted\", this->getName().c_str());\n            onPreempted_(result_msg);\n            postPreemptedEvent(result_msg);\n        }\n        else\n        {\n            ROS_INFO(\"[%s] request result: NOT HANDLED TYPE: %s\", this->getName().c_str(), resultType.toString().c_str());\n        }\n    }\n};\n\n#define SMACC_ACTION_CLIENT_DEFINITION(ActionType) ACTION_DEFINITION(ActionType); typedef smacc::client_bases::SmaccActionClientBase<ActionType> Base;\n} // namespace client_bases\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_publisher_client.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_client.h>\n#include <boost/optional/optional_io.hpp>\n\nnamespace smacc\n{\nnamespace client_bases\n{\nclass SmaccPublisherClient : public smacc::ISmaccClient\n{\npublic:\n  boost::optional<std::string> topicName;\n  boost::optional<int> queueSize;\n\n  SmaccPublisherClient()\n  {\n    initialized_ = false;\n  }\n\n  virtual ~SmaccPublisherClient()\n  {\n    pub_.shutdown();\n  }\n\n  template <typename MessageType>\n  void configure(std::string topicName)\n  {\n    this->topicName = topicName;\n    if (!initialized_)\n    {\n      if (!this->topicName)\n      {\n        ROS_ERROR(\"topic publisher with no topic name set. Skipping advertising.\");\n        return;\n      }\n      if (!queueSize)\n        queueSize = 1;\n\n      ROS_INFO_STREAM(\"[\" << this->getName() << \"] Client Publisher to topic: \" << topicName);\n      pub_ = nh_.advertise<MessageType>(*(this->topicName), *queueSize);\n\n      this->initialized_ = true;\n    }\n  }\n\n  template <typename MessageType>\n  void publish(const MessageType &msg)\n  {\n    pub_.publish(msg);\n  }\n\nprotected:\n  ros::NodeHandle nh_;\n  ros::Publisher pub_;\n\nprivate:\n  bool initialized_;\n};\n} // namespace client_bases\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_service_client.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_client.h>\n#include <boost/optional/optional_io.hpp>\n\nnamespace smacc\n{\nnamespace client_bases\n{\ntemplate <typename ServiceType>\nclass SmaccServiceClient : public smacc::ISmaccClient\n{\npublic:\n    boost::optional<std::string> serviceName_;\n\n    SmaccServiceClient()\n    {\n        initialized_ = false;\n    }\n    SmaccServiceClient(std::string service_name)\n    {\n      serviceName_ = service_name;\n      initialized_ = false;\n    }\n\n    virtual void initialize() override\n    {\n        if (!initialized_)\n        {\n            if (!serviceName_)\n            {\n                ROS_ERROR(\"service client with no service name set. Skipping.\");\n            }\n            else\n            {\n                ROS_INFO_STREAM(\"[\" << this->getName() << \"] Client Service: \" << *serviceName_);\n                this->initialized_ = true;\n\n                client_ = nh_.serviceClient<ServiceType>(*serviceName_);\n            }\n        }\n    }\n\n    bool call(ServiceType &srvreq)\n    {\n        return client_.call(srvreq);\n    }\n\nprotected:\n    ros::NodeHandle nh_;\n    ros::ServiceClient client_;\n    bool initialized_;\n};\n} // namespace client_bases\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_service_server_client.h",
    "content": "#pragma once\n\n#include <smacc/smacc_client.h>\n#include <smacc/smacc_signal.h>\n#include <std_srvs/Empty.h>\n\n#include <boost/optional/optional_io.hpp>\n\nnamespace smacc {\nnamespace client_bases {\ntemplate <typename TService>\nclass SmaccServiceServerClient : public smacc::ISmaccClient {\n  using TServiceRequest = typename TService::Request;\n  using TServiceResponse = typename TService::Response;\n\n public:\n  boost::optional<std::string> serviceName_;\n  SmaccServiceServerClient() { initialized_ = false; }\n  SmaccServiceServerClient(std::string service_name) {\n    serviceName_ = service_name;\n    initialized_ = false;\n  }\n\n  virtual ~SmaccServiceServerClient() { server_.shutdown(); }\n\n  smacc::SmaccSignal<void(TServiceRequest&, std::shared_ptr<TServiceResponse>)>\n      onServiceRequestReceived_;\n\n  template <typename T>\n  boost::signals2::connection onServiceRequestReceived(\n      void (T::*callback)(TServiceRequest&, std::shared_ptr<TServiceResponse>),\n      T* object) {\n    return this->getStateMachine()->createSignalConnection(\n        onServiceRequestReceived_, callback, object);\n  }\n\n  virtual void initialize() override {\n    if (!initialized_) {\n      if (!serviceName_) {\n        ROS_ERROR(\"service server with no service name set. Skipping.\");\n      } else {\n        ROS_INFO_STREAM(\"[\" << this->getName()\n                            << \"] Client Service: \" << serviceName_);\n\n        server_ = nh_.advertiseService(\n            *serviceName_, &SmaccServiceServerClient<TService>::serviceCallback,\n            this);\n        this->initialized_ = true;\n      }\n    }\n  }\n\n protected:\n  ros::NodeHandle nh_;\n\n private:\n  bool serviceCallback(TServiceRequest& req, TServiceResponse& res)\n  {\n    std::shared_ptr<TServiceResponse> response{new TServiceResponse};\n    onServiceRequestReceived_(req, response);\n    res = *response;\n    return true;\n  }\n  ros::ServiceServer server_;\n  bool initialized_;\n};\n}  // namespace client_bases\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_bases/smacc_subscriber_client.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_client.h>\n#include <boost/optional/optional_io.hpp>\n#include <smacc/impl/smacc_state_impl.h>\n\nnamespace smacc\n{\n\nnamespace client_bases\n{\n\nusing namespace smacc::default_events;\n\ntemplate <typename MessageType>\nclass SmaccSubscriberClient : public smacc::ISmaccClient\n{\npublic:\n  boost::optional<std::string> topicName;\n  boost::optional<int> queueSize;\n\n  typedef MessageType TMessageType;\n\n  SmaccSubscriberClient()\n  {\n    initialized_ = false;\n  }\n\n  SmaccSubscriberClient(std::string topicname)\n  {\n    topicName = topicname;\n  }\n\n  virtual ~SmaccSubscriberClient()\n  {\n    sub_.shutdown();\n  }\n\n  smacc::SmaccSignal<void(const MessageType &)> onFirstMessageReceived_;\n  smacc::SmaccSignal<void(const MessageType &)> onMessageReceived_;\n\n  std::function<void(const MessageType &)> postMessageEvent;\n  std::function<void(const MessageType &)> postInitialMessageEvent;\n\n  template <typename T>\n  boost::signals2::connection onMessageReceived(void (T::*callback)(const MessageType &), T *object)\n  {\n    return this->getStateMachine()->createSignalConnection(onMessageReceived_, callback, object);\n  }\n\n  template <typename T>\n  boost::signals2::connection onFirstMessageReceived(void (T::*callback)(const MessageType &), T *object)\n  {\n    return this->getStateMachine()->createSignalConnection(onFirstMessageReceived_, callback, object);\n  }\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    this->postMessageEvent = [=](auto msg) {\n      auto event = new EvTopicMessage<TSourceObject, TOrthogonal>();\n      event->msgData = msg;\n      this->postEvent(event);\n    };\n\n    this->postInitialMessageEvent = [=](auto msg) {\n      auto event = new EvTopicInitialMessage<TSourceObject, TOrthogonal>();\n      event->msgData = msg;\n      this->postEvent(event);\n    };\n  }\n\n  virtual void initialize()\n  {\n    if (!initialized_)\n    {\n      firstMessage_ = true;\n\n      if (!queueSize)\n        queueSize = 1;\n\n      if (!topicName)\n      {\n        ROS_ERROR(\"topic client with no topic name set. Skipping subscribing\");\n      }\n      else\n      {\n        ROS_INFO_STREAM(\"[\" << this->getName() << \"] Subscribing to topic: \" << topicName);\n\n        sub_ = nh_.subscribe(*topicName, *queueSize, &SmaccSubscriberClient<MessageType>::messageCallback, this);\n        this->initialized_ = true;\n      }\n    }\n  }\n\nprotected:\n  ros::NodeHandle nh_;\n\nprivate:\n  ros::Subscriber sub_;\n  bool firstMessage_;\n  bool initialized_;\n\n  void messageCallback(const MessageType &msg)\n  {\n    if (firstMessage_)\n    {\n      postInitialMessageEvent(msg);\n      onFirstMessageReceived_(msg);\n      firstMessage_ = false;\n    }\n\n    onMessageReceived_(msg);\n    postMessageEvent(msg);\n  }\n};\n} // namespace client_bases\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_behavior_bases/cb_service_server_callback_base.h",
    "content": "#pragma once\n#include <smacc/smacc_client_behavior.h>\n\nnamespace smacc {\ntemplate <typename TService>\nclass CbServiceServerCallbackBase : public smacc::SmaccClientBehavior {\n public:\n  virtual void onEntry() override {\n    this->requiresClient(attachedClient_);\n    attachedClient_->onServiceRequestReceived(\n        &CbServiceServerCallbackBase::onServiceRequestReceived, this);\n  }\n\n  virtual void onServiceRequestReceived(typename TService::Request& req,\n                                        std::shared_ptr<typename TService::Response> res) = 0;\n\n protected:\n  smacc::client_bases::SmaccServiceServerClient<TService>* attachedClient_ =\n      nullptr;\n};\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/client_behavior_bases/cb_subscription_callback_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2021\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <smacc/smacc_client_behavior.h>\n\nnamespace smacc\n{\ntemplate <typename TMsg>\nclass CbSubscriptionCallbackBase : public smacc::SmaccClientBehavior\n{\npublic:\n  virtual void onEntry() override\n  {\n    this->requiresClient(attachedClient_);\n    attachedClient_->onMessageReceived(&CbSubscriptionCallbackBase::onMessageReceived, this);\n  }\n\n  virtual void onMessageReceived(const TMsg& msg) = 0;\n\nprotected:\n  smacc::client_bases::SmaccSubscriberClient<TMsg>* attachedClient_ = nullptr;\n};\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/common.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <boost/statechart/state.hpp>\n#include <boost/statechart/simple_state.hpp>\n#include <boost/statechart/event.hpp>\n#include <boost/statechart/asynchronous_state_machine.hpp>\n#include <boost/statechart/custom_reaction.hpp>\n#include <boost/statechart/deep_history.hpp>\n\n#include <boost/config.hpp>\n#include <boost/intrusive_ptr.hpp>\n#include <boost/function.hpp>\n#include <boost/signals2.hpp>\n#include <boost/mpl/list.hpp>\n#include <boost/statechart/deep_history.hpp>\n#include <boost/any.hpp>\n#include <boost/algorithm/string.hpp>\n\n#include <mutex>\n\n#include <ros/ros.h>\n//#include <actionlib/client/simple_action_client.h>\n\n#include <smacc/smacc_fifo_scheduler.h>\n#include <smacc/smacc_types.h>\n#include <smacc/introspection/introspection.h>\n\ntypedef boost::statechart::processor_container<boost::statechart::fifo_scheduler<>, boost::function0<void>, std::allocator<boost::statechart::none>>::processor_context my_context;\nnamespace smacc\n{\n\nnamespace utils\n{\n// demangles the type name to be used as a node handle path\nstd::string cleanShortTypeName(const std::type_info &tinfo);\n} // namespace utils\n\nenum class SMRunMode\n{\n  DEBUG,\n  RELEASE\n};\n\n} // namespace smacc\n\n#include <smacc/smacc_default_events.h>\n#include <smacc/smacc_transition.h>\n"
  },
  {
    "path": "smacc/include/smacc/component.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/common.h>\n#include <boost/optional.hpp>\n\nnamespace smacc\n{\n\nclass ISmaccComponent\n{\npublic:\n    ISmaccComponent();\n\n    virtual ~ISmaccComponent();\n\n    // Returns a custom identifier defined by the specific plugin implementation\n    virtual std::string getName() const;\n\nprotected:\n\n    virtual void initialize(ISmaccClient *owner);\n\n    // Assigns the owner of this resource to the given state machine parameter object\n    void setStateMachine(ISmaccStateMachine *stateMachine);\n\n    template <typename EventType>\n    void postEvent(const EventType &ev);\n\n    template <typename EventType>\n    void postEvent();\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation() {}\n\n    template <typename TComponent>\n    void requiresComponent(TComponent *& requiredComponentStorage);\n\n    template <typename TClient>\n    void requiresClient(TClient *& requiredClientStorage);\n\n    virtual void onInitialize();\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *createSiblingComponent(TArgs... targs);\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *createSiblingNamedComponent(std::string name, TArgs... targs);\n\n    // A reference to the state machine object that owns this resource\n    ISmaccStateMachine *stateMachine_;\n\n    ISmaccClient *owner_;\n\n    friend class ISmaccOrthogonal;\n    friend class ISmaccClient;\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_asynchronous_client_behavior_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void SmaccAsyncClientBehavior::onOrthogonalAllocation()\n    {\n        postFinishEventFn_ = [=] {\n            this->onFinished_();\n            this->postEvent<EvCbFinished<TSourceObject, TOrthogonal>>();\n        };\n\n        postSuccessEventFn_ = [=] {\n            this->onSuccess_();\n            this->postEvent<EvCbSuccess<TSourceObject, TOrthogonal>>();\n        };\n\n        postFailureEventFn_ = [=] {\n            this->onFailure_();\n            this->postEvent<EvCbFailure<TSourceObject, TOrthogonal>>();\n        };\n    }\n\n    template <typename TCallback, typename T>\n    boost::signals2::connection SmaccAsyncClientBehavior::onSuccess(TCallback callback, T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onSuccess_, callback, object);\n    }\n\n    template <typename TCallback, typename T>\n    boost::signals2::connection SmaccAsyncClientBehavior::onFinished(TCallback callback, T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onFinished_, callback, object);\n    }\n\n    template <typename TCallback, typename T>\n    boost::signals2::connection SmaccAsyncClientBehavior::onFailure(TCallback callback, T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onFailure_, callback, object);\n    }\n}\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_client_behavior_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/smacc_client_behavior.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\n\ntemplate <typename EventType>\nvoid ISmaccClientBehavior::postEvent(const EventType &ev)\n{\n    if (stateMachine_ == nullptr)\n    {\n        ROS_ERROR(\"The client behavior cannot post events before being assigned to an orthogonal. Ignoring post event call.\");\n    }\n    else\n    {\n        stateMachine_->postEvent(ev, EventLifeTime::CURRENT_STATE);\n    }\n}\n\ntemplate <typename EventType>\nvoid ISmaccClientBehavior::postEvent()\n{\n    if (stateMachine_ == nullptr)\n    {\n        ROS_ERROR(\"The client behavior cannot post events before being assigned to an orthogonal. Ignoring post event call.\");\n    }\n    else\n    {\n\n        stateMachine_->template postEvent<EventType>(EventLifeTime::CURRENT_STATE);\n    }\n}\n\n//inline\nISmaccStateMachine *ISmaccClientBehavior::getStateMachine()\n{\n    return this->stateMachine_;\n}\n\n//inline\nISmaccState *ISmaccClientBehavior::getCurrentState()\n{\n    return this->currentState;\n}\n\ntemplate <typename SmaccClientType>\nvoid ISmaccClientBehavior::requiresClient(SmaccClientType *&storage)\n{\n    currentOrthogonal->requiresClient(storage);\n}\n\ntemplate <typename SmaccComponentType>\nvoid ISmaccClientBehavior::requiresComponent(SmaccComponentType *&storage)\n{\n    if (stateMachine_ == nullptr)\n    {\n        ROS_ERROR(\"Cannot use the requiresComponent funcionality before assigning the client behavior to an orthogonal. Try using the OnEntry method to capture required components.\");\n    }\n    else\n    {\n        stateMachine_->requiresComponent(storage);\n    }\n}\n\ntemplate <typename TOrthogonal, typename TSourceObject>\nvoid ISmaccClientBehavior::onOrthogonalAllocation() {}\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_client_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_client.h>\n#include <smacc/impl/smacc_state_machine_impl.h>\n\nnamespace smacc\n{\n    template <typename EventType>\n    void ISmaccClient::postEvent(const EventType &ev)\n    {\n        stateMachine_->postEvent(ev);\n    }\n\n    template <typename EventType>\n    void ISmaccClient::postEvent()\n    {\n        stateMachine_->postEvent<EventType>();\n    }\n\n    template <typename TComponent>\n    TComponent *ISmaccClient::getComponent()\n    {\n        return this->getComponent<TComponent>(std::string());\n    }\n\n    template <typename TComponent>\n    TComponent *ISmaccClient::getComponent(std::string name)\n    {\n        for (auto &component : components_)\n        {\n            if (component.first.name != name)\n                continue;\n\n            auto *tcomponent = dynamic_cast<TComponent *>(component.second.get());\n            if (tcomponent != nullptr)\n            {\n                return tcomponent;\n            }\n        }\n\n        return nullptr;\n    }\n\n    //inline\n    ISmaccStateMachine *ISmaccClient::getStateMachine()\n    {\n        return this->stateMachine_;\n    }\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *ISmaccClient::createNamedComponent(std::string name, TArgs... targs)\n    {\n        ComponentKey componentkey(&typeid(SmaccComponentType), name);\n\n        std::shared_ptr<SmaccComponentType> ret;\n\n        auto it = this->components_.find(componentkey);\n\n        if (it == this->components_.end())\n        {\n            auto tname = demangledTypeName<SmaccComponentType>();\n            ROS_DEBUG(\"%s smacc component is required. Creating a new instance.\", tname.c_str());\n\n            ret = std::shared_ptr<SmaccComponentType>(new SmaccComponentType(targs...));\n            ret->setStateMachine(this->getStateMachine());\n            ret->owner_ = this;\n            ret->initialize(this);\n\n            this->components_[componentkey] = ret; //std::dynamic_pointer_cast<smacc::ISmaccComponent>(ret);\n            ROS_DEBUG(\"%s resource is required. Done.\", tname.c_str());\n        }\n        else\n        {\n            ROS_DEBUG(\"%s resource is required. Found resource in cache.\", demangledTypeName<SmaccComponentType>().c_str());\n            ret = dynamic_pointer_cast<SmaccComponentType>(it->second);\n        }\n\n        ret->template onOrthogonalAllocation<TOrthogonal, TClient>();\n\n        return ret.get();\n    }\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *ISmaccClient::createComponent(TArgs... targs)\n    {\n        return this->createNamedComponent<SmaccComponentType, TOrthogonal, TClient>(std::string(), targs...);\n    }\n\n    template <typename TSmaccSignal, typename T>\n    void ISmaccClient::connectSignal(TSmaccSignal &signal, void (T::*callback)(), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(signal, callback, object);\n    }\n\n    template <typename SmaccClientType>\n    void ISmaccClient::requiresClient(SmaccClientType *&storage)\n    {\n        this->orthogonal_->requiresClient(storage);\n    }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_component_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/component.h>\n#include <smacc/impl/smacc_state_machine_impl.h>\n\nnamespace smacc\n{\n    template <typename EventType>\n    void ISmaccComponent::postEvent(const EventType &ev)\n    {\n        stateMachine_->postEvent(ev);\n    }\n\n    template <typename TComponent>\n    void ISmaccComponent::requiresComponent(TComponent *&requiredComponentStorage)\n    {\n        requiredComponentStorage = this->owner_->getComponent<TComponent>();\n    }\n\n    template <typename TClient>\n    void ISmaccComponent::requiresClient(TClient *&requiredClientStorage)\n    {\n        this->owner_->requiresClient(requiredClientStorage);\n    }\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *ISmaccComponent::createSiblingComponent(TArgs... targs)\n    {\n        return this->owner_->createComponent<SmaccComponentType, TOrthogonal, TClient>(targs...);\n    }\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *ISmaccComponent::createSiblingNamedComponent(std::string name, TArgs... targs)\n    {\n        return this->owner_->createNamedComponent<SmaccComponentType, TOrthogonal, TClient>(name, targs...);\n    }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_event_generator_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_event_generator.h>\n#include <smacc/introspection/introspection.h>\n\nnamespace smacc\n{\n    template <typename EventType>\n    void SmaccEventGenerator::postEvent(const EventType &ev)\n    {\n        ownerState_->postEvent(ev);\n    }\n\n    template <typename EventType>\n    void SmaccEventGenerator::postEvent()\n    {\n        ownerState_->postEvent<EventType>();\n    }\n\n    template <typename TState, typename TSource>\n    void SmaccEventGenerator::onStateAllocation()\n    {\n    }\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_orthogonal_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <smacc/smacc_client.h>\n#include <cassert>\n\nnamespace smacc\n{\n\ntemplate <typename SmaccClientType>\nbool ISmaccOrthogonal::requiresClient(SmaccClientType *&storage)\n{\n    for (auto &client : clients_)\n    {\n        storage = dynamic_cast<SmaccClientType *>(client.get());\n        if (storage != nullptr)\n            return true;\n    }\n\n    auto requiredClientName = demangledTypeName<SmaccClientType>();\n    ROS_WARN_STREAM(\"Required client [\"<< requiredClientName<< \"] not found in current orthogonal. Searching in other orthogonals.\");\n\n    for (auto &orthoentry : this->getStateMachine()->getOrthogonals())\n    {\n        for (auto &client : orthoentry.second->getClients())\n        {\n            storage = dynamic_cast<SmaccClientType *>(client.get());\n            if (storage != nullptr)\n            {\n                ROS_WARN_STREAM(\"Required client  [\"<< requiredClientName<<\"] found in other orthogonal.\");\n                return true;\n            }\n        }\n    }\n\n    ROS_ERROR_STREAM(\"Required client [\"<< requiredClientName<< \"] not found even in other orthogonals. Returning null pointer. If the requested client is used may result in a segmentation fault.\");\n    return false;\n}\n\ntemplate <typename SmaccComponentType>\nvoid ISmaccOrthogonal::requiresComponent(SmaccComponentType *&storage)\n{\n    if (stateMachine_ == nullptr)\n    {\n        ROS_ERROR(\"Cannot use the requiresComponent funcionality from an orthogonal before onInitialize\");\n    }\n    else\n    {\n        stateMachine_->requiresComponent(storage);\n    }\n}\n\ntemplate <typename TOrthogonal, typename TClient>\nvoid ISmaccOrthogonal::assignClientToOrthogonal(TClient* client)\n{\n    client->setStateMachine(getStateMachine());\n    client->setOrthogonal(this);\n\n    client->template onOrthogonalAllocation<TOrthogonal, TClient>();\n}\n\ntemplate <typename TClientBehavior>\nTClientBehavior *ISmaccOrthogonal::getClientBehavior()\n{\n    for (auto &cb : this->clientBehaviors_.back())\n    {\n        auto *ret = dynamic_cast<TClientBehavior *>(cb.get());\n        if (ret != nullptr)\n        {\n            return ret;\n        }\n    }\n\n    return nullptr;\n}\n\ninline const std::vector<std::shared_ptr<smacc::ISmaccClient>> &ISmaccOrthogonal::getClients()\n{\n    return clients_;\n}\n\ninline const std::vector<std::vector<std::shared_ptr<smacc::ISmaccClientBehavior>>> &ISmaccOrthogonal::getClientBehaviors() const\n{\n    return this->clientBehaviors_;\n}\n\ntemplate <typename T>\nvoid ISmaccOrthogonal::setGlobalSMData(std::string name, T value)\n{\n    this->getStateMachine()->setGlobalSMData(name, value);\n}\n\ntemplate <typename T>\nbool ISmaccOrthogonal::getGlobalSMData(std::string name, T &ret)\n{\n    return this->getStateMachine()->getGlobalSMData(name, ret);\n}\n\n//inline\nISmaccStateMachine *ISmaccOrthogonal::getStateMachine() { return this->stateMachine_; }\n\ntemplate <typename TOrthogonal, typename TClient>\nclass ClientHandler : public TClient\n{\npublic:\n    template <typename... TArgs>\n    ClientHandler(TArgs... args)\n        : TClient(args...)\n    {\n    }\n\n    ClientHandler()\n        : TClient()\n    {\n    }\n\n    template <typename SmaccComponentType, typename... TArgs>\n    SmaccComponentType *createComponent(TArgs... targs)\n    {\n        return ISmaccClient::createComponent<SmaccComponentType, TOrthogonal, TClient, TArgs...>(targs...);\n    }\n\n    template <typename SmaccComponentType, typename... TArgs>\n    SmaccComponentType *createNamedComponent(std::string name, TArgs... targs)\n    {\n        return ISmaccClient::createNamedComponent<SmaccComponentType, TOrthogonal, TClient, TArgs...>(name, targs...);\n    }\n\n    virtual smacc::introspection::TypeInfo::Ptr getType() override\n    {\n        return smacc::introspection::TypeInfo::getTypeInfoFromType<TClient>();\n    }\n};\n\ntemplate <typename TOrthogonal>\nclass Orthogonal : public ISmaccOrthogonal\n{\npublic:\n    template <typename TClient, typename... TArgs>\n    std::shared_ptr<ClientHandler<TOrthogonal, TClient>> createClient(TArgs... args)\n    {\n        //static_assert(std::is_base_of<ISmaccOrthogonal, TOrthogonal>::value, \"The object Tag must be the orthogonal type where the client was created\");\n        // if (typeid(*this) != typeid(TOrthogonal))\n        // {\n        //     ROS_ERROR_STREAM(\"Error creating client. The object Tag must be the type of the orthogonal where the client was created:\" << demangleType(typeid(*this)) << \". The object creation was skipped and a nullptr was returned\");\n        //     return nullptr;\n        // }\n\n        ROS_INFO(\"[%s] creates a client of type '%s' and object tag '%s'\",\n                    demangleType(typeid(*this)).c_str(),\n                    demangledTypeName<TClient>().c_str(),\n                    demangledTypeName<TOrthogonal>().c_str()\n                );\n\n        auto client = std::make_shared<ClientHandler<TOrthogonal, TClient>>(args...);\n        this->template assignClientToOrthogonal<TOrthogonal, TClient>(client.get());\n\n        // it is stored the client (not the client handler)\n        clients_.push_back(client);\n\n        return client;\n    }\n};\n}; // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_state_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_state.h>\n#include <smacc/smacc_orthogonal.h>\n#include <smacc/smacc_client_behavior.h>\n#include <smacc/introspection/introspection.h>\n#include <smacc/smacc_state_reactor.h>\n//#include <smacc/smacc_event_generator.h>\n#include <smacc/introspection/string_type_walker.h>\n#include <smacc/smacc_client_behavior.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\n    using namespace smacc::introspection;\n    //-------------------------------------------------------------------------------------------------------\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool ISmaccState::getParam(std::string param_name, T &param_storage)\n    {\n        return nh.getParam(param_name, param_storage);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    void ISmaccState::setParam(std::string param_name, T param_val)\n    {\n        return nh.setParam(param_name, param_val);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    //Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool ISmaccState::param(std::string param_name, T &param_val, const T &default_val) const\n    {\n        return nh.param(param_name, param_val, default_val);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n#define THIS_STATE_NAME ((demangleSymbol(typeid(*this).name()).c_str()))\n    template <typename TOrthogonal, typename TBehavior, typename... Args>\n    std::shared_ptr<TBehavior> ISmaccState::configure(Args &&... args)\n    {\n        std::string orthogonalkey = demangledTypeName<TOrthogonal>();\n        ROS_INFO(\"[%s] Configuring orthogonal: %s\", THIS_STATE_NAME, orthogonalkey.c_str());\n\n        TOrthogonal *orthogonal = this->getOrthogonal<TOrthogonal>();\n        if (orthogonal != nullptr)\n        {\n            auto clientBehavior = std::shared_ptr<TBehavior>(new TBehavior(args...));\n            clientBehavior->currentState = this;\n            orthogonal->addClientBehavior(clientBehavior);\n            clientBehavior->template onOrthogonalAllocation<TOrthogonal, TBehavior>();\n            return clientBehavior;\n        }\n        else\n        {\n            ROS_ERROR(\"[%s] Skipping client behavior creation in orthogonal [%s]. It does not exist.\", THIS_STATE_NAME, orthogonalkey.c_str());\n            return nullptr;\n        }\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename SmaccComponentType>\n    void ISmaccState::requiresComponent(SmaccComponentType *&storage)\n    {\n        this->getStateMachine().requiresComponent(storage);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename SmaccClientType>\n    void ISmaccState::requiresClient(SmaccClientType *&storage)\n    {\n        const char *sname = (demangleSymbol(typeid(*this).name()).c_str());\n        storage = nullptr;\n        auto &orthogonals = this->getStateMachine().getOrthogonals();\n        for (auto &ortho : orthogonals)\n        {\n            ortho.second->requiresClient(storage);\n            if (storage != nullptr)\n                return;\n        }\n\n        ROS_ERROR(\"[%s] Client of type '%s' not found in any orthogonal of the current state machine. This may produce a segmentation fault if the returned reference is used.\", sname, demangleSymbol<SmaccClientType>().c_str());\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename T>\n    bool ISmaccState::getGlobalSMData(std::string name, T &ret)\n    {\n        return this->getStateMachine().getGlobalSMData(name, ret);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    // Store globally in this state machine. (By value parameter )\n    template <typename T>\n    void ISmaccState::setGlobalSMData(std::string name, T value)\n    {\n        this->getStateMachine().setGlobalSMData(name, value);\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename TStateReactor, typename... TEvArgs>\n    std::shared_ptr<TStateReactor> ISmaccState::createStateReactor(TEvArgs... args)\n    {\n        auto sr = std::make_shared<TStateReactor>(args...);\n        //sb->initialize(this, mock);\n        //sb->setOutputEvent(typelist<TTriggerEvent>());\n        stateReactors_.push_back(sr);\n        return sr;\n    }\n\n    template <typename TEventGenerator, typename... TEvArgs>\n    std::shared_ptr<TEventGenerator> ISmaccState::createEventGenerator(TEvArgs... args)\n    {\n        auto eg = std::make_shared<TEventGenerator>(args...);\n        eventGenerators_.push_back(eg);\n        return eg;\n    }\n\n    template <typename TEventList>\n    struct AddTEventType\n    {\n        smacc::StateReactor *sr_;\n        AddTEventType(smacc::StateReactor *sr) : sr_(sr)\n        {\n        }\n\n        template <typename T>\n        void operator()(T)\n        {\n            sr_->addInputEvent<T>();\n        }\n    };\n\n    template <typename TStateReactor, typename TTriggerEvent, typename TEventList, typename... TEvArgs>\n    std::shared_ptr<TStateReactor> ISmaccState::createStateReactor(TEvArgs... args)\n    {\n        auto sr = std::make_shared<TStateReactor>(args...);\n        TEventList *mock;\n        sr->initialize(this);\n        sr->template setOutputEvent<TTriggerEvent>();\n\n        using boost::mpl::_1;\n        using wrappedList = typename boost::mpl::transform<TEventList, _1>::type;\n        AddTEventType<TEventList> op(sr.get());\n        boost::mpl::for_each<wrappedList>(op);\n\n        stateReactors_.push_back(sr);\n        return sr;\n    }\n\n\n    template <typename TOrthogonal>\n    TOrthogonal *ISmaccState::getOrthogonal()\n    {\n        //static_assert(boost::type_traits::is_base_of<ISmaccOrthogonal,TOrthogonal>::value);\n        return this->getStateMachine().getOrthogonal<TOrthogonal>();\n    }\n\n    template <typename TEventGenerator>\n    TEventGenerator* ISmaccState::getEventGenerator()\n    {\n        TEventGenerator* ret = nullptr;\n        for(auto& evg: this->eventGenerators_)\n        {\n            ret = dynamic_cast<TEventGenerator *>(evg.get());\n            if(ret!=nullptr)\n                break;\n        }\n        return ret;\n    }\n\n    template <typename TStateReactor>\n    TStateReactor* ISmaccState::getStateReactor()\n    {\n        TStateReactor* ret = nullptr;\n        for(auto& sr: this->stateReactors_)\n        {\n            ret = dynamic_cast<TStateReactor *>(sr.get());\n            if(ret!=nullptr)\n                break;\n        }\n        return ret;\n    }\n\n    // template <typename TStateReactor, typename TTriggerEvent, typename... TEvArgs>\n    // std::shared_ptr<TStateReactor> ISmaccState::createStateReactor(TEvArgs... args)\n    // {\n    //     auto sb = std::make_shared<TStateReactor>(std::forward(args...));\n    //     sb->initialize(this, typelist<TEvArgs...>());\n    //     sb->setOutputEvent(typelist<TTriggerEvent>());\n    //     stateReactors_.push_back(sb);\n\n    //     return sb;\n    // }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename EventType>\n    void ISmaccState::postEvent(const EventType &ev)\n    {\n        getStateMachine().postEvent(ev);\n    }\n\n    template <typename EventType>\n    void ISmaccState::postEvent()\n    {\n        getStateMachine().postEvent<EventType>();\n    }\n    //-------------------------------------------------------------------------------------------------------\n\n    template <typename TransitionType>\n    void ISmaccState::notifyTransition()\n    {\n        auto transitionType = TypeInfo::getTypeInfoFromType<TransitionType>();\n        this->notifyTransitionFromTransitionTypeInfo(transitionType);\n    }\n\n    //-------------------------------------------------------------------------------------------------------------------\n\n} // namespace smacc\n\n// implementation depends on state definition\n#include <smacc/impl/smacc_state_reactor_impl.h>\n#include <smacc/impl/smacc_event_generator_impl.h>\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_state_machine_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_state_machine.h>\n\n#include <smacc/smacc_client.h>\n#include <smacc/smacc_orthogonal.h>\n#include <smacc/smacc_state.h>\n\n#include <smacc/introspection/introspection.h>\n#include <smacc/smacc_signal_detector.h>\n#include <smacc/smacc_state_reactor.h>\n#include <smacc_msgs/SmaccStatus.h>\n#include <sstream>\n\n#include <boost/function_types/function_arity.hpp>\n#include <boost/function_types/function_type.hpp>\n#include <boost/function_types/parameter_types.hpp>\n\nnamespace smacc\n{\n  using namespace smacc::introspection;\n\n  template <typename TOrthogonal>\n  TOrthogonal *ISmaccStateMachine::getOrthogonal()\n  {\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    std::string orthogonalkey = demangledTypeName<TOrthogonal>();\n    TOrthogonal *ret;\n\n    auto it = orthogonals_.find(orthogonalkey);\n\n    if (it != orthogonals_.end())\n    {\n      ROS_DEBUG(\"Orthogonal %s resource is being required from some state, client or component. Found resource in cache.\", orthogonalkey.c_str());\n      ret = dynamic_cast<TOrthogonal *>(it->second.get());\n      return ret;\n    }\n    else\n    {\n      std::stringstream ss;\n      ss << \"Orthogonal not found \" << orthogonalkey.c_str() << std::endl;\n      ss << \"The existing orthogonals are the following: \" << std::endl;\n      for (auto &orthogonal : orthogonals_)\n      {\n        ss << \" - \" << orthogonal.first << std::endl;\n      }\n\n      ROS_WARN_STREAM(ss.str());\n\n      return nullptr;\n    }\n  }\n\n  //-------------------------------------------------------------------------------------------------------\n  template <typename TOrthogonal>\n  void ISmaccStateMachine::createOrthogonal()\n  {\n    this->lockStateMachine(\"create orthogonal\");\n    std::string orthogonalkey = demangledTypeName<TOrthogonal>();\n\n    if (orthogonals_.count(orthogonalkey) == 0)\n    {\n      auto ret = std::make_shared<TOrthogonal>();\n      orthogonals_[orthogonalkey] = dynamic_pointer_cast<smacc::ISmaccOrthogonal>(ret);\n\n      ret->setStateMachine(this);\n\n      ROS_INFO(\"%s Orthogonal is created\", orthogonalkey.c_str());\n    }\n    else\n    {\n      ROS_WARN_STREAM(\"There were already one existing orthogonal of type \"\n                      << orthogonalkey.c_str() << \". Skipping creation orthogonal request. \");\n      std::stringstream ss;\n      ss << \"The existing orthogonals are the following: \" << std::endl;\n      for (auto &orthogonal : orthogonals_)\n      {\n        ss << \" - \" << orthogonal.first << std::endl;\n      }\n      ROS_WARN_STREAM(ss.str());\n    }\n    this->unlockStateMachine(\"create orthogonal\");\n  }\n\n  //-------------------------------------------------------------------------------------------------------\n  template <typename SmaccComponentType>\n  void ISmaccStateMachine::requiresComponent(SmaccComponentType *&storage)\n  {\n    ROS_DEBUG(\"component %s is required\", demangleSymbol(typeid(SmaccComponentType).name()).c_str());\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    for (auto ortho : this->orthogonals_)\n    {\n      for (auto &client : ortho.second->clients_)\n      {\n\n        storage = client->getComponent<SmaccComponentType>();\n        if (storage != nullptr)\n        {\n          return;\n        }\n      }\n    }\n\n    ROS_WARN(\"component %s is required but it was not found in any orthogonal\", demangleSymbol(typeid(SmaccComponentType).name()).c_str());\n\n    // std::string componentkey = demangledTypeName<SmaccComponentType>();\n    // SmaccComponentType *ret;\n\n    // auto it = components_.find(componentkey);\n\n    // if (it == components_.end())\n    // {\n    //     ROS_DEBUG(\"%s smacc component is required. Creating a new instance.\", componentkey.c_str());\n\n    //     ret = new SmaccComponentType();\n    //     ret->setStateMachine(this);\n    //     components_[componentkey] = static_cast<smacc::ISmaccComponent *>(ret);\n    //     ROS_DEBUG(\"%s resource is required. Done.\", componentkey.c_str());\n    // }\n    // else\n    // {\n    //     ROS_DEBUG(\"%s resource is required. Found resource in cache.\", componentkey.c_str());\n    //     ret = dynamic_cast<SmaccComponentType *>(it->second);\n    // }\n\n    // storage = ret;\n  }\n  //-------------------------------------------------------------------------------------------------------\n  template <typename EventType>\n  void ISmaccStateMachine::postEvent(EventType *ev, EventLifeTime evlifetime)\n  {\n    std::lock_guard<std::recursive_mutex> guard(eventQueueMutex_);\n    if (evlifetime == EventLifeTime::CURRENT_STATE && (stateMachineCurrentAction == StateMachineInternalAction::STATE_EXITING ||\n                                                       stateMachineCurrentAction == StateMachineInternalAction::TRANSITIONING))\n    {\n      ROS_WARN_STREAM(\"CURRENT STATE SCOPED EVENT SKIPPED, state is exiting/transitioning \" << demangleSymbol<EventType>());\n      return;\n      // in this case we may lose/skip events, if this is not right for some cases we should create a queue\n      // to lock the events during the transitions. This issues appeared when a client asyncbehavior was posting an event\n      // meanwhile we were doing the transition, but the main thread was waiting for its correct finalization (with thread.join)\n    }\n\n    // when a postting event is requested by any component, client, or client behavior\n    // we reach this place. Now, we propagate the events to all the state state reactors to generate\n    // some more events\n\n    ROS_DEBUG_STREAM(\"[PostEvent entry point] \" << demangleSymbol<EventType>());\n\n    for (auto currentState : currentState_)\n    {\n      propagateEventToStateReactors(currentState, ev);\n    }\n\n    this->signalDetector_->postEvent(ev);\n  }\n\n  template <typename EventType>\n  void ISmaccStateMachine::postEvent(EventLifeTime evlifetime)\n  {\n    auto *ev = new EventType();\n    this->postEvent(ev, evlifetime);\n  }\n\n  template <typename T>\n  bool ISmaccStateMachine::getGlobalSMData(std::string name, T &ret)\n  {\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n    // ROS_WARN(\"get SM Data lock acquire\");\n    bool success = false;\n\n    if (!globalData_.count(name))\n    {\n      // ROS_WARN(\"get SM Data - data do not exist\");\n      success = false;\n    }\n    else\n    {\n      // ROS_WARN(\"get SM DAta -data exist. accessing\");\n      try\n      {\n        auto &v = globalData_[name];\n\n        // ROS_WARN(\"get SM DAta -data exist. any cast\");\n        ret = boost::any_cast<T>(v.second);\n        success = true;\n        // ROS_WARN(\"get SM DAta -data exist. success\");\n      }\n      catch (boost::bad_any_cast &ex)\n      {\n        ROS_ERROR(\"bad any cast: %s\", ex.what());\n        success = false;\n      }\n    }\n\n    // ROS_WARN(\"get SM Data lock release\");\n    return success;\n  }\n\n  template <typename T>\n  void ISmaccStateMachine::setGlobalSMData(std::string name, T value)\n  {\n    {\n      std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n      // ROS_WARN(\"set SM Data lock acquire\");\n\n      globalData_[name] = {[this, name]() {\n                             std::stringstream ss;\n                             auto val = any_cast<T>(globalData_[name].second);\n                             ss << val;\n                             return ss.str();\n                           },\n                           value};\n    }\n\n    this->updateStatusMessage();\n  }\n\n  template <typename StateField, typename BehaviorType>\n  void ISmaccStateMachine::mapBehavior()\n  {\n    std::string stateFieldName = demangleSymbol(typeid(StateField).name());\n    std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());\n    ROS_INFO(\"Mapping state field '%s' to stateReactor '%s'\", stateFieldName.c_str(), behaviorType.c_str());\n    SmaccClientBehavior *globalreference;\n    if (!this->getGlobalSMData(stateFieldName, globalreference))\n    {\n      // Using the requires component approach, we force a unique existence\n      // of this component\n      BehaviorType *behavior;\n      this->requiresComponent(behavior);\n      globalreference = dynamic_cast<ISmaccClientBehavior *>(behavior);\n\n      this->setGlobalSMData(stateFieldName, globalreference);\n    }\n  }\n\n  namespace utils\n  {\n    template <int arity>\n    struct Bind\n    {\n      template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n      boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback,\n                                          TSmaccObjectType *object, std::shared_ptr<CallbackCounterSemaphore> callbackCounter);\n    };\n\n    template <>\n    struct Bind<1>\n    {\n      template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n      boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr<CallbackCounterSemaphore> callbackCounter)\n      {\n        return signal.connect(\n\n        [=]()\n        {\n          if(callbackCounter == nullptr)\n          {\n           (object->*callback)();\n          }\n          else if (callbackCounter->acquire())\n          {\n            (object->*callback)();\n            callbackCounter->release();\n        }});\n      }\n    };\n\n    template <>\n    struct Bind<2>\n    {\n      template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n      boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr<CallbackCounterSemaphore> callbackCounter)\n      {\n        return signal.connect([=](auto a1)\n        {\n            if(callbackCounter == nullptr)\n          {\n            (object->*callback)(a1);\n          }\n          else if (callbackCounter->acquire())\n          {\n            (object->*callback)(a1);\n            callbackCounter->release();\n\n          }\n            });\n      }\n    };\n\n    template <>\n    struct Bind<3>\n    {\n      template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n      boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr<CallbackCounterSemaphore> callbackCounter)\n      {\n        return signal.connect([=](auto a1, auto a2) {\n           if(callbackCounter == nullptr)\n          {\n            (object->*callback)(a1,a2);\n          }\n          else if (callbackCounter->acquire())\n          {\n            (object->*callback)(a1,a2);\n            callbackCounter->release();\n\n          }\n          });\n      }\n    };\n\n    template <>\n    struct Bind<4>\n    {\n      template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n      boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr<CallbackCounterSemaphore> callbackCounter)\n      {\n        return signal.connect([=](auto a1, auto a2, auto a3) {\n           if(callbackCounter == nullptr)\n          {\n            (object->*callback)(a1,a2,a3);\n          }\n          else if (callbackCounter->acquire())\n          {\n            (object->*callback)(a1,a2,a3);\n            callbackCounter->release();\n\n          }\n          });\n\n      }\n    };\n  } // namespace utils\n  using namespace smacc::utils;\n\n  template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n  boost::signals2::connection ISmaccStateMachine::createSignalConnection(TSmaccSignal &signal,\n                                                                         TMemberFunctionPrototype callback,\n                                                                         TSmaccObjectType *object)\n  {\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    static_assert(std::is_base_of<ISmaccState, TSmaccObjectType>::value ||\n                      std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||\n                      std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||\n                      std::is_base_of<StateReactor, TSmaccObjectType>::value ||\n                      std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,\n                  \"Only are accepted smacc types as subscribers for smacc signals\");\n\n    typedef decltype(callback) ft;\n    Bind<boost::function_types::function_arity<ft>::value> binder;\n\n    boost::signals2::connection connection;\n\n    // long life-time objects\n    if (std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||\n        std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||\n        std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||\n        std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)\n    {\n      connection = binder.bindaux(signal, callback, object, nullptr);\n    }\n    else if (std::is_base_of<ISmaccState, TSmaccObjectType>::value ||\n             std::is_base_of<StateReactor, TSmaccObjectType>::value ||\n             std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)\n    {\n      ROS_INFO(\"[StateMachine] life-time constrained smacc signal subscription created. Subscriber is %s\",\n               demangledTypeName<TSmaccObjectType>().c_str());\n\n      std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;\n      if(stateCallbackConnections.count(object))\n      {\n        callbackCounterSemaphore = stateCallbackConnections[object];\n      }\n      else\n      {\n          callbackCounterSemaphore =  std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());\n          stateCallbackConnections[object] = callbackCounterSemaphore;\n      }\n\n      connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);\n      callbackCounterSemaphore->addConnection(connection);\n\n    }\n    else // state life-time objects\n    {\n      ROS_WARN(\"[StateMachine] connecting signal to an unknown object with life-time unknown behavior. It might provoke \"\n               \"an exception if the object is destroyed during the execution.\");\n\n      connection = binder.bindaux(signal, callback, object, nullptr);\n    }\n\n    return connection;\n  }\n\n  template <typename T>\n  bool ISmaccStateMachine::getParam(std::string param_name, T &param_storage)\n  {\n    return nh_.getParam(param_name, param_storage);\n  }\n\n  // Delegates to ROS param access with the current NodeHandle\n  template <typename T>\n  void ISmaccStateMachine::setParam(std::string param_name, T param_val)\n  {\n    return nh_.setParam(param_name, param_val);\n  }\n\n  // Delegates to ROS param access with the current NodeHandle\n  template <typename T>\n  bool ISmaccStateMachine::param(std::string param_name, T &param_val, const T &default_val) const\n  {\n    return nh_.param(param_name, param_val, default_val);\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnStateEntryStart(StateType *state)\n  {\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    ROS_DEBUG(\"[State Machne] Initializating a new state '%s' and updating current state. Getting state meta-information. number of orthogonals: %ld\", demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());\n\n    stateSeqCounter_++;\n    currentState_.push_back(state);\n    currentStateInfo_ = stateMachineInfo_->getState<StateType>();\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnStateEntryEnd(StateType *state)\n  {\n    ROS_INFO(\"[%s] State OnEntry code finished\", demangleSymbol(typeid(StateType).name()).c_str());\n\n    auto currentState = this->currentState_.back();\n    for (auto pair : this->orthogonals_)\n    {\n      //ROS_INFO(\"ortho onentry: %s\", pair.second->getName().c_str());\n      auto &orthogonal = pair.second;\n      try\n      {\n        orthogonal->onEntry();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s\",\n                  pair.second->getName().c_str(), e.what());\n      }\n    }\n\n    for (auto &sr : currentState->getStateReactors())\n    {\n      auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();\n      ROS_INFO(\"state reactor onEntry: %s\", srname);\n      try\n      {\n        sr->onEntry();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception info: %s\",\n                  srname, e.what());\n      }\n    }\n\n    for (auto &eg : currentState->getEventGenerators())\n    {\n      auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();\n      ROS_INFO(\"state reactor onEntry: %s\", egname);\n      try\n      {\n        eg->onEntry();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[Event generator %s] Exception on Entry - continuing with next state reactor. Exception info: %s\",\n                  egname, e.what());\n      }\n    }\n\n    {\n      std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n      this->updateStatusMessage();\n      stateMachineCurrentAction = StateMachineInternalAction::STATE_STEADY;\n    }\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnRuntimeConfigurationFinished(StateType *state)\n  {\n    for (auto pair : this->orthogonals_)\n    {\n      //ROS_INFO(\"ortho onruntime configure: %s\", pair.second->getName().c_str());\n      auto &orthogonal = pair.second;\n      orthogonal->runtimeConfigure();\n    }\n\n    {\n      std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n      this->updateStatusMessage();\n      this->signalDetector_->notifyStateConfigured(this->currentState_.back());\n\n      stateMachineCurrentAction = StateMachineInternalAction::STATE_ENTERING;\n    }\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnRuntimeConfigured(StateType *state)\n  {\n    stateMachineCurrentAction = StateMachineInternalAction::STATE_CONFIGURING;\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnStateExitting(StateType *state)\n  {\n    stateMachineCurrentAction = StateMachineInternalAction::STATE_EXITING;\n\n    auto fullname = demangleSymbol(typeid(StateType).name());\n    ROS_WARN_STREAM(\"exiting state: \" << fullname);\n    //this->setParam(\"destroyed\", true);\n\n    ROS_INFO_STREAM(\"Notification State Exit: leaving state\" << state);\n    for (auto pair : this->orthogonals_)\n    {\n      auto &orthogonal = pair.second;\n      try\n      {\n        orthogonal->onExit();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s\",\n                  pair.second->getName().c_str(), e.what());\n      }\n    }\n\n    for (auto &sr : state->getStateReactors())\n    {\n      auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();\n      ROS_INFO(\"state reactor OnExit: %s\", srname);\n      try\n      {\n        sr->onExit();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception info: %s\",\n                  srname, e.what());\n      }\n    }\n\n    for (auto &eg : state->getEventGenerators())\n    {\n      auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();\n      ROS_INFO(\"state reactor OnExit: %s\", egname);\n      try\n      {\n        eg->onExit();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception info: %s\",\n                  egname, e.what());\n      }\n    }\n  }\n\n  template <typename StateType>\n  void ISmaccStateMachine::notifyOnStateExited(StateType *state)\n  {\n    this->lockStateMachine(\"state exit\");\n\n    signalDetector_->notifyStateExited(state);\n\n    auto fullname = demangleSymbol(typeid(StateType).name());\n    ROS_WARN_STREAM(\"exiting state: \" << fullname);\n\n    ROS_INFO_STREAM(\"Notification State Disposing: leaving state\" << state);\n    for (auto pair : this->orthogonals_)\n    {\n      auto &orthogonal = pair.second;\n      try\n      {\n        orthogonal->onDispose();\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s\",\n                  pair.second->getName().c_str(), e.what());\n      }\n    }\n\n    for (auto &sr : state->getStateReactors())\n    {\n      auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();\n      ROS_INFO(\"state reactor disposing: %s\", srname);\n      try\n      {\n        this->disconnectSmaccSignalObject(sr.get());\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception info: %s\",\n                  srname, e.what());\n      }\n    }\n\n    for (auto &eg : state->getEventGenerators())\n    {\n      auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();\n      ROS_INFO(\"state reactor disposing: %s\", egname);\n      try\n      {\n        this->disconnectSmaccSignalObject(eg.get());\n      }\n      catch (const std::exception &e)\n      {\n        ROS_ERROR(\"[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception info: %s\",\n                  egname, e.what());\n      }\n    }\n\n    this->stateCallbackConnections.clear();\n    currentState_.pop_back();\n\n    // then call exit state\n    ROS_WARN_STREAM(\"state exit: \" << fullname);\n\n    stateMachineCurrentAction = StateMachineInternalAction::TRANSITIONING;\n    this->unlockStateMachine(\"state exit\");\n  }\n  //-------------------------------------------------------------------------------------------------------\n  template <typename EventType>\n  void ISmaccStateMachine::propagateEventToStateReactors(ISmaccState *st, EventType *ev)\n  {\n    ROS_DEBUG(\"PROPAGATING EVENT [%s] TO LUs [%s]: \", demangleSymbol<EventType>().c_str(), st->getClassName().c_str());\n    for (auto &sb : st->getStateReactors())\n    {\n      sb->notifyEvent(ev);\n    }\n\n    auto *pst = st->getParentState();\n    if (pst != nullptr)\n    {\n      propagateEventToStateReactors(pst, ev);\n    }\n  }\n\n  template <typename InitialStateType>\n  void ISmaccStateMachine::buildStateMachineInfo()\n  {\n    this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>();\n    this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();\n    this->stateMachineInfo_->assembleSMStructureMessage(this);\n    this->checkStateMachineConsistence();\n  }\n\n  uint64_t ISmaccStateMachine::getCurrentStateCounter() const\n  {\n    return this->stateSeqCounter_;\n  }\n\n  ISmaccState *ISmaccStateMachine::getCurrentState() const\n  {\n    return this->currentState_.back();\n  }\n\n  const smacc::introspection::SmaccStateMachineInfo &ISmaccStateMachine::getStateMachineInfo()\n  {\n    return *this->stateMachineInfo_;\n  }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/impl/smacc_state_reactor_impl.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_state_reactor.h>\n#include <smacc/introspection/introspection.h>\n\nnamespace smacc\n{\n\ntemplate <typename EventType>\nvoid StateReactor::postEvent(const EventType &ev)\n{\n    ownerState->postEvent(ev);\n}\n\ntemplate <typename EventType>\nvoid StateReactor::postEvent()\n{\n    ownerState->postEvent<EventType>();\n}\n\ntemplate <typename TEv>\nvoid StateReactor::setOutputEvent()\n{\n    this->postEventFn = [this]() {\n        ROS_INFO_STREAM(\"[State Reactor Base] postingfn posting event: \" << demangleSymbol<TEv>());\n        auto *ev = new TEv();\n        this->ownerState->getStateMachine().postEvent(ev);\n    };\n}\n\ntemplate <typename TEv>\nvoid StateReactor::addInputEvent()\n{\n    this->eventTypes.push_back(&typeid(TEv));\n}\n\ntemplate <typename T, typename TClass>\nvoid StateReactor::createEventCallback(void (TClass::*callback)(T *), TClass *object)\n{\n    const auto *eventtype = &typeid(T);\n    this->eventCallbacks_[eventtype] = [=](void *msg) {\n        T *evptr = (T *)msg;\n        (object->*callback)(evptr);\n    };\n}\n\ntemplate <typename T>\nvoid StateReactor::createEventCallback(std::function<void(T *)> callback)\n{\n    const auto *eventtype = &typeid(T);\n    this->eventCallbacks_[eventtype] = [=](void *msg) {\n        T *evptr = (T *)msg;\n        callback(evptr);\n    };\n}\n\nnamespace introspection\n{\n\ntemplate <typename TEv>\nvoid StateReactorHandler::addInputEvent()\n{\n    StateReactorCallbackFunctor functor;\n    functor.fn = [=](std::shared_ptr<smacc::StateReactor> sr) {\n        ROS_INFO(\"[%s] State Reactor adding input event: %s\", demangleType(srInfo_->stateReactorType).c_str(), demangledTypeName<TEv>().c_str());\n        sr->addInputEvent<TEv>();\n    };\n\n    this->callbacks_.push_back(functor);\n\n    auto evtype = TypeInfo::getFromStdTypeInfo(typeid(TEv));\n    auto evinfo = std::make_shared<SmaccEventInfo>(evtype);\n    EventLabel<TEv>(evinfo->label);\n\n    srInfo_->sourceEventTypes.push_back(evinfo);\n}\n\ntemplate <typename TEv>\nvoid StateReactorHandler::setOutputEvent()\n{\n    StateReactorCallbackFunctor functor;\n    functor.fn = [=](std::shared_ptr<smacc::StateReactor> sr) {\n        ROS_INFO(\"[%s] State Reactor setting output event: %s\", demangleType(srInfo_->stateReactorType).c_str(), demangledTypeName<TEv>().c_str());\n        sr->setOutputEvent<TEv>();\n    };\n\n    this->callbacks_.push_back(functor);\n}\n} // namespace introspection\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/introspection/introspection.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <boost/statechart/state.hpp>\n#include <boost/statechart/simple_state.hpp>\n#include <boost/statechart/event.hpp>\n\n#include <ros/ros.h>\n#include <typeinfo>\n#include <boost/mpl/list.hpp>\n#include <boost/mpl/for_each.hpp>\n#include <boost/mpl/transform.hpp>\n\n#include <smacc/smacc_types.h>\n#include <smacc/introspection/string_type_walker.h>\n#include <smacc/introspection/smacc_state_info.h>\n\n#include <smacc_msgs/SmaccTransition.h>\n\nnamespace sc = boost::statechart;\n\nnamespace smacc\n{\nnamespace introspection\n{\nusing namespace boost;\nusing namespace smacc::default_transition_tags;\n\nvoid transitionInfoToMsg(const SmaccTransitionInfo &transition, smacc_msgs::SmaccTransition &transitionMsg);\n\ntypedef std::allocator<boost::statechart::none> SmaccAllocator;\n\ntemplate <class T>\nauto optionalNodeHandle(boost::intrusive_ptr<T> &obj)\n    -> ros::NodeHandle\n{\n    return obj->getROSNode();\n}\n\ntemplate <class T>\nauto optionalNodeHandle(T *) -> ros::NodeHandle\n{\n    return ros::NodeHandle(\"\");\n}\n\ninline std::string demangleSymbol(const std::string &name)\n{\n    return demangleSymbol(name.c_str());\n}\n\ninline std::string demangleSymbol(const char *name)\n{\n#if (__GNUC__ && __cplusplus && __GNUC__ >= 3)\n    int status;\n    char *res = abi::__cxa_demangle(name, 0, 0, &status);\n    if (res)\n    {\n        const std::string demangled_name(res);\n        std::free(res);\n        return demangled_name;\n    }\n    // Demangling failed, fallback to mangled name\n    return std::string(name);\n#else\n    return std::string(name);\n#endif\n}\n\ntemplate <typename T>\ninline std::string demangleSymbol()\n{\n    return demangleSymbol(typeid(T).name());\n}\n\ntemplate <class T>\ninline std::string demangledTypeName()\n{\n    return demangleSymbol(typeid(T).name());\n}\n\ninline std::string demangleType(const std::type_info* tinfo)\n{\n    return demangleSymbol(tinfo->name());\n}\n\ninline std::string demangleType(const std::type_info &tinfo)\n{\n    return demangleSymbol(tinfo.name());\n}\n\ntemplate <typename...>\nstruct typelist\n{\n};\n\n//-------------------------------------------------------------------------\ntemplate <typename T>\nclass HasEventLabel\n{\nprivate:\n    typedef char YesType[1];\n    typedef char NoType[2];\n\n    template <typename C>\n    static YesType &test(decltype(&C::getEventLabel));\n    template <typename C>\n    static NoType &test(...);\n\npublic:\n    enum\n    {\n        value = sizeof(test<T>(0)) == sizeof(YesType)\n    };\n};\n\ntemplate <typename T>\ntypename std::enable_if<HasEventLabel<T>::value, void>::type\nEventLabel(std::string &label)\n{\n    label = T::getEventLabel();\n}\n\ntemplate <typename T>\ntypename std::enable_if<!HasEventLabel<T>::value, void>::type\nEventLabel(std::string &label)\n{\n    label = \"\";\n}\n//-----------------------------------------------------------------------\n\ntemplate <typename T>\nclass HasAutomaticTransitionTag\n{\nprivate:\n    typedef char YesType[1];\n    typedef char NoType[2];\n\n    template <typename C>\n    static YesType &test(decltype(&C::getDefaultTransitionTag));\n    template <typename C>\n    static NoType &test(...);\n\npublic:\n    enum\n    {\n        value = sizeof(test<T>(0)) == sizeof(YesType)\n    };\n};\n\ntemplate <typename T>\ntypename std::enable_if<HasAutomaticTransitionTag<T>::value, void>::type\nautomaticTransitionTag(std::string &transition_name)\n{\n    transition_name = T::getDefaultTransitionTag();\n}\n\ntemplate <typename T>\ntypename std::enable_if<!HasAutomaticTransitionTag<T>::value, void>::type\nautomaticTransitionTag(std::string &transition_name)\n{\n    transition_name = \"\";\n}\n\n//-------------------------------------------------\ntemplate <typename T>\nclass HasAutomaticTransitionType\n{\nprivate:\n    typedef char YesType[1];\n    typedef char NoType[2];\n\n    template <typename C>\n    static YesType &test(decltype(&C::getDefaultTransitionType));\n    template <typename C>\n    static NoType &test(...);\n\npublic:\n    enum\n    {\n        value = sizeof(test<T>(0)) == sizeof(YesType)\n    };\n};\n\ntemplate <typename T>\ntypename std::enable_if<HasAutomaticTransitionType<T>::value, void>::type\nautomaticTransitionType(std::string &transition_type)\n{\n    transition_type = T::getDefaultTransitionType();\n}\n\ntemplate <typename T>\ntypename std::enable_if<!HasAutomaticTransitionType<T>::value, void>::type\nautomaticTransitionType(std::string &transition_type)\n{\n    transition_type = demangledTypeName<DEFAULT>();\n}\n\n// there are many ways to implement this, for instance adding static methods to the types\ntypedef boost::mpl::list<SUCCESS, ABORT, PREEMPT, CONTINUELOOP, ENDLOOP> DEFAULT_TRANSITION_TYPES;\n\n//--------------------------------\n\ntemplate <typename T>\nstruct type_\n{\n    using type = T;\n};\n\n//---------------------------------------------\ntemplate <typename T>\nstruct add_type_wrapper\n{\n    using type = type_<T>;\n};\n\ntemplate <typename TTransition>\nstruct CheckType\n{\n    CheckType(std::string *transitionTypeName)\n    {\n        this->transitionTypeName = transitionTypeName;\n    }\n\n    std::string *transitionTypeName;\n    template <typename T>\n    void operator()(T)\n    {\n        //ROS_INFO_STREAM(\"comparing..\"<< demangleSymbol<T>() <<\" vs \" << demangleSymbol<TTransition>() );\n        if (std::is_base_of<T, TTransition>::value || std::is_same<T, TTransition>::value)\n        {\n            *(this->transitionTypeName) = demangledTypeName<T>();\n            //ROS_INFO(\"YESS!\");\n        }\n    }\n};\n\ntemplate <typename TTransition>\nstatic std::string getTransitionType()\n{\n    std::string output;\n    CheckType<TTransition> op(&output);\n    using boost::mpl::_1;\n    using wrappedList = typename boost::mpl::transform<DEFAULT_TRANSITION_TYPES, _1>::type;\n\n    boost::mpl::for_each<wrappedList>(op);\n    return output;\n};\n\n// // BASE CASE\n// template <typename T>\n// static void walkStateReactorsSources(SmaccStateReactorInfo &sbinfo, typelist<T>)\n// {\n//     auto sourceType = TypeInfo::getFromStdTypeInfo(typeid(T));\n//     auto evinfo = std::make_shared<SmaccEventInfo>(sourceType);\n//     EventLabel<T>(evinfo->label);\n//     sbinfo.sourceEventTypes.push_back(evinfo);\n//     ROS_INFO_STREAM(\"event: \" << sourceType->getFullName());\n//     ROS_INFO_STREAM(\"event parameters: \" << sourceType->templateParameters.size());\n// }\n\n// // RECURSIVE CASE\n// template <typename TEvHead, typename... TEvArgs>\n// static void walkStateReactorsSources(SmaccStateReactorInfo &sbinfo, typelist<TEvHead, TEvArgs...>)\n// {\n//     auto sourceType = TypeInfo::getFromStdTypeInfo(typeid(TEvHead));\n//     auto evinfo = std::make_shared<SmaccEventInfo>(sourceType);\n//     EventLabel<TEvHead>(evinfo->label);\n//     sbinfo.sourceEventTypes.push_back(evinfo);\n//     ROS_INFO_STREAM(\"event: \" << sourceType->getFullName());\n//     ROS_INFO_STREAM(\"event parameters: \" << sourceType->templateParameters.size());\n//     walkStateReactorsSources(sbinfo, typelist<TEvArgs...>());\n// }\n\n} // namespace introspection\n} // namespace smacc\n#include <smacc/introspection/smacc_state_machine_info.h>\n"
  },
  {
    "path": "smacc/include/smacc/introspection/smacc_state_info.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <memory>\n#include <functional>\n#include <vector>\n#include <smacc/smacc_types.h>\n\nnamespace smacc\n{\nnamespace introspection\n{\n\nstruct ClientBehaviorInfoEntry\n{\n    std::function<void(smacc::ISmaccState *)> factoryFunction;\n    const std::type_info *behaviorType;\n    const std::type_info *orthogonalType;\n};\n\n//---------------------------------------------\nstruct SmaccEventInfo\n{\n    SmaccEventInfo(std::shared_ptr<TypeInfo> eventType);\n\n    std::string getEventTypeName();\n\n    std::string getEventSourceName();\n\n    // AKA orthogonal\n    std::string getOrthogonalName();\n\n    std::string label;\n\n    std::shared_ptr<TypeInfo> eventType;\n\nprivate:\n};\n\nstruct SmaccTransitionInfo\n{\n    SmaccTransitionInfo()\n    {\n    }\n\n    bool historyNode;\n    int index;\n    std::shared_ptr<SmaccStateInfo> sourceState;\n    std::shared_ptr<SmaccStateInfo> destinyState;\n\n    std::string transitionTag;\n    std::string transitionType;\n    std::shared_ptr<SmaccEventInfo> eventInfo;\n\n    smacc::introspection::TypeInfo::Ptr transitionTypeInfo;\n};\n//---------------------------------------------\n\nstruct StateReactorCallbackFunctor\n{\n    std::function<void(std::shared_ptr<smacc::StateReactor>)> fn;\n};\n\nclass StateReactorHandler\n{\nprivate:\n    std::vector<StateReactorCallbackFunctor> callbacks_;\n\npublic:\n    void configureStateReactor(std::shared_ptr<smacc::StateReactor> sr);\n\n    template <typename TEv>\n    void addInputEvent();\n\n    template <typename TEv>\n    void setOutputEvent();\n\n    std::shared_ptr<smacc::introspection::SmaccStateReactorInfo> srInfo_;\n};\n\nstruct SmaccStateReactorInfo\n{\n    std::shared_ptr<SmaccStateInfo> ownerState;\n    std::function<void(smacc::ISmaccState *)> factoryFunction;\n\n    const std::type_info *stateReactorType;\n    std::shared_ptr<TypeInfo> objectTagType;\n    std::vector<std::shared_ptr<SmaccEventInfo>> sourceEventTypes;\n    std::shared_ptr<StateReactorHandler> srh;\n};\n\n//---------------------------------------------------------\nstruct EventGeneratorCallbackFunctor\n{\n    std::function<void(std::shared_ptr<smacc::SmaccEventGenerator>)> fn;\n};\n\nclass EventGeneratorHandler\n{\nprivate:\n    std::vector<EventGeneratorCallbackFunctor> callbacks_;\n\npublic:\n    void configureEventGenerator(std::shared_ptr<smacc::SmaccEventGenerator> eg);\n\n    template <typename TEv>\n    void setOutputEvent();\n\n    std::shared_ptr<smacc::introspection::SmaccEventGeneratorInfo> egInfo_;\n};\n\nstruct SmaccEventGeneratorInfo\n{\n    std::shared_ptr<SmaccStateInfo> ownerState;\n    std::function<void(smacc::ISmaccState *)> factoryFunction;\n\n    const std::type_info *eventGeneratorType;\n    std::shared_ptr<TypeInfo> objectTagType;\n    std::vector<std::shared_ptr<SmaccEventInfo>> sourceEventTypes;\n    std::shared_ptr<EventGeneratorHandler> egh;\n};\n\n//---------------------------------------------\n\nenum class SmaccStateType\n{\n    SUPERSTATE = 2,\n    STATE = 1,\n    SUPERSTATE_ROUTINE = 1\n};\n\nclass SmaccStateInfo : public std::enable_shared_from_this<SmaccStateInfo>\n{\n\npublic:\n    typedef std::shared_ptr<SmaccStateInfo> Ptr;\n\n    static std::map<const std::type_info *, std::vector<ClientBehaviorInfoEntry>> staticBehaviorInfo;\n    static std::map<const std::type_info *, std::vector<std::shared_ptr<SmaccStateReactorInfo>>> stateReactorsInfo;\n    static std::map<const std::type_info *, std::vector<std::shared_ptr<SmaccEventGeneratorInfo>>> eventGeneratorsInfo;\n\n    int stateIndex_;\n    std::string fullStateName;\n    std::string demangledStateName;\n\n    std::shared_ptr<SmaccStateMachineInfo> stateMachine_;\n    std::shared_ptr<SmaccStateInfo> parentState_;\n    std::vector<SmaccTransitionInfo> transitions_;\n\n    std::vector<std::shared_ptr<SmaccStateInfo>> children_;\n    int depth_;\n    const std::type_info *tid_;\n\n    SmaccStateInfo(const std::type_info *tid, std::shared_ptr<SmaccStateInfo> parentState, std::shared_ptr<SmaccStateMachineInfo> stateMachineInfo);\n\n    SmaccStateType getStateLevel();\n\n    inline int depth() const { return depth_; }\n\n    void getAncestors(std::list<const SmaccStateInfo *> &ancestorsList) const;\n\n    std::string getFullPath();\n\n    template <typename StateType>\n    std::shared_ptr<SmaccStateInfo> createChildState();\n\n    template <typename EvType>\n    void declareTransition(std::shared_ptr<SmaccStateInfo> &dstState, std::string transitionTag, std::string transitionType, bool history, TypeInfo::Ptr transitionTypeInfo);\n\n    // template <typename EvSource, template <typename> typename EvType>\n    // void declareTransition(std::shared_ptr<SmaccStateInfo> &dstState, std::string transitionTag, std::string transitionType, bool history);\n\n    const std::string &toShortName() const;\n\n    std::string getDemangledFullName() const;\n};\n} // namespace introspection\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/introspection/smacc_state_machine_info.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/common.h>\n#include <smacc/smacc_orthogonal.h>\n\n// smacc_msgs\n#include <smacc_msgs/SmaccState.h>\n#include <smacc_msgs/SmaccTransition.h>\n#include <smacc_msgs/SmaccOrthogonal.h>\n#include <smacc_msgs/SmaccStateReactor.h>\n#include <smacc_msgs/SmaccEventGenerator.h>\n\nnamespace smacc\n{\nnamespace introspection\n{\nclass SmaccStateMachineInfo : public std::enable_shared_from_this<SmaccStateMachineInfo>\n{\npublic:\n    std::map<std::string, std::shared_ptr<SmaccStateInfo>> states;\n\n    std::vector<smacc_msgs::SmaccState> stateMsgs;\n\n    template <typename InitialStateType>\n    void buildStateMachineInfo();\n\n    template <typename StateType>\n    std::shared_ptr<SmaccStateInfo> createState(std::shared_ptr<SmaccStateInfo> parentState);\n\n    template <typename StateType>\n    bool containsState()\n    {\n        auto typeNameStr = typeid(StateType).name();\n\n        return states.count(typeNameStr) > 0;\n    }\n\n    template <typename StateType>\n    std::shared_ptr<SmaccStateInfo> getState()\n    {\n        if (this->containsState<StateType>())\n        {\n            return states[typeid(StateType).name()];\n        }\n        return nullptr;\n    }\n\n    template <typename StateType>\n    void addState(std::shared_ptr<StateType> &state);\n\n    void assembleSMStructureMessage(ISmaccStateMachine *sm);\n};\n\n//---------------------------------------------\nstruct AddSubState\n{\n    std::shared_ptr<SmaccStateInfo> &parentState_;\n    AddSubState(std::shared_ptr<SmaccStateInfo> &parentState)\n        : parentState_(parentState)\n    {\n    }\n\n    template <typename T>\n    void operator()(T);\n};\n\n//---------------------------------------------\nstruct AddTransition\n{\n    std::shared_ptr<SmaccStateInfo> &currentState_;\n\n    AddTransition(std::shared_ptr<SmaccStateInfo> &currentState)\n        : currentState_(currentState)\n    {\n    }\n\n    template <template <typename, typename, typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename Tag, typename DestinyState>\n    void operator()(TTransition<EvType<TevSource>, DestinyState, Tag>);\n\n    template <template <typename, typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename DestinyState>\n    void operator()(TTransition<EvType<TevSource>, DestinyState>);\n\n    template <typename T>\n    void operator()(T);\n};\n\n//---------------------------------------------\ntemplate <typename InitialStateType>\nstruct WalkStatesExecutor\n{\n    static void walkStates(std::shared_ptr<SmaccStateInfo> &currentState, bool rootInitialNode);\n};\n\n//---------------------------------------------\ntemplate <typename T>\nvoid AddSubState::operator()(T)\n{\n    using type_t = typename T::type;\n    //auto childState = this->parentState_->createChildState<type_t>()\n    WalkStatesExecutor<type_t>::walkStates(parentState_, false);\n}\n//--------------------------------------------\ntemplate <typename T>\ntypename disable_if<boost::mpl::is_sequence<T>>::type\nprocessSubState(std::shared_ptr<SmaccStateInfo> &parentState)\n{\n    WalkStatesExecutor<T>::walkStates(parentState, false);\n}\n\n//---------------------------------------------\ntemplate <typename T>\ntypename enable_if<boost::mpl::is_sequence<T>>::type\nprocessSubState(std::shared_ptr<SmaccStateInfo> &parentState)\n{\n    using boost::mpl::_1;\n    using wrappedList = typename boost::mpl::transform<T, add_type_wrapper<_1>>::type;\n    boost::mpl::for_each<wrappedList>(AddSubState(parentState));\n}\n\n//--------------------------------------------\n/*Iterate on All Transitions*/\ntemplate <typename T>\ntypename enable_if<boost::mpl::is_sequence<T>>::type\nprocessTransitions(std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n\n    ROS_INFO_STREAM(\"State %s Walker has transition list\");\n    using boost::mpl::_1;\n    using wrappedList = typename boost::mpl::transform<T, add_type_wrapper<_1>>::type;\n    boost::mpl::for_each<wrappedList>(AddTransition(sourceState));\n}\n\ntemplate <typename Ev, typename Dst, typename Tag>\nvoid processTransition(smacc::Transition<Ev, boost::statechart::deep_history<Dst>, Tag> *, std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    auto transitionTypeInfo = TypeInfo::getTypeInfoFromType<smacc::Transition<Ev, boost::statechart::deep_history<Dst>, Tag>>();\n    smacc::Transition<Ev, Dst, Tag> *mock;\n    processTransitionAux(mock, sourceState, true, transitionTypeInfo);\n}\n\ntemplate <typename Ev, typename Dst, typename Tag>\nvoid processTransition(smacc::Transition<Ev, Dst, Tag> *t, std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    auto transitionTypeInfo = TypeInfo::getTypeInfoFromType<smacc::Transition<Ev, Dst, Tag>>();\n    processTransitionAux(t, sourceState, false, transitionTypeInfo);\n}\n\ntemplate <typename Ev, typename Dst, typename Tag>\nvoid processTransitionAux(smacc::Transition<Ev, Dst, Tag> *, std::shared_ptr<SmaccStateInfo> &sourceState, bool history, TypeInfo::Ptr &transitionTypeInfo)\n{\n    ROS_INFO(\"State %s Walker transition: %s\", sourceState->toShortName().c_str(), demangleSymbol(typeid(Ev).name()).c_str());\n    std::string transitionTag;\n    std::string transitionType;\n\n    if (typeid(Tag) != typeid(default_transition_name))\n    {\n        transitionTag = demangleSymbol<Tag>();\n        transitionType = getTransitionType<Tag>();\n        ROS_DEBUG_STREAM(\"TRANSITION TYPE:\" << transitionType);\n    }\n    else\n    {\n        transitionTag = \"\";\n        automaticTransitionTag<Ev>(transitionTag);\n        automaticTransitionType<Ev>(transitionType);\n    }\n\n    ROS_INFO_STREAM(\"Transition tag: \" << transitionTag);\n\n    if (!sourceState->stateMachine_->containsState<Dst>())\n    {\n        auto realparentState = sourceState->stateMachine_->getState<typename Dst::TContext>();\n        auto siblingnode = sourceState->stateMachine_->createState<Dst>(realparentState);\n\n        //auto siblingnode = sourceState->stateMachine_->createState<Dst>(sourceState->parentState_);\n        WalkStatesExecutor<Dst>::walkStates(siblingnode, true);\n        sourceState->declareTransition<Ev>(siblingnode, transitionTag, transitionType, history, transitionTypeInfo);\n    }\n    else\n    {\n        //auto realparentState = sourceState->stateMachine_->getState<typename Dst::TContext>();\n        //auto siblingnode = sourceState->stateMachine_->createState<Dst>(realparentState);\n\n        auto siblingnode = sourceState->stateMachine_->getState<Dst>();\n        sourceState->declareTransition<Ev>(siblingnode, transitionTag, transitionType, history, transitionTypeInfo);\n    }\n}\n\n//---------------------------------------------\ntemplate <typename EvType>\nvoid SmaccStateInfo::declareTransition(std::shared_ptr<SmaccStateInfo> &dstState, std::string transitionTag, std::string transitionType, bool history, TypeInfo::Ptr transitionTypeInfo)\n{\n    auto evtype = demangledTypeName<EvType>();\n\n    SmaccTransitionInfo transitionInfo;\n    transitionInfo.index = transitions_.size();\n    transitionInfo.sourceState = shared_from_this();\n    transitionInfo.destinyState = dstState;\n    transitionInfo.transitionTypeInfo = transitionTypeInfo;\n\n    if (transitionTag != \"\")\n        transitionInfo.transitionTag = transitionTag;\n    else\n        transitionInfo.transitionTag = \"Transition_\" + std::to_string(transitionInfo.index);\n\n    transitionInfo.transitionType = transitionType;\n    transitionInfo.historyNode = history;\n\n    transitionInfo.eventInfo = std::make_shared<SmaccEventInfo>(transitionTypeInfo->templateParameters.front());\n\n    EventLabel<EvType>(transitionInfo.eventInfo->label);\n    ROS_DEBUG_STREAM(\"LABEL: \" << transitionInfo.eventInfo->label);\n\n    transitions_.push_back(transitionInfo);\n}\n//---------------------------------------------\n\n// template <typename TevSource, template <typename> typename EvType>\n// void SmaccStateInfo::declareTransition(std::shared_ptr<SmaccStateInfo> &dstState, std::string transitionTag, std::string transitionType, bool history)\n// {\n//     auto evtype = demangledTypeName<EvType<TevSource>>();\n\n//     SmaccTransitionInfo transitionInfo;\n//     transitionInfo.index = transitions_.size();\n//     transitionInfo.sourceState = shared_from_this();\n//     transitionInfo.destinyState = dstState;\n\n//     if (transitionTag != \"\")\n//         transitionInfo.transitionTag = transitionTag;\n//     else\n//         transitionInfo.transitionTag = \"Transition_\" + std::to_string(transitionInfo.index);\n\n//     transitionInfo.transitionType = transitionType;\n\n//     transitionInfo.eventInfo = std::make_shared<SmaccEventInfo>(TypeInfo::getTypeInfoFromString(demangleSymbol(typeid(EvType<TevSource>).name())));\n\n//     EventLabel<EvType<TevSource>>(transitionInfo.eventInfo->label);\n//     ROS_ERROR_STREAM(\"LABEL: \" << transitionInfo.eventInfo->label);\n\n//     transitions_.push_back(transitionInfo);\n// }\n\n//---------------------------------------------\ntemplate <typename Ev, typename Dst>\nvoid processTransition(statechart::transition<Ev, Dst> *, std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    //ROS_INFO_STREAM(\"GOTCHA\");\n}\n\ntemplate <typename Ev>\nvoid processTransition(statechart::custom_reaction<Ev> *, std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    //ROS_INFO_STREAM(\"GOTCHA\");\n}\n\n//---------------------------------------------\n// only reached if it is a leaf transition in the mpl::list\n\ntemplate <typename T>\ntypename disable_if<boost::mpl::is_sequence<T>>::type\nprocessTransitions(std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    //ROS_INFO_STREAM(\"state transition from: \" << sourceState->demangledStateName << \" of type: \" << demangledTypeName<T>());\n    T *dummy;\n    processTransition(dummy, sourceState);\n}\n\n/*\n// only reached if it is a leaf transition in the mpl::list\ntemplate <template <typename,typename,typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename Tag, typename DestinyState >\ntypename disable_if<boost::mpl::is_sequence<TTransition<EvType<TevSource>,DestinyState, Tag>>>::type\nprocessTransitions(std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    ROS_INFO(\"DETECTED COMPLEX TRANSITION **************\");\n    //ROS_INFO_STREAM(\"state transition from: \" << sourceState->demangledStateName << \" of type: \" << demangledTypeName<T>());\n    TTransition<EvType<TevSource>,DestinyState, Tag> *dummy;\n    processTransition(dummy, sourceState);\n}\n\ntemplate <template <typename,typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename DestinyState >\ntypename disable_if<boost::mpl::is_sequence<TTransition<EvType<TevSource>,DestinyState>>>::type\nprocessTransitions(std::shared_ptr<SmaccStateInfo> &sourceState)\n{\n    ROS_INFO(\"DETECTED COMPLEX TRANSITION **************\");\n    //ROS_INFO_STREAM(\"state transition from: \" << sourceState->demangledStateName << \" of type: \" << demangledTypeName<T>());\n    TTransition<EvType<TevSource>,DestinyState> *dummy;\n    processTransition(dummy, sourceState);\n}\n*/\n\n//--------------------------------------------\n\ntemplate <template <typename, typename, typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename Tag, typename DestinyState>\nvoid AddTransition::operator()(TTransition<EvType<TevSource>, DestinyState, Tag>)\n{\n    processTransitions<TTransition<EvType<TevSource>, DestinyState, Tag>>(currentState_);\n}\n\n//--------------------------------------------\n\ntemplate <template <typename, typename> typename TTransition, typename TevSource, template <typename> typename EvType, typename DestinyState>\nvoid AddTransition::operator()(TTransition<EvType<TevSource>, DestinyState>)\n{\n    processTransitions<TTransition<EvType<TevSource>, DestinyState>>(currentState_);\n}\n\ntemplate <typename TTrans>\nvoid AddTransition::operator()(TTrans)\n{\n    using type_t = typename TTrans::type;\n    processTransitions<type_t>(currentState_);\n}\n\n//------------------ staticConfigure -----------------------------\n\n// SFINAE test\ntemplate <typename T>\nclass HasOnDefinition\n{\nprivate:\n    typedef char YesType[1];\n    typedef char NoType[2];\n\n    template <typename C>\n    static YesType &test(decltype(&C::staticConfigure));\n    template <typename C>\n    static NoType &test(...);\n\npublic:\n    enum\n    {\n        value = sizeof(test<T>(0)) == sizeof(YesType)\n    };\n};\n\ntemplate <typename T>\ntypename std::enable_if<HasOnDefinition<T>::value, void>::type\nCallOnDefinition()\n{\n    /* something when T has toString ... */\n    ROS_INFO_STREAM(\"EXECUTING ONDEFINITION: \" << demangleSymbol(typeid(T).name()));\n    T::staticConfigure();\n}\n\ntemplate <typename T>\ntypename std::enable_if<!HasOnDefinition<T>::value, void>::type\nCallOnDefinition()\n{\n    ROS_INFO_STREAM(\"static OnDefinition: dont exist for \" << demangleSymbol(typeid(T).name()));\n    /* something when T has toString ... */\n}\n\n/*\nvoid CallOnDefinition(...)\n{\n\n}*/\n\n//-----------------------------------------------------------------------------------\ntemplate <typename InitialStateType>\nvoid WalkStatesExecutor<InitialStateType>::walkStates(std::shared_ptr<SmaccStateInfo> &parentState, bool rootInitialNode)\n{\n    //ros::Duration(1).sleep();\n    auto currentname = demangledTypeName<InitialStateType>();\n\n    std::shared_ptr<SmaccStateInfo> targetState;\n\n    if (!rootInitialNode)\n    {\n        if (parentState->stateMachine_->containsState<InitialStateType>())\n        {\n            // it already exist: break;\n            return;\n        }\n\n        targetState = parentState->createChildState<InitialStateType>();\n    }\n    else\n    {\n        targetState = parentState;\n    }\n\n    CallOnDefinition<InitialStateType>();\n\n    typedef typename std::remove_pointer<decltype(InitialStateType::smacc_inner_type)>::type InnerType;\n    processSubState<InnerType>(targetState);\n\n    // -------------------- REACTIONS --------------------\n    typedef typename InitialStateType::reactions reactions;\n    //ROS_INFO_STREAM(\"state machine initial state reactions: \"<< demangledTypeName<reactions>());\n\n    processTransitions<reactions>(targetState);\n}\n\n//------------------------------------------------\n\ntemplate <typename InitialStateType>\nvoid SmaccStateMachineInfo::buildStateMachineInfo()\n{\n    auto initialState = this->createState<InitialStateType>(nullptr);\n    WalkStatesExecutor<InitialStateType>::walkStates(initialState, true);\n}\n\ntemplate <typename StateType>\nstd::shared_ptr<SmaccStateInfo> SmaccStateMachineInfo::createState(std::shared_ptr<SmaccStateInfo> parent)\n{\n    auto thisptr = this->shared_from_this();\n    auto *statetid = &(typeid(StateType));\n\n    auto demangledName = demangledTypeName<StateType>();\n    ROS_INFO_STREAM(\"Creating State Info: \" << demangledName);\n\n    auto state = std::make_shared<SmaccStateInfo>(statetid, parent, thisptr);\n    state->demangledStateName = demangledName;\n    state->fullStateName = typeid(StateType).name();\n    state->stateIndex_ = states.size();\n\n    if (parent != nullptr)\n    {\n        parent->children_.push_back(state);\n    }\n\n    this->addState(state);\n\n    return state;\n}\n\ntemplate <typename StateType>\nvoid SmaccStateMachineInfo::addState(std::shared_ptr<StateType> &state)\n{\n    states[state->fullStateName] = state;\n}\n\ntemplate <typename StateType>\nstd::shared_ptr<SmaccStateInfo> SmaccStateInfo::createChildState()\n{\n    auto realparentState = this->stateMachine_->getState<typename StateType::TContext>();\n\n    auto childState = this->stateMachine_->createState<StateType>(realparentState);\n\n    ROS_WARN_STREAM(\"Real parent state> \" << demangleSymbol<typename StateType::TContext>());\n\n    /*auto contextInfo = TypeInfo::getTypeInfoFromType<InitialStateType>();\n    auto parentState2= getState<InitialStateType::TContext>();\n    parentState2->createChildState<InitialStateType>();*/\n\n    //this->stateMachine_->addState(childState);\n    //stateMachineInfo.addState(stateMachineInfo)\n    //stateNames.push_back(currentname);\n    //ROS_INFO(\"------------\");\n    //ROS_INFO_STREAM(\"** STATE state: \"<< this->demangledStateName);\n\n    return childState;\n}\n} // namespace introspection\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/introspection/state_traits.h",
    "content": "#pragma once\n\nnamespace smacc\n{\n    template <typename T, typename TransitionTagName>\n    class HasSpecificNamedOnExit\n    {\n        template <typename U, void (U::*)(TransitionTagName)>\n        struct Check;\n        template <typename U>\n        static char func(Check<U, &U::onExit> *);\n        template <typename U>\n        static int func(...);\n\n    public:\n        typedef HasSpecificNamedOnExit type;\n        enum\n        {\n            value = sizeof(func<T>(0)) == sizeof(char)\n        };\n    };\n\n    template <typename TState, typename TTransitionTagName>\n    void specificNamedOnExit(TState &st, TTransitionTagName tn, std::true_type)\n    {\n        st.onExit(tn);\n    }\n\n    template <typename TState, typename TTransitionTagName>\n    void specificNamedOnExit(TState &, TTransitionTagName tn, std::false_type)\n    {\n    }\n\n    template <typename TState, typename TTransitionTagName>\n    void specificNamedOnExit(TState &m, TTransitionTagName tn)\n    {\n        specificNamedOnExit(m, tn,\n                            std::integral_constant<bool, HasSpecificNamedOnExit<TState, TTransitionTagName>::value>());\n    }\n\n    //-------------------------------------------------\n\n    template <typename T>\n    class HasStandardOnExit\n    {\n        template <typename U, void (U::*)()>\n        struct Check;\n        template <typename U>\n        static char func(Check<U, &U::onExit> *);\n        template <typename U>\n        static int func(...);\n\n    public:\n        typedef HasStandardOnExit type;\n        enum\n        {\n            value = sizeof(func<T>(0)) == sizeof(char)\n        };\n    };\n\n    template <typename TState>\n    void standardOnExit(TState &st, std::true_type)\n    {\n        st.onExit();\n    }\n\n    template <typename TState>\n    void standardOnExit(TState &, std::false_type)\n    {\n    }\n\n    template <typename TState>\n    void standardOnExit(TState &m)\n    {\n        standardOnExit(m,\n                       std::integral_constant<bool, HasStandardOnExit<TState>::value>());\n    }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/introspection/string_type_walker.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <string>\n#include <memory>\n#include <vector>\n#include <typeinfo>\n#include <map>\n\nnamespace smacc\n{\nnamespace introspection\n{\nclass TypeInfo\n{\npublic:\n    typedef std::shared_ptr<TypeInfo> Ptr;\n\n    //---- FACTORY STATIC METHODS -----------\n    static TypeInfo::Ptr getTypeInfoFromString(std::string inputtext);\n    static TypeInfo::Ptr getFromStdTypeInfo(const std::type_info &tid);\n\n    template <typename T>\n    static TypeInfo::Ptr getTypeInfoFromType()\n    {\n        return TypeInfo::getFromStdTypeInfo(typeid(T));\n    }\n    //---------------------------------------\n\n    std::vector<Ptr> templateParameters;\n\n    TypeInfo(std::string tkey, std::string codedtype, std::string finaltype)\n    {\n        this->tkey = tkey;\n        this->codedtype = codedtype;\n        this->finaltype = finaltype;\n    }\n\n    std::string toString()\n    {\n        return this->tkey + \":\" + this->finaltype;\n    }\n\n    std::string getNonTemplatedTypeName()\n    {\n        auto index = this->finaltype.find(\"<\");\n        return this->finaltype.substr(0, index);\n    }\n\n\n    const std::string &getFullName()\n    {\n        return this->finaltype;\n    }\n\n    static std::map<std::string, Ptr> typeInfoDatabase;\n\nprivate:\n    std::string tkey;\n    std::string codedtype;\n    std::string finaltype;\n};\n} // namespace introspection\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_state_machine_base.h>\n#include <smacc/smacc_signal_detector.h>\n#include <smacc/smacc_default_events.h>\n"
  },
  {
    "path": "smacc/include/smacc/smacc_asynchronous_client_behavior.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_client_behavior_base.h>\n#include <smacc/smacc_signal.h>\n#include <thread>\n#include <condition_variable>\n#include <mutex>\n#include <future>\n\nnamespace smacc\n{\n    template <typename AsyncCB, typename Orthogonal>\n    struct EvCbFinished : sc::event<EvCbFinished<AsyncCB, Orthogonal>>\n    {\n    };\n\n    template <typename AsyncCB, typename Orthogonal>\n    struct EvCbSuccess : sc::event<EvCbSuccess<AsyncCB, Orthogonal>>\n    {\n    };\n\n    template <typename AsyncCB, typename Orthogonal>\n    struct EvCbFailure : sc::event<EvCbFailure<AsyncCB, Orthogonal>>\n    {\n    };\n\n    // Asnchronous client behaviors are used when the onEntry or onExit function execution is slow\n    // CONCEPT: this funcionality is related with the orthogonality of SmaccState machines.\n    // No behavior should block the creation of other behaviors, all of them conceptually start in parallel.\n    // Alternative for long duration behaviors: using default-synchromous SmaccClientBehaviors with the update method\n    // ASYNCHRONOUS STATE MACHINES DESIGN NOTES: Asynchronous behaviors can safely post events and use its local methods,\n    //  but the interaction with other components or elements of\n    // the state machine is not by-default thread safe and must be manually implemented. For example, if some element of the architecture\n    // (components, states, clients) need to access to this behavior client information it is needed to implement a mutex for the internal\n    // state of this behavior. Other example: if this behavior access to some component located in other thread, it is also may be needed\n    // to some mutex for that component\n    class SmaccAsyncClientBehavior : public ISmaccClientBehavior\n    {\n    public:\n        template <typename TOrthogonal, typename TSourceObject>\n        void onOrthogonalAllocation();\n\n        virtual ~SmaccAsyncClientBehavior();\n\n        template <typename TCallback, typename T>\n        boost::signals2::connection onSuccess(TCallback callback, T *object);\n\n        template <typename TCallback, typename T>\n        boost::signals2::connection onFinished(TCallback callback, T *object);\n\n        template <typename TCallback, typename T>\n        boost::signals2::connection onFailure(TCallback callback, T *object);\n\n    protected:\n        virtual void executeOnEntry() override;\n        virtual void executeOnExit() override;\n\n        void postSuccessEvent();\n        void postFailureEvent();\n\n        virtual void dispose() override;\n\n    private:\n        std::future<int> onEntryThread_;\n        std::future<int> onExitThread_;\n\n        std::function<void()> postFinishEventFn_;\n        std::function<void()> postSuccessEventFn_;\n        std::function<void()> postFailureEventFn_;\n\n        SmaccSignal<void()> onFinished_;\n        SmaccSignal<void()> onSuccess_;\n        SmaccSignal<void()> onFailure_;\n    };\n} // namespace smacc\n\n#include <smacc/impl/smacc_asynchronous_client_behavior_impl.h>\n"
  },
  {
    "path": "smacc/include/smacc/smacc_client.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/common.h>\n#include <smacc/component.h>\n#include <typeinfo>\n\nnamespace smacc\n{\nstruct ComponentKey\n{\n    ComponentKey(const std::type_info *typeinfo, std::string name)\n    {\n        this->name = name;\n        this->typeinfo = typeinfo;\n        encodedKey = std::to_string((long)(void *)typeinfo) + \"_\" + name;\n    }\n    std::string encodedKey;\n    const std::type_info *typeinfo;\n    std::string name;\n\n    bool operator<(const ComponentKey &other) const\n    {\n        return this->encodedKey < other.encodedKey;\n    }\n    bool operator==(const ComponentKey &other) const\n    {\n        return this->encodedKey == other.encodedKey;\n    }\n};\n\nclass ISmaccClient\n{\npublic:\n    ISmaccClient();\n    virtual ~ISmaccClient();\n\n    virtual void initialize();\n\n    // Returns a custom identifier defined by the specific plugin implementation\n    virtual std::string getName() const;\n\n    template <typename EventType>\n    void postEvent(const EventType &ev);\n\n    template <typename EventType>\n    void postEvent();\n\n    template <typename TComponent>\n    TComponent *getComponent();\n\n    template <typename TComponent>\n    TComponent *getComponent(std::string name);\n\n    virtual smacc::introspection::TypeInfo::Ptr getType();\n\n    inline ISmaccStateMachine *getStateMachine();\n\n    template <typename TSmaccSignal, typename T>\n    void connectSignal(TSmaccSignal &signal, void (T::*callback)(), T *object);\n\n    template <typename SmaccClientType>\n    void requiresClient(SmaccClientType *&storage);\n\n    void getComponents(std::vector<std::shared_ptr<ISmaccComponent>> &components);\n\nprotected:\n\n// it is called after the client initialization, provides information about the orthogonal it is located in\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation() {}\n\n    // components\n    std::map<ComponentKey, std::shared_ptr<smacc::ISmaccComponent>> components_;\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *createComponent(TArgs... targs);\n\n    template <typename SmaccComponentType, typename TOrthogonal, typename TClient, typename... TArgs>\n    SmaccComponentType *createNamedComponent(std::string name, TArgs... targs);\n\n    // Assigns the owner of this resource to the given state machine parameter object\n    void setStateMachine(ISmaccStateMachine *stateMachine);\n\n    void setOrthogonal(ISmaccOrthogonal *orthogonal);\n\nprivate:\n    // A reference to the state machine object that owns this resource\n    ISmaccStateMachine *stateMachine_;\n    ISmaccOrthogonal *orthogonal_;\n\n    friend class ISmaccOrthogonal;\n    friend class ISmaccComponent;\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_client_behavior.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_client_behavior_base.h>\n\nnamespace smacc\n{\n    class SmaccClientBehavior : public ISmaccClientBehavior\n    {\n    public:\n        virtual void onEntry() override;\n        virtual void onExit() override;\n    };\n} // namespace smacc\n\n#include <smacc/impl/smacc_client_behavior_impl.h>\n"
  },
  {
    "path": "smacc/include/smacc/smacc_client_behavior_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/common.h>\n\nnamespace smacc\n{\n    class ISmaccClientBehavior\n    {\n    public:\n        ISmaccClientBehavior();\n\n        virtual ~ISmaccClientBehavior();\n\n        inline ISmaccStateMachine *getStateMachine();\n\n        std::string getName() const;\n\n        template <typename SmaccClientType>\n        void requiresClient(SmaccClientType *&storage);\n\n        template <typename SmaccComponentType>\n        void requiresComponent(SmaccComponentType *&storage);\n\n        ros::NodeHandle getNode();\n\n    protected:\n        virtual void runtimeConfigure();\n\n        virtual void onEntry();\n\n        virtual void onExit();\n\n        template <typename EventType>\n        void postEvent(const EventType &ev);\n\n        template <typename EventType>\n        void postEvent();\n\n        inline ISmaccState *getCurrentState();\n\n        virtual void executeOnEntry();\n\n        virtual void executeOnExit();\n\n        virtual void dispose();\n\n    private:\n\n        template <typename TOrthogonal, typename TSourceObject>\n        void onOrthogonalAllocation();\n\n        // a reference to the owner state machine\n        ISmaccStateMachine *stateMachine_;\n\n        // a reference to the state where the client behavior is being executed\n        ISmaccState *currentState;\n\n        smacc::ISmaccOrthogonal *currentOrthogonal;\n\n        friend class ISmaccState;\n        friend class ISmaccOrthogonal;\n    };\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_default_events.h",
    "content": "#pragma once\n\n#include <boost/statechart/state.hpp>\n#include <boost/statechart/event.hpp>\n\n#include <smacc/smacc_types.h>\n\nnamespace smacc\n{\nnamespace default_events\n{\nusing namespace smacc::introspection;\nusing namespace smacc::default_transition_tags;\n\ntemplate <typename ActionFeedback, typename TOrthogonal>\nstruct EvActionFeedback : sc::event<EvActionFeedback<ActionFeedback, TOrthogonal>>\n{\n  smacc::client_bases::ISmaccActionClient *client;\n  ActionFeedback feedbackMessage;\n  //boost::any feedbackMessage;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvActionResult : sc::event<EvActionResult<TSource, TOrthogonal>>\n{\n  typename TSource::Result resultMessage;\n};\n\n//--------------------------------\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvActionSucceeded : sc::event<EvActionSucceeded<TSource, TOrthogonal>>\n{\n  typename TSource::Result resultMessage;\n\n  static std::string getEventLabel()\n  {\n    // show ros message type\n    std::string label;\n    EventLabel<TSource>(label);\n    return label;\n  }\n\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<SUCCESS>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<SUCCESS>();\n  }\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvActionAborted : sc::event<EvActionAborted<TSource, TOrthogonal>>\n{\n  typename TSource::Result resultMessage;\n\n  static std::string getEventLabel()\n  {\n    // show ros message type\n    std::string label;\n    EventLabel<TSource>(label);\n    return label;\n  }\n\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<ABORT>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<ABORT>();\n  }\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvActionPreempted : sc::event<EvActionPreempted<TSource, TOrthogonal>>\n{\n  typename TSource::Result resultMessage;\n\n  static std::string getEventLabel()\n  {\n    // show ros message type\n    std::string label;\n    EventLabel<TSource>(label);\n    return label;\n  }\n\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<PREEMPT>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<PREEMPT>();\n  }\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvActionRejected : sc::event<EvActionRejected<TSource, TOrthogonal>>\n{\n  typename TSource::Result resultMessage;\n\n  static std::string getEventLabel()\n  {\n    // show ros message type\n    std::string label;\n    EventLabel<TSource>(label);\n    return label;\n  }\n\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<REJECT>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<REJECT>();\n  }\n};\n\ntemplate <typename StateType>\nstruct EvSequenceFinished : sc::event<EvSequenceFinished<StateType>>\n{\n\n};\n\ntemplate <typename TSource>\nstruct EvLoopContinue : sc::event<EvLoopContinue<TSource>>\n{\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<CONTINUELOOP>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<CONTINUELOOP>();\n  }\n};\n\ntemplate <typename TSource>\nstruct EvLoopEnd : sc::event<EvLoopEnd<TSource>>\n{\n  static std::string getDefaultTransitionTag()\n  {\n    return demangledTypeName<ENDLOOP>();\n  }\n\n  static std::string getDefaultTransitionType()\n  {\n    return demangledTypeName<ENDLOOP>();\n  }\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvTopicInitialMessage : sc::event<EvTopicInitialMessage<TSource, TOrthogonal>>\n{\n  //typename EvTopicInitialMessage<SensorBehaviorType>::TMessageType msgData;\n  static std::string getEventLabel()\n  {\n    auto typeinfo = TypeInfo::getTypeInfoFromType<typename TSource::TMessageType>();\n\n    std::string label = typeinfo->getNonTemplatedTypeName();\n    return label;\n  }\n\n  typename TSource::TMessageType msgData;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvTopicMessage : sc::event<EvTopicMessage<TSource, TOrthogonal>>\n{\n  static std::string getEventLabel()\n  {\n    auto typeinfo = TypeInfo::getTypeInfoFromType<typename TSource::TMessageType>();\n\n    std::string label = typeinfo->getNonTemplatedTypeName();\n    return label;\n  }\n\n  typename TSource::TMessageType msgData;\n};\n} // namespace default_events\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_event_generator.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <functional>\n#include <memory>\n#include <vector>\n#include <algorithm>\n#include <smacc/introspection/introspection.h>\n#include <boost/statechart/event.hpp>\n#include <map>\n\nnamespace smacc\n{\n    class ISmaccState;\n    class ISMaccStateMachine;\n\n    class SmaccEventGenerator\n    {\n    public:\n        SmaccEventGenerator();\n        virtual ~SmaccEventGenerator();\n\n        template <typename TState, typename TSource>\n        void onStateAllocation();\n\n        virtual void onEntry();\n        virtual void onExit();\n\n        template <typename EventType>\n        void postEvent(const EventType &ev);\n\n        template <typename EventType>\n        void postEvent();\n\n        void initialize(ISmaccState *ownerState);\n        virtual void onInitialized();\n\n    private:\n        ISmaccState *ownerState_;\n        friend ISmaccStateMachine;\n    };\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_fifo_scheduler.h",
    "content": "#include <boost/statechart/fifo_scheduler.hpp>\n#include <smacc/smacc_fifo_worker.h>\n\ntypedef boost::statechart::fifo_scheduler<SmaccFifoWorker, SmaccAllocator> SmaccFifoScheduler;\n"
  },
  {
    "path": "smacc/include/smacc/smacc_fifo_worker.h",
    "content": "#pragma once\n#include <boost/statechart/fifo_worker.hpp>\n\ntypedef std::allocator<boost::statechart::none> SmaccAllocator;\ntypedef boost::statechart::fifo_worker<SmaccAllocator> SmaccFifoWorker;\n"
  },
  {
    "path": "smacc/include/smacc/smacc_orthogonal.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/common.h>\n#include <utility>\n\nnamespace smacc\n{\nclass ISmaccOrthogonal\n{\npublic:\n    void setStateMachine(ISmaccStateMachine *value);\n\n    inline ISmaccStateMachine *getStateMachine();\n\n    void initState(ISmaccState *state);\n\n    void addClientBehavior(std::shared_ptr<smacc::ISmaccClientBehavior> clientBehavior);\n\n    void runtimeConfigure();\n\n    void onEntry();\n\n    void onExit();\n\n    void onDispose();\n\n    virtual std::string getName() const;\n\n    template <typename SmaccComponentType>\n    void requiresComponent(SmaccComponentType *&storage);\n\n    template <typename SmaccClientType>\n    bool requiresClient(SmaccClientType *&storage);\n\n    inline const std::vector<std::shared_ptr<smacc::ISmaccClient>> &getClients();\n\n    inline const std::vector<std::vector<std::shared_ptr<smacc::ISmaccClientBehavior>>> &getClientBehaviors() const;\n\n    template <typename T>\n    void setGlobalSMData(std::string name, T value);\n\n    template <typename T>\n    bool getGlobalSMData(std::string name, T &ret);\n\n    template <typename TClientBehavior>\n    TClientBehavior *getClientBehavior();\n\nprotected:\n    virtual void onInitialize();\n\n    template <typename TOrthogonal, typename TClient>\n    void assignClientToOrthogonal(TClient* client);\n\n    std::vector<std::shared_ptr<smacc::ISmaccClient>> clients_;\n\nprivate:\n    ISmaccStateMachine *stateMachine_;\n\n    std::vector<std::vector<std::shared_ptr<smacc::ISmaccClientBehavior>>> clientBehaviors_;\n    friend class ISmaccStateMachine;\n};\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_signal.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <boost/signals2/signal.hpp>\n#include <boost/any.hpp>\n\nnamespace smacc\n{\nusing namespace boost;\nusing namespace boost::signals2;\nusing namespace boost::signals2::detail;\n\ntemplate <typename Signature,\n          typename Combiner = optional_last_value<typename boost::function_traits<Signature>::result_type>,\n          typename Group = int,\n          typename GroupCompare = std::less<Group>,\n          typename SlotFunction = function<Signature>,\n          typename ExtendedSlotFunction = typename extended_signature<function_traits<Signature>::arity, Signature>::function_type,\n          typename Mutex = boost::signals2::mutex>\nclass SmaccSignal : public boost::signals2::signal<Signature, Combiner, Group, GroupCompare, SlotFunction, ExtendedSlotFunction, Mutex>\n{\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_signal_detector.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <boost/thread.hpp>\n#include <smacc/common.h>\n#include <atomic>\n\nnamespace smacc\n{\nenum class ExecutionModel\n{\n  SINGLE_THREAD_SPINNER,\n  ASYNCHRONOUS_SPINNER\n};\n\n// Mostly define the state machine ros thread and receive events state machine components (clients, state elements)\n// This class also contains the event queue of the state machine\nclass SignalDetector\n{\npublic:\n  SignalDetector(SmaccFifoScheduler* scheduler, ExecutionModel executionModel = ExecutionModel::SINGLE_THREAD_SPINNER);\n\n  void initialize(ISmaccStateMachine* stateMachine);\n\n  void setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle);\n\n  // Runs the polling loop into a thread...\n  void runThread();\n\n  // Waits for the polling thread to end...\n  void join();\n\n  void stop();\n\n  void pollingLoop();\n\n  template <typename EventType>\n  void postEvent(EventType* ev)\n  {\n    boost::intrusive_ptr<EventType> weakPtrEvent = ev;\n    this->scheduler_->queue_event(processorHandle_, weakPtrEvent);\n  }\n\n  void notifyStateConfigured(ISmaccState* currentState);\n\n  void notifyStateExited(ISmaccState* currentState);\n\nprivate:\n  void pollOnce();\n\n  ISmaccStateMachine* smaccStateMachine_;\n\n  std::vector<ISmaccUpdatable*> updatableClients_;\n\n  std::vector<std::vector<ISmaccUpdatable*>> updatableStateElements_;\n\n  std::atomic<uint64_t> lastState_;\n\n  void findUpdatableClients();\n  void findUpdatableStateElements(ISmaccState* currentState);\n\n  // Loop frequency of the signal detector (to check answers from actionservers)\n  double loop_rate_hz;\n\n  std::atomic<bool> end_;\n\n  std::atomic<bool> initialized_;\n\n  ros::NodeHandle nh_;\n\n  ros::Publisher statusPub_;\n\n  // ---- boost statechart related ----\n\n  SmaccFifoScheduler* scheduler_;\n\n  SmaccFifoScheduler::processor_handle processorHandle_;\n\n  boost::thread signalDetectorThread_;\n\n  ExecutionModel executionModel_;\n};\n\n// Main entry point for any SMACC state machine\n// It instantiates and starts the specified state machine type\n// it uses two threads: a new thread and the current one.\n// The created thread is for the state machine process\n// it locks the current thread to handle events of the state machine\ntemplate <typename StateMachineType>\nvoid run(ExecutionModel executionModel = ExecutionModel::SINGLE_THREAD_SPINNER)\n{\n  // create the asynchronous state machine scheduler\n  SmaccFifoScheduler scheduler1(true);\n\n  // create the signalDetector component\n  SignalDetector signalDetector(&scheduler1, executionModel);\n\n  // create the asynchronous state machine processor\n  SmaccFifoScheduler::processor_handle sm = scheduler1.create_processor<StateMachineType>(&signalDetector);\n\n  // initialize the asynchronous state machine processor\n  signalDetector.setProcessorHandle(sm);\n\n  scheduler1.initiate_processor(sm);\n\n  // create a thread for the asynchronous state machine processor execution\n  boost::thread otherThread(boost::bind(&sc::fifo_scheduler<>::operator(), &scheduler1, 0));\n\n  // use the  main thread for the signal detector component (waiting actionclient requests)\n  signalDetector.pollingLoop();\n  scheduler1.terminate();\n  otherThread.join();\n}\n\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_state.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <smacc/common.h>\n\nnamespace smacc\n{\n  class ISmaccState\n  {\n  public:\n    virtual ISmaccStateMachine &getStateMachine() = 0;\n\n    inline ISmaccState *getParentState() { return parentState_; }\n\n    inline ros::NodeHandle &getROSNode() { return nh; }\n\n    virtual std::string getClassName();\n\n    template <typename TOrthogonal, typename TBehavior, typename... Args>\n    std::shared_ptr<TBehavior> configure(Args &&... args);\n\n    template <typename SmaccComponentType>\n    void requiresComponent(SmaccComponentType *&storage);\n\n    template <typename SmaccClientType>\n    void requiresClient(SmaccClientType *&storage);\n\n    template <typename T>\n    bool getGlobalSMData(std::string name, T &ret);\n\n    // Store globally in this state machine. (By value parameter )\n    template <typename T>\n    void setGlobalSMData(std::string name, T value);\n\n    template <typename TStateReactor, typename TTriggerEvent, typename TEventList, typename... TEvArgs>\n    std::shared_ptr<TStateReactor> createStateReactor(TEvArgs... args);\n\n    template <typename TStateReactor, typename... TEvArgs>\n    std::shared_ptr<TStateReactor> createStateReactor(TEvArgs... args);\n\n    template <typename TEventGenerator, typename... TEvArgs>\n    std::shared_ptr<TEventGenerator> createEventGenerator(TEvArgs... args);\n\n    template <typename EventType>\n    void postEvent(const EventType &ev);\n\n    template <typename EventType>\n    void postEvent();\n\n    // used for transition logging\n    template <typename TransitionType>\n    void notifyTransition();\n\n    // used for transition logging\n    void notifyTransitionFromTransitionTypeInfo(std::shared_ptr<smacc::introspection::TypeInfo> &transitionTypeInfo);\n\n    inline std::vector<std::shared_ptr<StateReactor>> &getStateReactors() { return stateReactors_; }\n\n    inline std::vector<std::shared_ptr<SmaccEventGenerator>> &getEventGenerators() { return eventGenerators_; }\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool getParam(std::string param_name, T &param_storage);\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    void setParam(std::string param_name, T param_val);\n\n    //Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool param(std::string param_name, T &param_val, const T &default_val) const;\n\n    template <typename TOrthogonal>\n    TOrthogonal *getOrthogonal();\n\n    template <typename TEventGenerator>\n    TEventGenerator* getEventGenerator();\n\n    template <typename TStateReactor>\n    TStateReactor* getStateReactor();\n\n  protected:\n    std::vector<std::shared_ptr<StateReactor>> stateReactors_;\n    std::vector<std::shared_ptr<smacc::SmaccEventGenerator>> eventGenerators_;\n\n    ros::NodeHandle nh;\n\n    ros::NodeHandle contextNh;\n\n    ISmaccState *parentState_;\n\n    const smacc::introspection::SmaccStateInfo *stateInfo_;\n  };\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_state_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <smacc/smacc_state.h>\n#include <smacc/smacc_state_reactor.h>\n#include <smacc/smacc_event_generator.h>\n#include <smacc/introspection/state_traits.h>\n\nnamespace smacc\n{\n  using namespace smacc::introspection;\n  using namespace smacc::default_events;\n\n  template <class MostDerived,\n            class Context,\n            class InnerInitial = mpl::list<>,\n            sc::history_mode historyMode = sc::has_deep_history>\n  class SmaccState : public sc::simple_state<\n                         MostDerived, Context, InnerInitial, historyMode>,\n                     public ISmaccState\n  {\n    typedef sc::simple_state<MostDerived, Context, InnerInitial, historyMode>\n        base_type;\n\n  public:\n    typedef Context TContext;\n    typedef typename Context::inner_context_type context_type;\n    typedef typename context_type::state_iterator state_iterator;\n\n    typedef InnerInitial LastDeepState;\n\n    bool finishStateThrown;\n    InnerInitial *smacc_inner_type;\n\n    //////////////////////////////////////////////////////////////////////////\n    struct my_context\n    {\n      my_context(typename base_type::context_ptr_type pContext) : pContext_(pContext)\n      {\n      }\n\n      typename base_type::context_ptr_type pContext_;\n    };\n\n    SmaccState() = delete;\n\n#define STATE_NAME (demangleSymbol(typeid(MostDerived).name()).c_str())\n    // Constructor that initializes the state ros node handle\n    SmaccState(my_context ctx)\n    {\n      static_assert(std::is_base_of<ISmaccState, Context>::value || std::is_base_of<ISmaccStateMachine, Context>::value, \"The context class must be a SmaccState or a SmaccStateMachine\");\n\n      static_assert(!std::is_same<MostDerived, Context>::value, \"The context must be a different state or state machine than the current state\");\n\n      ROS_WARN(\"[%s] creating \", STATE_NAME);\n      this->set_context(ctx.pContext_);\n\n      this->stateInfo_ = getStateInfo();\n\n      // storing a reference to the parent state\n      auto &ps = this->template context<Context>();\n      parentState_ = dynamic_cast<ISmaccState *>(&ps);\n      finishStateThrown = false;\n\n      this->contextNh = optionalNodeHandle(ctx.pContext_);\n      ROS_DEBUG(\"[%s] Ros node handle namespace for this state: %s\", STATE_NAME, contextNh.getNamespace().c_str());\n      if (contextNh.getNamespace() == \"/\")\n      {\n        auto nhname = smacc::utils::cleanShortTypeName(typeid(Context));\n        ROS_INFO(\"[%s] Creating ros NodeHandle for this state: %s\", STATE_NAME, nhname.c_str());\n        contextNh = ros::NodeHandle(nhname);\n      }\n    }\n\n    virtual ~SmaccState()\n    {\n    }\n\n    const smacc::introspection::SmaccStateInfo *getStateInfo()\n    {\n      auto smInfo = this->getStateMachine().getStateMachineInfo();\n\n      auto key = typeid(MostDerived).name();\n      if (smInfo.states.count(key))\n      {\n        return smInfo.states[key].get();\n      }\n      else\n      {\n        return nullptr;\n      }\n    }\n\n    std::string getFullName()\n    {\n      return demangleSymbol(typeid(MostDerived).name());\n    }\n\n    std::string getShortName()\n    {\n      return smacc::utils::cleanShortTypeName(typeid(MostDerived));\n    }\n\n    virtual ISmaccState *getParentState()\n    {\n      //auto* ctx = dynamic_cast<ISmaccState*>(this->template context<Context *>());\n\n      return parentState_;\n    }\n\n    // this function is called by boot statechart before the destructor call\n    void exit()\n    {\n      auto *derivedThis = static_cast<MostDerived *>(this);\n      this->getStateMachine().notifyOnStateExitting(derivedThis);\n      try\n      { // static_cast<MostDerived *>(this)->onExit();\n        standardOnExit(*derivedThis);\n      }\n      catch (...)\n      {\n      }\n      this->getStateMachine().notifyOnStateExited(derivedThis);\n    }\n\n  public:\n    // This method is static-polymorphic because of the curiously recurring template pattern. It\n    // calls to the most derived class onEntry method if declared on smacc state construction\n    void runtimeConfigure()\n    {\n    }\n\n    // This method is static-polymorphic because of the curiously recurring template pattern. It\n    // calls to the most derived class onEntry method if declared on smacc state construction\n    void onEntry()\n    {\n    }\n\n    // this method is static-polimorphic because of the curiously recurreing pattern. It\n    // calls to the most derived class onExit method if declared on smacc state destruction\n    void onExit()\n    {\n    }\n\n    template <typename T>\n    bool getGlobalSMData(std::string name, T &ret)\n    {\n      return base_type::outermost_context().getGlobalSMData(name, ret);\n    }\n\n    // Store globally in this state machine. (By value parameter )\n    template <typename T>\n    void setGlobalSMData(std::string name, T value)\n    {\n      base_type::outermost_context().setGlobalSMData(name, value);\n    }\n\n    template <typename SmaccComponentType>\n    void requiresComponent(SmaccComponentType *&storage)\n    {\n      base_type::outermost_context().requiresComponent(storage);\n    }\n\n    virtual ISmaccStateMachine &getStateMachine()\n    {\n      return base_type::outermost_context();\n    }\n\n    template <typename TOrthogonal, typename TBehavior>\n    static void configure_orthogonal_runtime(std::function<void(TBehavior &bh, MostDerived &)> initializationFunction)\n    {\n      configure_orthogonal_internal<TOrthogonal, TBehavior>([=](ISmaccState *state) {\n        //auto bh = std::make_shared<TBehavior>(args...);\n        auto bh = state->configure<TOrthogonal, TBehavior>();\n        initializationFunction(*bh, *(static_cast<MostDerived *>(state)));\n      });\n    }\n\n    template <typename TOrthogonal, typename TBehavior>\n    static void configure_orthogonal_runtime(std::function<void(TBehavior &bh)> initializationFunction)\n    {\n      configure_orthogonal_internal<TOrthogonal, TBehavior>([=](ISmaccState *state) {\n        //auto bh = std::make_shared<TBehavior>(args...);\n        auto bh = state->configure<TOrthogonal, TBehavior>();\n        initializationFunction(*bh);\n      });\n    }\n\n    template <typename TOrthogonal, typename TBehavior, typename... Args>\n    static void configure_orthogonal(Args &&... args)\n    {\n      configure_orthogonal_internal<TOrthogonal, TBehavior>(\n          [=](ISmaccState *state) {\n            //auto bh = std::make_shared<TBehavior>(args...);\n            state->configure<TOrthogonal, TBehavior>(args...);\n          });\n    }\n\n    /*\n\n  template<typename TInputEventList>\n  void ISmaccState::state_reactor_initialize_inputEventList(smacc::introspection::StateReactorHandler* sr, TInputEventList *)\n  {\n      using boost::mpl::_1;\n      using wrappedList = typename boost::mpl::transform<TInputEventList, _1>::type;\n      AddTEventType<TInputEventList> op(sr);\n      boost::mpl::for_each<wrappedList>(op);\n  }\n\n    template <typename TStateReactor, typename TOutputEvent, typename TInputEventList, typename... TArgs... args>\n    std::shared_ptr<TStateReactor> ISmaccState::static_createStateReactor(TArgs... args)\n    {\n      auto srHandler = static_createStateReactor_aux(args...);\n\n      srHandler->addInputEvent<EvTopicMessage<CbLidarSensor, OrObstaclePerception>>();\n      srHandler->addInputEvent<EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>>();\n\n      TInputEventList* mock;\n      state_reactor_initialize_inputEventList(mock,)\n\n      srHandler->setOutputEvent<TOutputEvent>();\n    }\n*/\n    template <typename TStateReactor, typename TOutputEvent, typename TInputEventList, typename... TArgs>\n    static std::shared_ptr<smacc::introspection::StateReactorHandler> static_createStateReactor(TArgs... args)\n    {\n      auto srh = std::make_shared<smacc::introspection::StateReactorHandler>();\n      auto srinfo = std::make_shared<SmaccStateReactorInfo>();\n\n      srinfo->stateReactorType = &typeid(TStateReactor);\n      srinfo->srh = srh;\n      srh->srInfo_ = srinfo;\n\n      const std::type_info *tindex = &(typeid(MostDerived)); // get identifier of the current state\n\n      if (!SmaccStateInfo::stateReactorsInfo.count(tindex))\n        SmaccStateInfo::stateReactorsInfo[tindex] = std::vector<std::shared_ptr<SmaccStateReactorInfo>>();\n\n      srinfo->factoryFunction = [&, srh, args...](ISmaccState *state) {\n        auto sr = state->createStateReactor<TStateReactor, TOutputEvent, TInputEventList, TArgs...>(args...);\n        srh->configureStateReactor(sr);\n        sr->initialize(state);\n        return sr;\n      };\n\n      SmaccStateInfo::stateReactorsInfo[tindex].push_back(srinfo);\n\n      return srh;\n    }\n\n    template <typename TEventGenerator, typename... TUArgs>\n    static std::shared_ptr<smacc::introspection::EventGeneratorHandler> static_createEventGenerator(TUArgs... args)\n    {\n      auto egh = std::make_shared<smacc::introspection::EventGeneratorHandler>();\n      auto eginfo = std::make_shared<SmaccEventGeneratorInfo>();\n      eginfo->eventGeneratorType = &typeid(TEventGenerator);\n      eginfo->egh = egh;\n      egh->egInfo_ = eginfo;\n\n      const std::type_info *tindex = &(typeid(MostDerived)); // get identifier of the current state\n\n      if (!SmaccStateInfo::eventGeneratorsInfo.count(tindex))\n        SmaccStateInfo::eventGeneratorsInfo[tindex] = std::vector<std::shared_ptr<SmaccEventGeneratorInfo>>();\n\n      eginfo->factoryFunction = [&, egh, args...](ISmaccState *state) {\n        auto eg = state->createEventGenerator<TEventGenerator>(args...);\n        egh->configureEventGenerator(eg);\n        eg->initialize(state);\n        eg->template onStateAllocation<MostDerived, TEventGenerator>();\n        return eg;\n      };\n\n      SmaccStateInfo::eventGeneratorsInfo[tindex].push_back(eginfo);\n      return egh;\n    }\n\n    template <typename TStateReactor, typename... TUArgs>\n    static std::shared_ptr<smacc::introspection::StateReactorHandler> static_createStateReactor_aux(TUArgs... args)\n    {\n      auto srh = std::make_shared<smacc::introspection::StateReactorHandler>();\n      auto srinfo = std::make_shared<SmaccStateReactorInfo>();\n\n      srinfo->stateReactorType = &typeid(TStateReactor);\n      srinfo->srh = srh;\n      srh->srInfo_ = srinfo;\n\n      const std::type_info *tindex = &(typeid(MostDerived)); // get identifier of the current state\n\n      if (!SmaccStateInfo::stateReactorsInfo.count(tindex))\n        SmaccStateInfo::stateReactorsInfo[tindex] = std::vector<std::shared_ptr<SmaccStateReactorInfo>>();\n\n      srinfo->factoryFunction = [&, srh, args...](ISmaccState *state) {\n        auto sr = state->createStateReactor<TStateReactor>(args...);\n        srh->configureStateReactor(sr);\n        sr->initialize(state);\n        return sr;\n      };\n\n      SmaccStateInfo::stateReactorsInfo[tindex].push_back(srinfo);\n\n      return srh;\n    }\n\n    void checkWhileLoopConditionAndThrowEvent(bool (MostDerived::*conditionFn)())\n    {\n      auto *thisobject = static_cast<MostDerived *>(this);\n      auto condition = boost::bind(conditionFn, thisobject);\n      bool conditionResult = condition();\n\n      //ROS_INFO(\"LOOP EVENT CONDITION: %d\", conditionResult);\n      if (conditionResult)\n      {\n        this->postEvent<EvLoopContinue<MostDerived>>();\n      }\n      else\n      {\n        this->postEvent<EvLoopEnd<MostDerived>>();\n      }\n      ROS_INFO(\"[%s] POST THROW CONDITION\", STATE_NAME);\n    }\n\n    void throwSequenceFinishedEvent()\n    {\n      this->postEvent<EvSequenceFinished<MostDerived>>();\n    }\n\n    //////////////////////////////////////////////////////////////////////////\n    // The following declarations should be private.\n    // They are only public because many compilers lack template friends.\n    //////////////////////////////////////////////////////////////////////////\n    // See base class for documentation\n    typedef typename base_type::outermost_context_base_type\n        outermost_context_base_type;\n    typedef typename base_type::inner_context_ptr_type inner_context_ptr_type;\n    typedef typename base_type::context_ptr_type context_ptr_type;\n    typedef typename base_type::inner_initial_list inner_initial_list;\n\n    static void initial_deep_construct(\n        outermost_context_base_type &outermostContextBase)\n    {\n      deep_construct(&outermostContextBase, outermostContextBase);\n    }\n\n    // See base class for documentation\n    static void deep_construct(\n        const context_ptr_type &pContext,\n        outermost_context_base_type &outermostContextBase)\n    {\n      const inner_context_ptr_type pInnerContext(\n          shallow_construct(pContext, outermostContextBase));\n      base_type::template deep_construct_inner<inner_initial_list>(\n          pInnerContext, outermostContextBase);\n    }\n\n    static inner_context_ptr_type shallow_construct(\n        const context_ptr_type &pContext,\n        outermost_context_base_type &outermostContextBase)\n    {\n      // allocating in memory\n      auto state = new MostDerived(SmaccState<MostDerived, Context, InnerInitial, historyMode>::my_context(pContext));\n      const inner_context_ptr_type pInnerContext(state);\n\n      ROS_INFO(\"[%s] State object created. Initializating...\", STATE_NAME);\n      state->entryStateInternal();\n\n      outermostContextBase.add(pInnerContext);\n      return pInnerContext;\n    }\n\n  private:\n    template <typename TOrthogonal, typename TBehavior>\n    static void configure_orthogonal_internal(std::function<void(ISmaccState *state)> initializationFunction)\n    {\n      ROS_INFO(\"[%s] Runtime configure orthogonal %s -> %s\", STATE_NAME, demangleSymbol(typeid(TOrthogonal).name()).c_str(), demangleSymbol(typeid(TBehavior).name()).c_str());\n\n      ClientBehaviorInfoEntry bhinfo;\n      bhinfo.factoryFunction = initializationFunction;\n\n      bhinfo.behaviorType = &(typeid(TBehavior));\n      bhinfo.orthogonalType = &(typeid(TOrthogonal));\n\n      const std::type_info *tindex = &(typeid(MostDerived));\n      if (!SmaccStateInfo::staticBehaviorInfo.count(tindex))\n        SmaccStateInfo::staticBehaviorInfo[tindex] = std::vector<ClientBehaviorInfoEntry>();\n\n      SmaccStateInfo::staticBehaviorInfo[tindex].push_back(bhinfo);\n    }\n\n    void entryStateInternal()\n    {\n      this->getStateMachine().notifyOnStateEntryStart(static_cast<MostDerived *>(this));\n\n      // TODO: make this static to build the parameter tree at startup\n      this->nh = ros::NodeHandle(contextNh.getNamespace() + std::string(\"/\") + smacc::utils::cleanShortTypeName(typeid(MostDerived)).c_str());\n\n      ROS_DEBUG(\"[%s] nodehandle namespace: %s\", STATE_NAME, nh.getNamespace().c_str());\n\n      this->setParam(\"created\", true);\n\n      // before dynamic runtimeConfigure, we execute the staticConfigure behavior configurations\n      {\n        ROS_INFO(\"[%s] -- STATIC STATE DESCRIPTION --\", STATE_NAME);\n\n        for (const auto &stateReactorsVector : SmaccStateInfo::staticBehaviorInfo)\n        {\n          ROS_DEBUG(\"[%s] state info: %s\", STATE_NAME, demangleSymbol(stateReactorsVector.first->name()).c_str());\n          for (auto &bhinfo : stateReactorsVector.second)\n          {\n            ROS_DEBUG(\"[%s] client behavior: %s\", STATE_NAME, demangleSymbol(bhinfo.behaviorType->name()).c_str());\n          }\n        }\n\n        const std::type_info *tindex = &(typeid(MostDerived));\n        auto &staticDefinedBehaviors = SmaccStateInfo::staticBehaviorInfo[tindex];\n        auto &staticDefinedStateReactors = SmaccStateInfo::stateReactorsInfo[tindex];\n        auto &staticDefinedEventGenerators = SmaccStateInfo::eventGeneratorsInfo[tindex];\n\n        for(auto & ortho : this->getStateMachine().getOrthogonals())\n        {\n          ROS_INFO(\"[%s] Initializing orthogonal: %s\", STATE_NAME, demangleSymbol(typeid(*ortho.second).name()).c_str());\n          ortho.second->initState(this);\n        }\n\n        for (auto &bhinfo : staticDefinedBehaviors)\n        {\n          ROS_INFO(\"[%s] Creating static client behavior: %s\", STATE_NAME, demangleSymbol(bhinfo.behaviorType->name()).c_str());\n          bhinfo.factoryFunction(this);\n        }\n\n        for (auto &sr : staticDefinedStateReactors)\n        {\n          ROS_INFO(\"[%s] Creating static state reactor: %s\", STATE_NAME, demangleSymbol(sr->stateReactorType->name()).c_str());\n          sr->factoryFunction(this);\n        }\n\n        for (auto &eg : staticDefinedEventGenerators)\n        {\n          ROS_INFO(\"[%s] Creating static event generator: %s\", STATE_NAME, demangleSymbol(eg->eventGeneratorType->name()).c_str());\n          eg->factoryFunction(this);\n        }\n\n        ROS_INFO(\"[%s] ---- END STATIC DESCRIPTION\", STATE_NAME);\n      }\n\n      ROS_INFO(\"[%s] State runtime configuration\", STATE_NAME);\n\n      auto *derivedthis = static_cast<MostDerived *>(this);\n\n      // second the orthogonals are internally configured\n      this->getStateMachine().notifyOnRuntimeConfigured(derivedthis);\n\n      // first we runtime configure the state, where we create client behaviors\n      static_cast<MostDerived *>(this)->runtimeConfigure();\n\n      this->getStateMachine().notifyOnRuntimeConfigurationFinished(derivedthis);\n\n      ROS_INFO(\"[%s] State OnEntry\", STATE_NAME);\n\n      // finally we go to the derived state onEntry Function\n      static_cast<MostDerived *>(this)->onEntry();\n\n      // here orthogonals and client behaviors are entered OnEntry\n      this->getStateMachine().notifyOnStateEntryEnd(derivedthis);\n    }\n  };\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_state_machine.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <boost/any.hpp>\n#include <map>\n#include <mutex>\n#include <stack>\n\n#include <smacc/common.h>\n#include <smacc/introspection/introspection.h>\n#include <smacc/introspection/smacc_state_machine_info.h>\n#include <smacc/smacc_updatable.h>\n#include <smacc/smacc_signal.h>\n\n#include <smacc_msgs/SmaccStateMachine.h>\n#include <smacc_msgs/SmaccTransitionLogEntry.h>\n#include <smacc_msgs/SmaccStatus.h>\n#include <smacc_msgs/SmaccGetTransitionHistory.h>\n\n#include <smacc/smacc_state.h>\n#include <smacc/smacc_state_reactor.h>\n//#include <smacc/smacc_event_generator.h>\n#include <smacc/callback_counter_semaphore.h>\n\nnamespace smacc\n{\n\nusing namespace smacc::introspection;\n\nenum class EventLifeTime{\n    ABSOLUTE,\n    CURRENT_STATE /*events are discarded if we are leaving the state it were created. I is used for client behaviors whose lifetime is associated to state*/\n};\n\nenum class StateMachineInternalAction\n{\n    STATE_CONFIGURING,\n    STATE_ENTERING,\n    STATE_STEADY,\n    STATE_EXITING,\n    TRANSITIONING\n};\n\n\n\n// This class describes the concept of Smacc State Machine in an abastract way.\n// The SmaccStateMachineBase inherits from this state machine and from\n// statechart::StateMachine<> (via multiple inheritance)\nclass ISmaccStateMachine\n{\npublic:\n    ISmaccStateMachine(SignalDetector *signalDetector);\n\n    virtual ~ISmaccStateMachine();\n\n    virtual void reset();\n\n    virtual void stop();\n\n    virtual void eStop();\n\n    template <typename TOrthogonal>\n    TOrthogonal *getOrthogonal();\n\n    const std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> &getOrthogonals() const;\n\n    template <typename SmaccComponentType>\n    void requiresComponent(SmaccComponentType *&storage);\n\n    template <typename EventType>\n    void postEvent(EventType *ev, EventLifeTime evlifetime = EventLifeTime::ABSOLUTE);\n\n    template <typename EventType>\n    void postEvent(EventLifeTime evlifetime = EventLifeTime::ABSOLUTE);\n\n    void getTransitionLogHistory();\n\n    template <typename T>\n    bool getGlobalSMData(std::string name, T &ret);\n\n    template <typename T>\n    void setGlobalSMData(std::string name, T value);\n\n    template <typename StateField, typename BehaviorType>\n    void mapBehavior();\n\n    std::string getStateMachineName();\n\n    void state_machine_visualization(const ros::TimerEvent &);\n\n    inline std::shared_ptr<SmaccStateInfo> getCurrentStateInfo() { return currentStateInfo_; }\n\n    void publishTransition(const SmaccTransitionInfo &transitionInfo);\n\n    /// this function should be implemented by the user to create the orthogonals\n    virtual void onInitialize();\n\n    bool getTransitionLogHistory(smacc_msgs::SmaccGetTransitionHistory::Request &req, smacc_msgs::SmaccGetTransitionHistory::Response &res);\n\n    template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>\n    boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object);\n\n    void disconnectSmaccSignalObject(void *object);\n\n    template <typename StateType>\n    void notifyOnStateEntryStart(StateType *state);\n\n    template <typename StateType>\n    void notifyOnStateEntryEnd(StateType *state);\n\n    template <typename StateType>\n    void notifyOnRuntimeConfigured(StateType *state);\n\n    template <typename StateType>\n    void notifyOnStateExitting(StateType *state);\n\n    template <typename StateType>\n    void notifyOnStateExited(StateType *state);\n\n    template <typename StateType>\n    void notifyOnRuntimeConfigurationFinished(StateType *state);\n\n    inline uint64_t getCurrentStateCounter() const;\n\n    inline ISmaccState *getCurrentState() const;\n\n    inline const SmaccStateMachineInfo &getStateMachineInfo();\n\n    template <typename InitialStateType>\n    void buildStateMachineInfo();\n\n    inline ros::NodeHandle getNode(){\n        return nh_;\n    };\n\n\nprotected:\n    void checkStateMachineConsistence();\n\n    void initializeROS(std::string smshortname);\n\n    void onInitialized();\n\n    template <typename TOrthogonal>\n    void createOrthogonal();\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool getParam(std::string param_name, T &param_storage);\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    void setParam(std::string param_name, T param_val);\n\n    // Delegates to ROS param access with the current NodeHandle\n    template <typename T>\n    bool param(std::string param_name, T &param_val, const T &default_val) const;\n\n    // The node handle for this state\n    ros::NodeHandle nh_;\n    ros::NodeHandle private_nh_;\n\n    ros::Timer timer_;\n    ros::Publisher stateMachinePub_;\n    ros::Publisher stateMachineStatusPub_;\n    ros::Publisher transitionLogPub_;\n    ros::ServiceServer transitionHistoryService_;\n\n    // if it is null, you may be located in a transition. There is a small gap of time where internally\n    // this currentState_ is null. This may change in the future.\n    std::vector<ISmaccState*>  currentState_;\n\n    std::shared_ptr<SmaccStateInfo> currentStateInfo_;\n\n    smacc_msgs::SmaccStatus status_msg_;\n\n    // orthogonals\n    std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> orthogonals_;\n\nprivate:\n    std::recursive_mutex m_mutex_;\n    std::recursive_mutex eventQueueMutex_;\n\n    StateMachineInternalAction stateMachineCurrentAction;\n\n    std::map<void*, std::shared_ptr<CallbackCounterSemaphore>> stateCallbackConnections;\n\n    // shared variables\n    std::map<std::string, std::pair<std::function<std::string()>, boost::any>> globalData_;\n\n    std::vector<smacc_msgs::SmaccTransitionLogEntry> transitionLogHistory_;\n\n    smacc::SMRunMode runMode_;\n\n    // Event to notify to the signaldetection thread that a request has been created...\n    SignalDetector *signalDetector_;\n\n    uint64_t stateSeqCounter_;\n\n    void lockStateMachine(std::string msg);\n\n    void unlockStateMachine(std::string msg);\n\n    template <typename EventType>\n    void propagateEventToStateReactors(ISmaccState *st, EventType *ev);\n\n    std::shared_ptr<SmaccStateMachineInfo> stateMachineInfo_;\n\n    void updateStatusMessage();\n\n    friend class ISmaccState;\n    friend class SignalDetector;\n};\n} // namespace smacc\n\n#include <smacc/impl/smacc_state_impl.h>\n#include <smacc/impl/smacc_client_impl.h>\n#include <smacc/impl/smacc_component_impl.h>\n#include <smacc/impl/smacc_orthogonal_impl.h>\n"
  },
  {
    "path": "smacc/include/smacc/smacc_state_machine_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <smacc/common.h>\n\n#include <smacc/smacc_state_base.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\n\n/// State Machine\ntemplate <typename DerivedStateMachine, typename InitialStateType>\nstruct SmaccStateMachineBase : public ISmaccStateMachine, public sc::asynchronous_state_machine<DerivedStateMachine, InitialStateType, SmaccFifoScheduler, SmaccAllocator>\n{\npublic:\n    SmaccStateMachineBase(my_context ctx, SignalDetector *signalDetector)\n        : ISmaccStateMachine(signalDetector),\n          sc::asynchronous_state_machine<DerivedStateMachine, InitialStateType, SmaccFifoScheduler, SmaccAllocator>(ctx)\n    {\n    }\n\n    virtual ~SmaccStateMachineBase()\n    {\n        //updateCurrentState<InitialStateType>(false);\n    }\n\n    virtual void reset() override\n    {\n        ISmaccStateMachine::reset();\n        this->terminate();\n        smacc::run<DerivedStateMachine>();\n    }\n\n    virtual void stop() override\n    {\n        ISmaccStateMachine::stop();\n        this->terminate();\n    }\n\n    virtual void eStop() override\n    {\n        ISmaccStateMachine::eStop();\n        this->terminate();\n    }\n\n    virtual void initiate_impl() override\n    {\n        // this is before because this creates orthogonals\n        this->onInitialize();\n\n        ROS_INFO(\"[SmaccStateMachine] Introspecting state machine via typeWalker\");\n        this->buildStateMachineInfo<InitialStateType>();\n\n        ROS_INFO(\"[SmaccStateMachine] initiate_impl\");\n        auto shortname =  smacc::utils::cleanShortTypeName(typeid(DerivedStateMachine));\n\n        this->initializeROS(shortname);\n\n        ROS_INFO(\"[SmaccStateMachine] Initializing ROS communication mechanisms\");\n        this->onInitialized();\n\n        ROS_INFO(\"[SmaccStateMachine] Initializing state machine\");\n        sc::state_machine<DerivedStateMachine, InitialStateType, SmaccAllocator>::initiate();\n    }\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_state_reactor.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <functional>\n#include <memory>\n#include <vector>\n#include <algorithm>\n#include <smacc/introspection/introspection.h>\n#include <boost/statechart/event.hpp>\n#include <map>\n\nnamespace smacc\n{\nclass ISmaccState;\nclass ISMaccStateMachine;\n\nnamespace state_reactors\n{\nstruct EmptyObjectTag\n{\n};\n} // namespace state_reactors\n\nclass StateReactor\n{\npublic:\n    ISmaccState *ownerState;\n    std::function<void()> postEventFn;\n    std::vector<const std::type_info *> eventTypes;\n    std::map<const std::type_info *, std::function<void(void *)>> eventCallbacks_;\n\n    StateReactor();\n\n    virtual void onInitialized();\n\n    virtual void onEntry();\n    virtual void onExit();\n\n    virtual void onEventNotified(const std::type_info *eventType);\n\n    template <typename EventType>\n    void postEvent(const EventType &ev);\n\n    template <typename EventType>\n    void postEvent();\n\n    // type based event callback\n    template <typename T, typename TClass>\n    void createEventCallback(void (TClass::*callback)(T *), TClass *object);\n\n    // type based event callback\n    template <typename T>\n    void createEventCallback(std::function<void(T *)> callback);\n\n    void update();\n\n    //must returns true when the output event is triggered\n    virtual bool triggers() = 0;\n\n    template <typename TEv>\n    void addInputEvent();\n\n    template <typename TEv>\n    void setOutputEvent();\n\n    //TDerived\n    void initialize(ISmaccState *ownerState);\n\nprivate:\n    friend ISmaccStateMachine;\n\n    template <typename TEvent>\n    void notifyEvent(TEvent *ev)\n    {\n        //the state machine uses this method to notify this state reactor some event happened.\n        auto tid = &(typeid(TEvent));\n        if (std::find(eventTypes.begin(), eventTypes.end(), tid) != eventTypes.end())\n        {\n            this->onEventNotified(tid);\n            this->update();\n\n            if (eventCallbacks_.count(tid))\n            {\n                eventCallbacks_[tid]((void *)ev);\n            }\n        }\n    }\n};\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_transition.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/introspection/introspection.h>\n#include <smacc/introspection/state_traits.h>\nnamespace smacc\n{\n\n//////////////////////////////////////////////////////////////////////////////\ntemplate <class Event,\n          class Destination,\n          typename Tag,\n          class TransitionContext,\n          void (TransitionContext::*pTransitionAction)(const Event &)>\nclass Transition\n{\npublic:\n  typedef Tag TRANSITION_TAG;\n\nprivate:\n  //////////////////////////////////////////////////////////////////////////\n  template <class State>\n  struct reactions\n  {\n    static boost::statechart::result react_without_action(State &stt)\n    {\n      ROS_DEBUG(\"[Smacc Transition] REACT WITHOUT ACTION\");\n      typedef smacc::Transition<Event, Destination, Tag, TransitionContext, pTransitionAction> Transtype;\n      TRANSITION_TAG mock;\n      specificNamedOnExit(stt, mock);\n\n      stt.template notifyTransition<Transtype>();\n      return stt.template transit<Destination>();\n    }\n\n    static boost::statechart::result react_with_action(State &stt, const Event &evt)\n    {\n      ROS_DEBUG(\"[Smacc Transition] REACT WITH ACTION AND EVENT\");\n      typedef smacc::Transition<Event, Destination, Tag, TransitionContext, pTransitionAction> Transtype;\n      TRANSITION_TAG mock;\n      specificNamedOnExit(stt, mock);\n      stt.template notifyTransition<Transtype>();\n      return stt.template transit<Destination>(pTransitionAction, evt);\n    }\n  };\n\npublic:\n  //////////////////////////////////////////////////////////////////////////\n  // The following declarations should be private.\n  // They are only public because many compilers lack template friends.\n  //////////////////////////////////////////////////////////////////////////\n  template <class State, class EventBase, class IdType>\n  static boost::statechart::detail::reaction_result react(\n      State &stt, const EventBase &evt, const IdType &eventType)\n  {\n    typedef boost::statechart::detail::reaction_dispatcher<\n        reactions<State>, State, EventBase, Event, TransitionContext, IdType>\n        dispatcher;\n    return dispatcher::react(stt, evt, eventType);\n  }\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_types.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <boost/statechart/transition.hpp>\n\nnamespace smacc\n{\nclass ISmaccState;\nclass ISmaccStateMachine;\nclass ISmaccClient;\nclass ISmaccUpdatable;\nclass ISmaccComponent;\nclass ISmaccClientBehavior;\nclass SmaccClientBehavior;\nclass SignalDetector;\n\nclass StateReactor;\nclass SmaccEventGenerator;\n\nnamespace client_bases\n{\nclass ISmaccActionClient;\nclass ISmaccSubscriber;\n} // namespace client_bases\n\nnamespace introspection\n{\nclass SmaccStateMachineInfo;\nclass SmaccStateInfo;\nclass StateReactorHandler;\nclass SmaccStateReactorInfo;\nclass SmaccEventGeneratorInfo;\n} // namespace introspection\n\n// ----TAGS FOR TRANSITIONS -----\n\nnamespace default_transition_tags\n{\n\n// you can also use these other labels in order to have\n// a better code readability and also to improve the visual representation\n// in the viewer\nstruct DEFAULT\n{\n};\n\nstruct ABORT\n{\n};\nstruct SUCCESS\n{\n};\nstruct PREEMPT\n{\n};\nstruct REJECT\n{\n};\n\nstruct CONTINUELOOP\n{\n};\nstruct ENDLOOP\n{\n};\n\nstruct default_transition_name : SUCCESS\n{\n};\n} // namespace default_transition_tags\n\ntemplate <class Event,\n          class Destination,\n          typename Tag = default_transition_tags::default_transition_name,\n          class TransitionContext = boost::statechart::detail::no_context<Event>,\n          void (TransitionContext::*pTransitionAction)(const Event &) =\n              &boost::statechart::detail::no_context<Event>::no_function>\nclass Transition;\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/include/smacc/smacc_updatable.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n#include <chrono>\n#include <boost/optional.hpp>\n#include <ros/duration.h>\n#include <ros/time.h>\n\nnamespace smacc\n{\nclass ISmaccUpdatable\n{\npublic:\n    ISmaccUpdatable();\n    ISmaccUpdatable(ros::Duration duration);\n\n    void executeUpdate();\n    void setUpdatePeriod(ros::Duration duration);\n\nprotected:\n    virtual void update() = 0;\n\nprivate:\n    boost::optional<ros::Duration> periodDuration_;\n    ros::Time lastUpdate_;\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>smacc</name>\n    <version>1.4.16</version>\n\n  <description>SMACC is a ROS/C++ library to implement in easy and systematic way UML StateCharts (AKA state machines). SMACC is inspired by the SMACH ROS package and it is built on top of Boost StateChart library. Developed by Reel Robotics.\n</description>\n\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n  <author email=\"ba@leadtank.org\">Brett Aldrich</author>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n  <license>MIT</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>smacc_msgs</depend>\n  <depend>std_msgs</depend>\n  <depend>actionlib_msgs</depend>\n  <depend>controller_manager_msgs</depend>\n\n  <depend>roscpp</depend>\n  <depend>actionlib</depend>\n  <depend>ros_control</depend>\n  <depend>pluginlib</depend>\n\n  <depend>log4cxx</depend>\n\n  <build_depend>message_generation</build_depend>\n  <exec_depend>message_runtime</exec_depend>\n\n  <export>\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n\n</package>\n"
  },
  {
    "path": "smacc/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc/smacc_client_behavior_base.h",
    "content": "#pragma once\n"
  },
  {
    "path": "smacc/src/smacc/callback_counter_semaphore.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <iostream>\n#include <boost/signals2.hpp>\n#include <thread>\n#include <condition_variable>\n#include <mutex>\n#include <boost/signals2.hpp>\n#include <ros/ros.h>\n#include <smacc/callback_counter_semaphore.h>\n\nnamespace smacc\n{\n    CallbackCounterSemaphore::CallbackCounterSemaphore(std::string name, int count) : count_(count), name_(name) {}\n\n    bool CallbackCounterSemaphore::acquire() {\n        std::unique_lock<std::mutex> lock(mutex_);\n        ROS_DEBUG(\"[CallbackCounterSemaphore] acquire callback %s %ld\",name_.c_str(), (long)this);\n\n        if(finalized)\n        {\n            ROS_DEBUG(\"[CallbackCounterSemaphore] callback rejected %s %ld\",name_.c_str(), (long)this);\n            return false;\n        }\n\n        ++count_;\n        cv_.notify_one();\n\n        ROS_DEBUG(\"[CallbackCounterSemaphore] callback accepted %s %ld\",name_.c_str(), (long)this);\n        return true;\n    }\n\n    void CallbackCounterSemaphore::release() {\n        std::unique_lock<std::mutex> lock(mutex_);\n        --count_;\n        cv_.notify_one();\n\n        ROS_DEBUG(\"[CallbackCounterSemaphore] callback finished %s %ld\",name_.c_str(), (long)this);\n    }\n\n    void CallbackCounterSemaphore::finalize() {\n        std::unique_lock<std::mutex> lock(mutex_);\n\n        while (count_ > 0) {\n            cv_.wait(lock);\n        }\n        finalized = true;\n\n        for(auto conn: connections_)\n        {\n            conn.disconnect();\n        }\n\n        connections_.clear();\n        ROS_DEBUG(\"[CallbackCounterSemaphore] callbacks finalized %s %ld\",name_.c_str(), (long)this);\n    }\n\n    void CallbackCounterSemaphore::addConnection(boost::signals2::connection conn)\n    {\n        std::unique_lock<std::mutex> lock(mutex_);\n\n        if(finalized)\n        {\n            ROS_DEBUG(\"[CallbackCounterSemaphore] ignoring adding callback, already finalized %s %ld\",name_.c_str(), (long)this);\n            return;\n        }\n\n        connections_.push_back(conn);\n    }\n\n}\n"
  },
  {
    "path": "smacc/src/smacc/client.cpp",
    "content": "\n/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <smacc/smacc_client.h>\n#include <smacc/impl/smacc_client_impl.h>\n\nnamespace smacc\n{\nISmaccClient::ISmaccClient()\n{\n}\n\nISmaccClient::~ISmaccClient()\n{\n}\n\nvoid ISmaccClient::initialize()\n{\n\n}\n\nvoid ISmaccClient::getComponents(std::vector<std::shared_ptr<ISmaccComponent>> &components)\n{\n    for (auto &ce : components_)\n    {\n        components.push_back(ce.second);\n    }\n}\n\nstd::string ISmaccClient::getName() const\n{\n    std::string keyname = demangleSymbol(typeid(*this).name());\n    return keyname;\n}\n\nvoid ISmaccClient::setStateMachine(ISmaccStateMachine *stateMachine)\n{\n    stateMachine_ = stateMachine;\n}\n\nvoid ISmaccClient::setOrthogonal(ISmaccOrthogonal* orthogonal)\n{\n    orthogonal_ = orthogonal;\n}\n\nsmacc::introspection::TypeInfo::Ptr ISmaccClient::getType()\n{\n    return smacc::introspection::TypeInfo::getFromStdTypeInfo(typeid(*this));\n}\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/client_bases/smacc_action_client.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include \"smacc/client_bases/smacc_action_client.h\"\n\nnamespace smacc\n{\nnamespace client_bases\n{\n\nISmaccActionClient::ISmaccActionClient()\n{\n}\n\nISmaccActionClient::~ISmaccActionClient()\n{\n}\n\n} // namespace client_bases\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/common.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include \"smacc/common.h\"\n#include \"smacc/client_bases/smacc_action_client_base.h\"\n\nnamespace smacc\n{\nnamespace utils\n{\n\nstd::string cleanShortTypeName(const std::type_info &tinfo)\n{\n    auto typeinfo= TypeInfo::getFromStdTypeInfo(tinfo);\n    auto nontemplatedfullclasname = typeinfo->getNonTemplatedTypeName();\n\n\n    //ROS_INFO(\"State full classname: %s\", fullclassname.c_str());\n\n    std::vector<std::string> strs;\n    boost::split(strs, nontemplatedfullclasname, boost::is_any_of(\"::\"));\n    std::string classname = strs.back();\n    //ROS_INFO(\"State classname: %s\", classname.c_str());\n\n\n    return classname;\n}\n} // namespace utils\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/components/cp_ros_control_interface.cpp",
    "content": "#include <smacc/client_base_components/cp_ros_control_interface.h>\n\n#include <controller_manager_msgs/ListControllerTypes.h>\n#include <controller_manager_msgs/ListControllers.h>\n#include <controller_manager_msgs/LoadController.h>\n#include <controller_manager_msgs/ReloadControllerLibraries.h>\n#include <controller_manager_msgs/SwitchController.h>\n#include <controller_manager_msgs/UnloadController.h>\n\nnamespace smacc\n{\nnamespace components\n{\nusing namespace controller_manager_msgs;\n\nCpRosControlInterface::CpRosControlInterface()\n{\n}\n\nCpRosControlInterface::~CpRosControlInterface()\n{\n}\n\nvoid CpRosControlInterface::onInitialize()\n{\n    srvListControllers = nh_.serviceClient<ListControllers>(*serviceName_);\n    srvListControllersTypes = nh_.serviceClient<ListControllerTypes>(*serviceName_);\n\n    srvLoadController = nh_.serviceClient<LoadController>(*serviceName_);\n    srvUnloadController = nh_.serviceClient<UnloadController>(*serviceName_);\n    srvReloadControllerLibraries = nh_.serviceClient<ReloadControllerLibraries>(*serviceName_);\n    srvSwitchControllers = nh_.serviceClient<SwitchController>(*serviceName_);\n}\n\nstd::vector<controller_manager_msgs::ControllerState> CpRosControlInterface::listControllers()\n{\n    ListControllers::Request req;\n    ListControllers::Response res;\n\n    srvListControllers.call(req, res);\n    return res.controller;\n}\n\nstd::vector<ControllerTypeInfo> CpRosControlInterface::listControllerTypes()\n{\n    ListControllerTypes::Request req;\n    ListControllerTypes::Response res;\n    srvListControllersTypes.call(req, res);\n\n    std::vector<ControllerTypeInfo> ret;\n    for (int i = 0; i < res.types.size(); i++)\n    {\n        ControllerTypeInfo entry;\n        entry.type = res.types[i];\n        entry.baseClass = res.base_classes[i];\n\n        ret.push_back(entry);\n    }\n\n    return ret;\n}\n\nbool CpRosControlInterface::loadController(std::string name)\n{\n    LoadController::Request req;\n    LoadController::Response res;\n    req.name = name;\n\n    srvLoadController.call(req, res);\n    return res.ok;\n}\n\nbool CpRosControlInterface::unloadController(std::string name)\n{\n    UnloadController::Request req;\n    UnloadController::Response res;\n\n    req.name = name;\n    srvUnloadController.call(req, res);\n    return res.ok;\n}\n\nbool CpRosControlInterface::reloadControllerLibraries(bool forceKill)\n{\n    ReloadControllerLibraries::Request req;\n    ReloadControllerLibraries::Response res;\n    req.force_kill = forceKill;\n\n    srvReloadControllerLibraries.call(req, res);\n\n    return res.ok;\n    //srvReloadControllerLibraries\n}\n\nbool CpRosControlInterface::switchControllers(std::vector<std::string> start_controllers,\n                                              std::vector<std::string> stop_controllers,\n                                              Strictness strictness)\n{\n    SwitchController::Request req;\n    SwitchController::Response res;\n\n    req.start_controllers = start_controllers;\n    req.stop_controllers = stop_controllers;\n    req.strictness = strictness;\n\n    srvSwitchControllers.call(req, res);\n\n    return res.ok;\n}\n}\n}\n"
  },
  {
    "path": "smacc/src/smacc/introspection/reflection.cpp",
    "content": "#include <smacc/introspection/introspection.h>\n#include <ros/ros.h>\n\nnamespace smacc\n{\n\nnamespace introspection\n{\nvoid transitionInfoToMsg(const SmaccTransitionInfo &transition, smacc_msgs::SmaccTransition &transitionMsg)\n{\n    transitionMsg.index = transition.index;\n    transitionMsg.event.event_type = transition.eventInfo->getEventTypeName();\n\n    transitionMsg.source_state_name = transition.sourceState->demangledStateName;\n\n    transitionMsg.transition_name = transition.transitionTag;\n    transitionMsg.transition_type = transition.transitionType;\n    transitionMsg.event.event_source = transition.eventInfo->getEventSourceName();\n    transitionMsg.event.event_object_tag = transition.eventInfo->getOrthogonalName();\n    transitionMsg.event.label = transition.eventInfo->label;\n    transitionMsg.history_node = transition.historyNode;\n\n    if (transition.historyNode)\n    {\n        if (transition.destinyState->parentState_ != nullptr)\n            transitionMsg.destiny_state_name = transition.destinyState->parentState_->demangledStateName;\n        else\n            transitionMsg.destiny_state_name = \"\";\n    }\n    else\n    {\n        transitionMsg.destiny_state_name = transition.destinyState->demangledStateName;\n    }\n}\n} // namespace introspection\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/introspection/string_type_walker.cpp",
    "content": "\n/*****************************************************************************************************************\n *\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <smacc/introspection/string_type_walker.h>\n\n#include <regex>\n#include <memory>\n#include <map>\n#include <set>\n#include <iostream>\n#include <boost/algorithm/string.hpp>\n\n#include <boost/algorithm/string/find_iterator.hpp>\n#include <algorithm>\n#include <boost/algorithm/string/trim.hpp>\n\n#include <smacc/common.h>\n\nnamespace smacc\n{\nnamespace introspection\n{\nbool replace(std::string& str, const std::string& from, const std::string& to)\n{\n  size_t start_pos = str.find(from);\n  if (start_pos == std::string::npos)\n    return false;\n  str.replace(start_pos, from.length(), to);\n  return true;\n}\n\nstd::string replace_back(std::string roottype, std::vector<std::pair<std::string, std::string>>& orderedtypesdict)\n{\n  while (roottype.find(\"$\") != std::string::npos)\n  {\n    for (auto& t : orderedtypesdict)\n    {\n      auto& tkey = t.first;\n      auto& tval = t.second;\n\n      replace(roottype, tkey, tval);\n    }\n  }\n\n  return roottype;\n\n  //   def replace_back(roottype, typesdict):\n  //     # replace back\n  //     while \"$\" in roottype:\n  //         #print roottype\n  //         for tkey in typesdict:\n  //             tval = typesdict[tkey]\n  //             roottype = roottype.replace(tkey, tval)\n\n  //     return roottype\n}\n\nstd::map<std::string, TypeInfo::Ptr> TypeInfo::typeInfoDatabase;\n\nTypeInfo::Ptr TypeInfo::getFromStdTypeInfo(const std::type_info& tid)\n{\n  return TypeInfo::getTypeInfoFromString(demangleSymbol(tid.name()));\n}\n\nTypeInfo::Ptr TypeInfo::getTypeInfoFromString(std::string inputtext)\n{\n  auto it = typeInfoDatabase.find(inputtext);\n\n  if (it != typeInfoDatabase.end())\n    return typeInfoDatabase[inputtext];\n\n  bool ok = false;\n  int typecount = 0;\n  std::string originalinputtext = inputtext;\n  std::map<std::string, std::string> typesdict;\n  std::map<std::string, std::string> typesdict_content;\n\n  while (!ok)\n  {\n    // simpletypeRE = r\"[^<>,\\s]+<[^<>]+>\"\n    // print (\"input: \" + inputtext)\n\n    const char* simpletypeRE = \"[^\\\\<\\\\>,\\\\s]+\\\\<[^\\\\<\\\\>]+\\\\>\";\n    // std::cout << inputtext << std::endl;\n\n    // locate moste outer template\n    std::smatch matches;\n    std::regex regex(simpletypeRE);  // matches words beginning by \"sub\"\n\n    // matches = [m for m in enumerate(re.finditer(simpletypeRE, inputtext))]\n    std::regex_search(inputtext, matches, regex);\n\n    //   if len(matches) == 0:\n    //     if len(typesdict) == 0:\n    //         tkey = \"$T\" + str(typecount)\n    //         typesdict[tkey] = inputtext\n    //     break\n\n    if (matches.size() == 0)\n    {\n      if (typesdict.size() == 0)\n      {\n        auto tkey = \"$T\" + std::to_string(typecount);\n        typesdict[tkey] = inputtext;\n      }\n      break;\n    }\n\n    // for i, m in matches:\n    //     tstr = m.group(0)\n    //     tkey = \"$T\" + str(typecount)\n    //     inputtext = inputtext.replace(tstr, tkey)\n    //     print(\"updating input text: \" + inputtext)\n    //     typecount += 1\n    //     typesdict[tkey] = tstr\n\n    // find and replace internal templates with tokens\n    int i = 0;\n    for (auto& m : matches)\n    {\n      std::string tstr = m;\n      auto tkey = \"$T\" + std::to_string(typecount);\n      replace(inputtext, tstr, tkey);\n\n      // std::cout << \"updating input text:\" << inputtext << std::endl;\n\n      typecount++;\n      typesdict[tkey] = tstr;\n\n      i++;\n    }\n  }\n\n  // allbasetypes = set()\n  // for tkey in typesdict.keys():\n  //     flat = typesdict[tkey]\n  //     print flat\n  //     startindex = flat.index(\"<\")\n  //     flat = flat[startindex + 1:-1]\n  //     basetypes = [t.strip() for t in flat.split(\",\")]\n  //     for b in basetypes:\n  //         if not \"$\" in b:\n  //             allbasetypes.add(b)\n\n  // SORT by token key to replace back in a single pass\n  std::vector<std::pair<std::string, std::string>> orderedTypedict;\n  for (const auto& item : typesdict)\n  {\n    orderedTypedict.emplace_back(item);\n  }\n\n  std::sort(orderedTypedict.begin(), orderedTypedict.end(),\n            [](auto& a, auto& b) { return std::stoi(a.first.substr(2)) < std::stoi(b.first.substr(2)); });\n\n  std::set<std::string> allbasetypes;\n  for (auto& typeentry : orderedTypedict /*typesdict*/)\n  {\n    auto flat = typeentry.second;\n    // std::cout << flat << std::endl;\n\n    size_t startindex = flat.find(\"<\");\n    size_t endindex = flat.find(\">\");\n    if (startindex != std::string::npos)\n    {\n      flat = flat.substr(startindex + 1,\n                         endindex - startindex - 1);  // gets the list of template parameters in csv format\n\n      // std::cout << typeentry.first <<\":\" << flat << std::endl;\n      typesdict_content[typeentry.first] = flat;\n      std::vector<std::string> localbasetypes;\n\n      std::istringstream iss(flat);\n      std::string token;\n      while (std::getline(iss, token, ','))\n      {\n        boost::trim(token);\n        localbasetypes.push_back(token);\n        // std::cout << \"base type: \" << token << std::endl;\n      }\n\n      for (auto& b : localbasetypes)\n      {\n        size_t found = b.find(\"$\");\n\n        if (found == std::string::npos)\n        {\n          allbasetypes.insert(b);\n        }\n      }\n    }\n\n    // for b in allbasetypes:\n    // typesdict[b] = b\n\n    // refresh\n    for (auto& b : allbasetypes)\n    {\n      typesdict[b] = b;\n    }\n  }\n  // types = []\n  // for tkey in typesdict:\n  //     finaltype = replace_back(typesdict[tkey], typesdict)\n  //     t = TypeInfo(tkey, typesdict[tkey], finaltype)\n  //     types.append(t)\n\n  //     print t\n\n  // append leaf types\n  for (auto& b : allbasetypes)\n  {\n    orderedTypedict.push_back({ b, b });\n  }\n\n  // std::cout << \"---------- TYPES -------\" << std::endl;\n  std::vector<TypeInfo::Ptr> types;\n  std::vector<std::string> tokens;\n\n  for (auto t : orderedTypedict)  // must be ordered. to avoid issue, ie: $11 to be replaced in $T14\n  {\n    // auto t = *it;\n    auto& tkey = t.first;\n    auto& tval = t.second;\n    auto finaltype = replace_back(tval, orderedTypedict);\n    auto tinfo = std::make_shared<TypeInfo>(tkey, tval, finaltype);\n    types.push_back(tinfo);\n    tokens.push_back(tkey);\n\n    // std::cout << \"replacing back: \" << finaltype << std::endl;\n  }\n\n  TypeInfo::Ptr roottype = nullptr;\n  for (auto& t : types)\n  {\n    // std::cout << t->finaltype << \" vs \" <<originalinputtext;\n    if (t->finaltype == originalinputtext)\n    {\n      roottype = t;\n      break;\n    }\n  }\n\n  // std::sort(types.begin(), types.end(),[](auto& a, auto& b)\n  // {\n  //     return a->getFullName().size() > b->getFullName().size();\n  // });\n\n  /*\n    std::cout<<\"types order:\" << std::endl;\n    for(auto t: types)\n    {\n        std::cout<< t->codedtype << std::endl;\n    }\n    std::cout<<\"---------\" << std::endl;\n\n    std::cout<<\"types order:\" << std::endl;\n    for(auto t: types)\n    {\n        std::cout<< t->finaltype << std::endl;\n    }\n    std::cout<<\"---------\" << std::endl;\n    */\n\n  for (size_t i = 0; i < types.size(); i++)\n  {\n    auto t = types[i];\n    auto ttoken = tokens[i];\n\n    // auto t = types[it1];\n    std::vector<std::pair<int, TypeInfo::Ptr>> unorderedTemplateParameters;\n\n    // std::cout << \"original typestr: \" << codedtypecopy << std::endl;\n\n    // auto codedtypecopy = t->codedtype;\n    auto codedtypecopy = typesdict_content[ttoken];\n\n    // std::cout << \"original typestr: \" << codedtypecopy << std::endl;\n    // std::cout << \"original token: \" << ttoken << std::endl;\n    // std::cout << \"original typestr: \" << typesdict_content[ttoken] << std::endl;\n\n    // size_t startindex = codedtypecopy.find(\"<\");\n    // size_t endindex = codedtypecopy.find(\">\");\n\n    // if (startindex != std::string::npos)\n    // {\n    //     codedtypecopy = codedtypecopy.substr(startindex + 1, endindex - startindex - 1);\n    // }\n    // std::cout << \"original typestr: \" << codedtypecopy << std::endl;\n\n    for (auto& t2 : types)\n    // for (auto it2= types.size() -1; it2 >=0; it2--)\n    {\n      // std::cout << it2 << std::endl;\n      // auto t2 = types[it2];\n      // std::cout << t2->getFullName() << std::endl;\n      if (t == t2)\n        continue;\n\n      auto index = codedtypecopy.find(t2->tkey);\n      if (index != std::string::npos)\n      {\n        auto pair = std::make_pair(index, t2);  // this line is important for the order of templates\n        // auto pair = std::make_pair(0, t2);\n        // std::cout << \"matches: \" << t2->tkey <<std::endl;\n        unorderedTemplateParameters.push_back(pair);\n        replace(codedtypecopy, t2->tkey, \"\");  // consume token\n        // std::cout << \"codedtypecopy: \" << codedtypecopy << std::endl;\n      }\n    }\n\n    std::sort(unorderedTemplateParameters.begin(), unorderedTemplateParameters.end(),\n              [](auto& a, auto& b) -> bool { return a.first <= b.first; });\n\n    ROS_DEBUG_STREAM(\"------------------\");\n    ROS_DEBUG_STREAM(\"CREATING TYPE:\" << t->getFullName());\n\n    for (auto& item : unorderedTemplateParameters)\n    {\n      ROS_DEBUG_STREAM(\" - template parameter: \" << item.second->getFullName());\n      t->templateParameters.push_back(item.second);\n    }\n    ROS_DEBUG_STREAM(\"------------------\");\n  }\n\n  ROS_DEBUG_STREAM(\"ADDING TYPE TO DATABASE: \" << inputtext);\n  ROS_DEBUG_STREAM(\"Current Database\");\n  for (auto& en : typeInfoDatabase)\n  {\n    ROS_DEBUG_STREAM(\"- \" << en.first);\n  }\n\n  typeInfoDatabase[originalinputtext] = roottype;\n  return roottype;\n}\n\n/*\n\n    print (typesdict)\n    roottype = [t for t in types if t.finaltype == originalinputtext][0]\n\n    print \"---------------------------------\"\n\n    # fill template parameters\n    for t in types:\n        for t2 in types:\n            if t2.tkey in t.codedtype:\n                index = t.codedtype.index(t2.tkey)\n                t.template_parameters.append((index, t2))\n\n        t.template_parameters = [x[1] for x in sorted(\n            t.template_parameters, key=lambda e: e[0])]\n\n    return roottype\n\n}\n*/\n\n}  // namespace introspection\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/orthogonal.cpp",
    "content": "#include <smacc/impl/smacc_state_machine_impl.h>\n#include <smacc/smacc_client_behavior.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace smacc\n{\n    void ISmaccOrthogonal::setStateMachine(ISmaccStateMachine *value)\n    {\n        this->stateMachine_ = value;\n        this->onInitialize();\n    }\n\n    void ISmaccOrthogonal::addClientBehavior(std::shared_ptr<smacc::ISmaccClientBehavior> clBehavior)\n    {\n        if (clBehavior != nullptr)\n        {\n            ROS_INFO(\"[Orthogonal %s] adding client behavior: %s\", this->getName().c_str(), clBehavior->getName().c_str());\n            clBehavior->stateMachine_ = this->getStateMachine();\n            clBehavior->currentOrthogonal = this;\n\n            clientBehaviors_.back().push_back(clBehavior);\n        }\n        else\n        {\n            ROS_INFO(\"[orthogonal %s] no client behaviors in this state\", this->getName().c_str());\n        }\n    }\n\n    void ISmaccOrthogonal::onInitialize()\n    {\n    }\n\n    void ISmaccOrthogonal::initState(ISmaccState *state)\n    {\n        ROS_INFO(\"[Orthogonal %s] initState: %s\", this->getName().c_str(), state->getClassName().c_str());\n        clientBehaviors_.push_back(std::vector<std::shared_ptr<smacc::ISmaccClientBehavior>>());\n    }\n\n    std::string ISmaccOrthogonal::getName() const\n    {\n        return demangleSymbol(typeid(*this).name());\n    }\n\n    void ISmaccOrthogonal::runtimeConfigure()\n    {\n        for (auto &clBehavior : clientBehaviors_.back())\n        {\n            ROS_INFO(\"[Orthogonal %s] runtimeConfigure, current Behavior: %s\", this->getName().c_str(),\n                     clBehavior->getName().c_str());\n\n            clBehavior->runtimeConfigure();\n        }\n    }\n\n    void ISmaccOrthogonal::onEntry()\n    {\n        if (clientBehaviors_.back().size() > 0)\n        {\n            for (auto &clBehavior : clientBehaviors_.back())\n            {\n                ROS_INFO(\"[Orthogonal %s] OnEntry, current Behavior: %s\", this->getName().c_str(), clBehavior->getName().c_str());\n\n                try\n                {\n                    clBehavior->executeOnEntry();\n                }\n                catch (const std::exception &e)\n                {\n                    ROS_ERROR(\"[ClientBehavior %s] Exception on Entry - continuing with next client behavior. Exception info: %s\",\n                              clBehavior->getName().c_str(), e.what());\n                }\n            }\n        }\n        else\n        {\n            ROS_INFO(\"[Orthogonal %s] OnEntry\", this->getName().c_str());\n        }\n    }\n\n    void ISmaccOrthogonal::onExit()\n    {\n        if (clientBehaviors_.back().size() > 0)\n        {\n            for (auto &clBehavior : clientBehaviors_.back())\n            {\n                ROS_INFO(\"[Orthogonal %s] OnExit, current Behavior: %s\", this->getName().c_str(), clBehavior->getName().c_str());\n                try\n                {\n                    clBehavior->executeOnExit();\n                }\n                catch (const std::exception &e)\n                {\n                    ROS_ERROR(\"[ClientBehavior %s] Exception onExit - continuing with next client behavior. Exception info: %s\", clBehavior->getName().c_str(), e.what());\n                }\n            }\n        }\n        else\n        {\n            ROS_INFO(\"[Orthogonal %s] OnExit\", this->getName().c_str());\n        }\n    }\n\n    void ISmaccOrthogonal::onDispose()\n    {\n        for (auto &clBehavior : clientBehaviors_.back())\n        {\n            clBehavior->dispose();\n            this->getStateMachine()->disconnectSmaccSignalObject((void*)clBehavior.get());\n        }\n\n        clientBehaviors_.back().clear();\n        clientBehaviors_.pop_back();\n    }\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/signal_detector.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <smacc/client_bases/smacc_action_client_base.h>\n#include <smacc/smacc_signal_detector.h>\n#include <smacc/smacc_state_machine.h>\n#include <thread>\n\nnamespace smacc\n{\n/**\n ******************************************************************************************************************\n * SignalDetector()\n ******************************************************************************************************************\n */\nSignalDetector::SignalDetector(SmaccFifoScheduler *scheduler, ExecutionModel executionModel)\n  : end_(false),\n    initialized_(false),\n    executionModel_(executionModel)\n{\n  scheduler_ = scheduler;\n  loop_rate_hz = 20.0;\n}\n\n/**\n ******************************************************************************************************************\n * initialize()\n ******************************************************************************************************************\n */\nvoid SignalDetector::initialize(ISmaccStateMachine *stateMachine)\n{\n  smaccStateMachine_ = stateMachine;\n  lastState_ = std::numeric_limits<uint64_t>::quiet_NaN();\n  findUpdatableClients();\n  initialized_ = true;\n}\n\n/**\n ******************************************************************************************************************\n * findUpdatableClients()\n ******************************************************************************************************************\n */\nvoid SignalDetector::findUpdatableClients()\n{\n  this->updatableClients_.clear();\n  for (auto pair : this->smaccStateMachine_->getOrthogonals())\n  {\n    auto &orthogonal = pair.second;\n    auto &clients = orthogonal->getClients();\n\n    for (auto &client : clients)\n    {\n      // updatable client components\n      auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());\n\n      if (updatableClient != nullptr)\n      {\n        ROS_DEBUG_STREAM(\"Adding updatable client: \" << demangleType(typeid(updatableClient)));\n        this->updatableClients_.push_back(updatableClient);\n      }\n\n      // updatable client components\n      std::vector<std::shared_ptr<ISmaccComponent>> components;\n      client->getComponents(components);\n      for (auto &componententry : components)\n      {\n        auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());\n        if (updatableComponent != nullptr)\n        {\n          ROS_DEBUG_STREAM(\"Adding updatable component: \" << demangleType(typeid(*updatableComponent)));\n          this->updatableClients_.push_back(updatableComponent);\n        }\n      }\n    }\n  }\n}\n\n/**\n ******************************************************************************************************************\n * findUpdatableClientBehaviors()\n ******************************************************************************************************************\n */\nvoid SignalDetector::findUpdatableStateElements(ISmaccState *currentState)\n{\n  updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());\n\n  auto& updatableElements = updatableStateElements_.back();\n\n  for (auto pair : this->smaccStateMachine_->getOrthogonals())\n  {\n    auto &orthogonal = pair.second;\n    auto &behaviors = orthogonal->getClientBehaviors().back();\n\n    for (auto &currentBehavior : behaviors)\n    {\n      ISmaccUpdatable *updatableClientBehavior = dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());\n\n      if (updatableClientBehavior != nullptr)\n      {\n        ROS_DEBUG_STREAM(\"Adding updatable behavior: \" << demangleType(typeid(updatableClientBehavior)));\n        updatableElements.push_back(updatableClientBehavior);\n      }\n    }\n  }\n\n  auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);\n  if (updatableState != nullptr)\n  {\n    updatableElements.push_back(updatableState);\n  }\n\n  auto statereactors = currentState->getStateReactors();\n  for (auto &sr : statereactors)\n  {\n    ISmaccUpdatable *updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());\n    if (updatableStateReactor != nullptr)\n    {\n      ROS_DEBUG_STREAM(\"Adding updatable stateReactorr: \" << demangleType(typeid(updatableStateReactor)));\n      updatableElements.push_back(updatableStateReactor);\n    }\n  }\n\n  auto eventgenerators = currentState->getEventGenerators();\n  for (auto &eg : eventgenerators)\n  {\n    ISmaccUpdatable *updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());\n    if (updatableEventGenerator != nullptr)\n    {\n      ROS_DEBUG_STREAM(\"Adding updatable eventGenerator: \" << demangleType(typeid(updatableEventGenerator)));\n      updatableElements.push_back(updatableEventGenerator);\n    }\n  }\n}\n\n/**\n ******************************************************************************************************************\n * setProcessorHandle()\n ******************************************************************************************************************\n */\nvoid SignalDetector::setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)\n{\n  processorHandle_ = processorHandle;\n}\n\n/**\n ******************************************************************************************************************\n * runThread()\n ******************************************************************************************************************\n */\nvoid SignalDetector::runThread()\n{\n  signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));\n}\n\n/**\n ******************************************************************************************************************\n * join()\n ******************************************************************************************************************\n */\nvoid SignalDetector::join()\n{\n  signalDetectorThread_.join();\n}\n\n/**\n ******************************************************************************************************************\n * stop()\n ******************************************************************************************************************\n */\nvoid SignalDetector::stop()\n{\n  end_ = true;\n}\n\nvoid SignalDetector::notifyStateConfigured(ISmaccState* currentState)\n{\n  this->findUpdatableStateElements(currentState);\n}\n\nvoid SignalDetector::notifyStateExited(ISmaccState* currentState)\n{\n  this->updatableStateElements_.pop_back();\n}\n\n\n/**\n ******************************************************************************************************************\n * poll()\n ******************************************************************************************************************\n */\nvoid SignalDetector::pollOnce()\n{\n  // precondition: smaccStateMachine_ != nullptr\n\n  try\n  {\n    smaccStateMachine_->lockStateMachine(\"update behaviors\");\n\n    this->findUpdatableClients();\n    ROS_DEBUG_STREAM(\"updatable clients: \" << this->updatableClients_.size());\n\n    if (this->updatableClients_.size())\n    {\n      for (auto *updatableClient : this->updatableClients_)\n      {\n        ROS_DEBUG_STREAM(\"[PollOnce] update client call:  \" << demangleType(typeid(updatableClient)));\n        updatableClient->executeUpdate();\n      }\n    }\n\n    // STATE UPDATABLE ELEMENTS\n    if (this->smaccStateMachine_->stateMachineCurrentAction != StateMachineInternalAction::TRANSITIONING &&\n        this->smaccStateMachine_->stateMachineCurrentAction != StateMachineInternalAction::STATE_CONFIGURING &&\n        this->smaccStateMachine_->stateMachineCurrentAction != StateMachineInternalAction::STATE_EXITING &&\n        this->smaccStateMachine_->stateMachineCurrentAction != StateMachineInternalAction::STATE_ENTERING)\n    {\n\n      // // we do not update updatable elements during trasitioning or configuration of states\n      // long currentStateIndex = smaccStateMachine_->getCurrentStateCounter();\n\n      // ROS_DEBUG_STREAM(\"[PollOnce] update behaviors. checking current state\");\n\n      // auto currentState = smaccStateMachine_->getCurrentState();\n      // if (currentState != nullptr)\n      // {\n      //   ROS_DEBUG_STREAM(\"[PollOnce] current state: \" << currentStateIndex);\n      //   ROS_DEBUG_STREAM(\"[PollOnce] last state: \" << this->lastState_);\n\n      //   if (currentStateIndex != 0)\n      //   {\n      //     if (currentStateIndex != this->lastState_)\n      //     {\n      //       ROS_DEBUG_STREAM(\"[PollOnce] detected new state, refreshing updatable client behavior table\");\n      //       // we are in a new state, refresh the updatable client behaviors table\n      //       this->lastState_ = currentStateIndex;\n      //     }\n\n        ROS_DEBUG_STREAM(\"updatable states: \" << this->updatableStateElements_.size());\n\n        for (auto stateElement : this->updatableStateElements_)\n        {\n          for (auto *udpatableStateElement : stateElement)\n          {\n            ROS_DEBUG_STREAM(\"pollOnce update client behavior call: \" << demangleType(typeid(*udpatableStateElement)));\n            udpatableStateElement->executeUpdate();\n          }\n        }\n        // }\n      //}\n    }\n  }\n  catch (std::exception &ex)\n  {\n    ROS_ERROR(\"Exception during Signal Detector update loop. %s\", ex.what());\n  }\n\n  smaccStateMachine_->unlockStateMachine(\"update behaviors\");\n}\n\n/**\n ******************************************************************************************************************\n * pollingLoop()\n ******************************************************************************************************************\n */\nvoid SignalDetector::pollingLoop()\n{\n  // ros::NodeHandle nh(\"~\"); // use node name as root of the parameter server\n\n  ros::NodeHandle _;\n  ros::Rate r0(20);\n  while (!initialized_)\n  {\n    r0.sleep();\n  }\n\n  ros::NodeHandle nh(smacc::utils::cleanShortTypeName(typeid(*this->smaccStateMachine_)));\n\n  if (!nh.getParam(\"signal_detector_loop_freq\", this->loop_rate_hz))\n  {\n    ROS_WARN(\"Signal detector frequency (ros param ~signal_detector_loop_freq) was not set, using default frequency: \"\n             \"%lf\",\n             this->loop_rate_hz);\n  }\n  else\n  {\n    ROS_WARN(\"Signal detector frequency (ros param ~signal_detector_loop_freq): %lf\", this->loop_rate_hz);\n  }\n\n  nh.setParam(\"signal_detector_loop_freq\", this->loop_rate_hz);\n\n  ROS_INFO_STREAM(\"[SignalDetector] loop rate hz:\" << loop_rate_hz);\n\n  if (this->executionModel_ == ExecutionModel::SINGLE_THREAD_SPINNER)\n  {\n    ROS_INFO_STREAM(\"[SignalDetector] running in single threaded mode\");\n\n    ros::Rate r(loop_rate_hz);\n    while (ros::ok() && !end_)\n    {\n      ROS_INFO_STREAM_THROTTLE(10, \"[SignalDetector] heartbeat\");\n      pollOnce();\n      ros::spinOnce();\n      r.sleep();\n    }\n  }\n  else\n  {\n    ROS_INFO_STREAM(\"[SignalDetector] running in multi threaded mode\");\n    ros::AsyncSpinner spinner(1);\n    spinner.start();\n    ros::waitForShutdown();\n  }\n\n}\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_client_async_behavior.cpp",
    "content": "#include <smacc/smacc_asynchronous_client_behavior.h>\n\nnamespace smacc\n{\n    void SmaccAsyncClientBehavior::executeOnEntry()\n    {\n        ROS_INFO_STREAM(\"[\" << getName() << \"] Creating asynchronous onEntry thread\");\n        this->onEntryThread_ = std::async(std::launch::async,\n                                          [=] {\n                                              this->onEntry();\n                                              this->postFinishEventFn_();\n                                              return 0;\n                                          });\n    }\n\n    void SmaccAsyncClientBehavior::executeOnExit()\n    {\n        ROS_INFO_STREAM(\"[\" << getName() << \"] onExit - join async onEntry thread\");\n\n        try\n        {\n            ros::Rate r(200);\n            while (ros::ok())\n            {\n                bool valid = this->onEntryThread_.valid();\n                if (valid)\n                {\n                    auto status = this->onEntryThread_.wait_for(std::chrono::milliseconds(20));\n                    if (status == std::future_status::ready)\n                    {\n                        this->onEntryThread_.get();\n                        break;\n                    }\n                }\n\n                r.sleep();\n                ros::spinOnce();\n                ROS_DEBUG(\"waiting for finishing client behavior\");\n            }\n        }\n        catch (const std::exception &e)\n        {\n            ROS_DEBUG(\"[SmaccAsyncClientBehavior] trying to Join onEntry function, but it was already finished.\");\n        }\n\n        ROS_INFO_STREAM(\"[\" << getName() << \"] onExit - Creating asynchronous onExit thread\");\n        this->onExitThread_ = std::async(std::launch::async,\n                                         [=] {\n                                             this->onExit();\n                                             return 0;\n                                         });\n    }\n\n    void SmaccAsyncClientBehavior::dispose()\n    {\n        ROS_DEBUG_STREAM(\"[\" << getName() << \"] Destroying client behavior- Waiting finishing of asynchronous onExit thread\");\n        try\n        {\n            this->onExitThread_.get();\n        }\n        catch (...)\n        {\n            ROS_DEBUG(\"[SmaccAsyncClientBehavior] trying to Join onExit function, but it was already finished.\");\n        }\n\n        ROS_DEBUG_STREAM(\"[\" << getName() << \"] Destroying client behavior-  onExit thread finished. Proccedding destruction.\");\n    }\n\n    SmaccAsyncClientBehavior::~SmaccAsyncClientBehavior()\n    {\n    }\n\n    void SmaccAsyncClientBehavior::postSuccessEvent()\n    {\n        postSuccessEventFn_();\n    }\n\n    void SmaccAsyncClientBehavior::postFailureEvent()\n    {\n        postFailureEventFn_();\n    }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_client_behavior.cpp",
    "content": "#include <smacc/smacc_client_behavior.h>\n\nnamespace smacc\n{\n    void SmaccClientBehavior::onEntry()\n    {\n        ROS_DEBUG(\"[%s] Default empty SmaccClientBehavior onEntry\", this->getName().c_str());\n    }\n\n    void SmaccClientBehavior::onExit()\n    {\n        ROS_DEBUG(\"[%s] Default empty SmaccClientBehavior onExit\", this->getName().c_str());\n    }\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_client_behavior_base.cpp",
    "content": "#include <smacc/smacc_client_behavior.h>\n\nnamespace smacc\n{\nISmaccClientBehavior::ISmaccClientBehavior()\n{\n  stateMachine_ = nullptr;\n  currentState = nullptr;\n}\n\nISmaccClientBehavior::~ISmaccClientBehavior()\n{\n  ROS_WARN(\"Client behavior deallocated.\");\n}\n\nstd::string ISmaccClientBehavior::getName() const\n{\n  return demangleSymbol(typeid(*this).name());\n}\n\nvoid ISmaccClientBehavior::runtimeConfigure()\n{\n  ROS_DEBUG(\"[%s] Default empty SmaccClientBehavior runtimeConfigure\", this->getName().c_str());\n}\n\nvoid ISmaccClientBehavior::onEntry(){};\n\nvoid ISmaccClientBehavior::onExit(){};\n\nros::NodeHandle ISmaccClientBehavior::getNode()\n{\n  return this->stateMachine_->getNode();\n}\n\nvoid ISmaccClientBehavior::executeOnEntry()\n{\n  ROS_DEBUG(\"[%s] Default empty SmaccClientBehavior onEntry\", this->getName().c_str());\n  this->onEntry();\n}\n\nvoid ISmaccClientBehavior::executeOnExit()\n{\n  ROS_DEBUG(\"[%s] Default empty SmaccClientBehavior onExit\", this->getName().c_str());\n  this->onExit();\n}\n\nvoid ISmaccClientBehavior::dispose()\n{\n}\n\n}  // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_component.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <smacc/component.h>\n#include <smacc/impl/smacc_component_impl.h>\nnamespace smacc\n{\n\nISmaccComponent::~ISmaccComponent()\n{\n}\n\nISmaccComponent::ISmaccComponent()\n    : owner_(nullptr)\n{\n}\n\nvoid ISmaccComponent::initialize(ISmaccClient *owner)\n{\n    owner_ = owner;\n    this->onInitialize();\n}\n\nvoid ISmaccComponent::onInitialize()\n{\n\n}\n\nvoid ISmaccComponent::setStateMachine(ISmaccStateMachine *stateMachine)\n{\n    stateMachine_ = stateMachine;\n}\n\nstd::string ISmaccComponent::getName() const\n{\n    std::string keyname = demangleSymbol(typeid(*this).name());\n    return keyname;\n}\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_event_generator.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <smacc/smacc_event_generator.h>\n\nnamespace smacc\n{\n\n    SmaccEventGenerator::SmaccEventGenerator()\n    {\n    }\n\n    SmaccEventGenerator::~SmaccEventGenerator()\n    {\n    }\n\n    void SmaccEventGenerator::onEntry()\n    {\n    }\n\n    void SmaccEventGenerator::onExit()\n    {\n    }\n\n    void SmaccEventGenerator::initialize(smacc::ISmaccState *ownerState)\n    {\n        this->ownerState_ = ownerState;\n        this->onInitialized();\n    }\n\n    void SmaccEventGenerator::onInitialized()\n    {\n    }\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_state.cpp",
    "content": "#include <smacc/smacc_state.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\nstd::string ISmaccState::getClassName()\n{\n    return demangleSymbol(typeid(*this).name());\n}\n\nvoid ISmaccState::notifyTransitionFromTransitionTypeInfo(TypeInfo::Ptr &transitionType)\n{\n    ROS_INFO_STREAM(\"NOTIFY TRANSITION: \" << transitionType->getFullName());\n\n    //auto currstateinfo = this->getStateMachine().getCurrentStateInfo();\n    auto currstateinfo = this->stateInfo_;\n\n    if (currstateinfo != nullptr)\n    {\n        //ROS_ERROR_STREAM(\"CURRENT STATE INFO: \" << currstateinfo->fullStateName);\n        for (auto &transition : currstateinfo->transitions_)\n        {\n            std::string transitionCandidateName = transition.transitionTypeInfo->getFullName();\n            //ROS_ERROR_STREAM(\"candidate transition: \" << transitionCandidateName);\n\n            if (transitionType->getFullName() == transitionCandidateName)\n            {\n                this->getStateMachine().publishTransition(transition);\n                return;\n            }\n        }\n\n        // debug information if not found\n        ROS_ERROR_STREAM(\"Transition happened, from current state \" << currstateinfo->getDemangledFullName() << \" but there is not any transitioninfo match available to publish transition: \" << transitionType->getFullName());\n        std::stringstream ss;\n\n        auto stateinfo = currstateinfo;\n\n        for (auto &transition : currstateinfo->transitions_)\n        {\n            std::string transitionCandidateName = transition.transitionTypeInfo->getFullName();\n            ROS_ERROR_STREAM(\"- candidate transition: \" << transitionCandidateName);\n        }\n\n        ROS_ERROR(\"Ancestors candidates: \");\n\n        std::list<const SmaccStateInfo *> ancestors;\n        stateinfo->getAncestors(ancestors);\n\n        for (auto &ancestor : ancestors)\n        {\n            ROS_ERROR_STREAM(\" * Ancestor \" << ancestor->getDemangledFullName() << \":\");\n            for (auto &transition : ancestor->transitions_)\n            {\n                std::string transitionCandidateName = transition.transitionTypeInfo->getFullName();\n                ROS_ERROR_STREAM(\"- candidate transition: \" << transitionCandidateName);\n                if (transitionType->getFullName() == transitionCandidateName)\n                {\n                    ROS_ERROR(\"GOTCHA\");\n                }\n            }\n        }\n    }\n    else\n    {\n        ROS_ERROR_STREAM(\"Transition happened, but current state was not set. Transition candidates:\");\n    }\n}\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_state_info.cpp",
    "content": "#include <smacc/introspection/introspection.h>\n#include <ros/ros.h>\n#include <smacc/common.h>\n\nnamespace smacc\n{\nusing namespace smacc::introspection;\n\nstd::map<const std::type_info *, std::vector<ClientBehaviorInfoEntry>> SmaccStateInfo::staticBehaviorInfo;\nstd::map<const std::type_info *, std::vector<std::shared_ptr<smacc::introspection::SmaccStateReactorInfo>>> SmaccStateInfo::stateReactorsInfo;\nstd::map<const std::type_info *, std::vector<std::shared_ptr<SmaccEventGeneratorInfo>>> SmaccStateInfo::eventGeneratorsInfo;\n\nSmaccStateInfo::SmaccStateInfo(const std::type_info *tid, std::shared_ptr<SmaccStateInfo> parentState, std::shared_ptr<SmaccStateMachineInfo> stateMachineInfo)\n{\n    tid_ = tid;\n    parentState_ = parentState;\n    stateMachine_ = stateMachineInfo;\n\n    if (parentState_ != nullptr)\n        depth_ = parentState->depth_ + 1;\n}\n\nvoid SmaccStateInfo::getAncestors(std::list<const SmaccStateInfo*> &ancestorsList) const\n{\n    ancestorsList.push_front(this);\n    if (parentState_ != nullptr)\n    {\n        this->parentState_->getAncestors(ancestorsList);\n    }\n}\n\nSmaccStateType SmaccStateInfo::getStateLevel()\n{\n    if (this->children_.size() == 0)\n    {\n        if (this->parentState_ != nullptr)\n        {\n            return SmaccStateType::SUPERSTATE_ROUTINE;\n        }\n        else\n        {\n            return SmaccStateType::STATE;\n        }\n    }\n    else\n    {\n        return SmaccStateType::SUPERSTATE;\n    }\n}\n\nstd::string SmaccStateInfo::getFullPath()\n{\n    if (parentState_ == nullptr)\n        return this->toShortName();\n    else\n        return this->parentState_->getFullPath() + \"/\" + this->toShortName();\n}\n\nconst std::string &SmaccStateInfo::toShortName() const\n{\n    return this->demangledStateName;\n}\n\nstd::string SmaccStateInfo::getDemangledFullName() const\n{\n    return demangleSymbol(this->fullStateName.c_str());\n}\n//---------------------------------------------\nSmaccEventInfo::SmaccEventInfo(std::shared_ptr<TypeInfo> eventType)\n{\n    ROS_INFO_STREAM(\"CREATING EVENT INFO: \" << eventType->getFullName());\n\n    this->eventType = eventType;\n}\n\nstd::string SmaccEventInfo::getEventSourceName()\n{\n    if (eventType->templateParameters.size() > 0)\n    {\n        auto eventsourcename = demangleSymbol(eventType->templateParameters[0]->getFullName().c_str());\n        return eventsourcename;\n    }\n    else\n    {\n        return \"\";\n    }\n}\n\nstd::string SmaccEventInfo::getEventTypeName()\n{\n    return demangleSymbol(eventType->getNonTemplatedTypeName().c_str());\n}\n\nstd::string SmaccEventInfo::getOrthogonalName()\n{\n    if (eventType->templateParameters.size() > 1)\n    {\n        return demangleSymbol(eventType->templateParameters[1]->getFullName().c_str());\n    }\n    else\n    {\n        return \"\";\n    }\n}\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_state_machine.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <smacc/smacc_state_machine.h>\n#include <smacc/smacc_signal_detector.h>\n#include <smacc/smacc_orthogonal.h>\n#include <smacc/client_bases/smacc_action_client.h>\n#include <smacc_msgs/SmaccStatus.h>\n#include <smacc_msgs/SmaccTransitionLogEntry.h>\nnamespace smacc\n{\nusing namespace smacc::introspection;\nISmaccStateMachine::ISmaccStateMachine(SignalDetector *signalDetector)\n    : private_nh_(\"~\"), stateSeqCounter_(0)\n{\n    ROS_INFO(\"Creating State Machine Base\");\n    signalDetector_ = signalDetector;\n    signalDetector_->initialize(this);\n\n    std::string runMode;\n    if (nh_.getParam(\"run_mode\", runMode))\n    {\n        if (runMode == \"debug\")\n        {\n            runMode_ = SMRunMode::DEBUG;\n        }\n        else if (runMode == \"release\")\n        {\n            runMode_ = SMRunMode::RELEASE;\n        }\n        else\n        {\n            ROS_ERROR(\"Incorrect run_mode value: %s\", runMode.c_str());\n        }\n    }\n    else\n    {\n        runMode_ = SMRunMode::DEBUG;\n    }\n}\n\nvoid ISmaccStateMachine::disconnectSmaccSignalObject(void *object_ptr)\n{\n    ROS_INFO(\"[SmaccSignals] object signal disconnecting %ld\", (long)object_ptr);\n    if(stateCallbackConnections.count(object_ptr) > 0)\n    {\n        auto callbackSemaphore = stateCallbackConnections[object_ptr];\n        callbackSemaphore->finalize();\n        stateCallbackConnections.erase(object_ptr);\n    }\n    else\n    {\n        ROS_INFO(\"[SmaccSignals] no signals found %ld\", (long)object_ptr);\n    }\n}\n\nISmaccStateMachine::~ISmaccStateMachine()\n{\n    ROS_INFO(\"Finishing State Machine\");\n}\n\nvoid ISmaccStateMachine::reset()\n{\n}\n\nvoid ISmaccStateMachine::stop()\n{\n}\n\nvoid ISmaccStateMachine::eStop()\n{\n}\n\nconst std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> &ISmaccStateMachine::getOrthogonals() const\n{\n    return this->orthogonals_;\n}\n\nvoid ISmaccStateMachine::updateStatusMessage()\n{\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    if (currentStateInfo_ != nullptr)\n    {\n        ROS_WARN_STREAM(\"[StateMachine] setting state active \"\n                        << \": \" << currentStateInfo_->getFullPath());\n\n        if (this->runMode_ == SMRunMode::DEBUG)\n        {\n            status_msg_.current_states.clear();\n            std::list<const SmaccStateInfo *> ancestorList;\n            currentStateInfo_->getAncestors(ancestorList);\n\n            for (auto &ancestor : ancestorList)\n            {\n                status_msg_.current_states.push_back(ancestor->toShortName());\n            }\n\n            status_msg_.global_variable_names.clear();\n            status_msg_.global_variable_values.clear();\n\n            for (auto entry : this->globalData_)\n            {\n                status_msg_.global_variable_names.push_back(entry.first);\n                status_msg_.global_variable_values.push_back(entry.second.first()); // <- invoke to_string()\n            }\n\n            status_msg_.header.stamp = ros::Time::now();\n            status_msg_.header.frame_id = \"odom\";\n            this->stateMachineStatusPub_.publish(status_msg_);\n        }\n    }\n}\n\nvoid ISmaccStateMachine::publishTransition(const SmaccTransitionInfo &transitionInfo)\n{\n    smacc_msgs::SmaccTransitionLogEntry transitionLogEntry;\n    transitionLogEntry.timestamp = ros::Time::now();\n    transitionInfoToMsg(transitionInfo, transitionLogEntry.transition);\n    this->transitionLogHistory_.push_back(transitionLogEntry);\n\n    transitionLogPub_.publish(transitionLogEntry);\n}\n\nvoid ISmaccStateMachine::onInitialize()\n{\n}\n\nvoid ISmaccStateMachine::onInitialized()\n{\n    timer_ = nh_.createTimer(ros::Duration(0.5), &ISmaccStateMachine::state_machine_visualization, this);\n}\n\nvoid ISmaccStateMachine::initializeROS(std::string shortname)\n{\n    ROS_WARN_STREAM(\"State machine base creation:\" << shortname);\n    // STATE MACHINE TOPICS\n    stateMachinePub_ = nh_.advertise<smacc_msgs::SmaccStateMachine>(shortname + \"/smacc/state_machine_description\", 1);\n    stateMachineStatusPub_ = nh_.advertise<smacc_msgs::SmaccStatus>(shortname + \"/smacc/status\", 1);\n    transitionLogPub_ = nh_.advertise<smacc_msgs::SmaccTransitionLogEntry>(shortname + \"/smacc/transition_log\", 1);\n\n    // STATE MACHINE SERVICES\n    transitionHistoryService_ = nh_.advertiseService(shortname + \"/smacc/transition_log_history\", &ISmaccStateMachine::getTransitionLogHistory, this);\n}\n\nbool ISmaccStateMachine::getTransitionLogHistory(smacc_msgs::SmaccGetTransitionHistory::Request &req, smacc_msgs::SmaccGetTransitionHistory::Response &res)\n{\n    ROS_WARN(\"Requesting Transition Log History, current size: %ld\", this->transitionLogHistory_.size());\n    res.history = this->transitionLogHistory_;\n    return true;\n}\n\nvoid ISmaccStateMachine::state_machine_visualization(const ros::TimerEvent &)\n{\n    std::lock_guard<std::recursive_mutex> lock(m_mutex_);\n\n    smacc_msgs::SmaccStateMachine state_machine_msg;\n    state_machine_msg.states = stateMachineInfo_->stateMsgs;\n    this->stateMachinePub_.publish(state_machine_msg);\n\n    status_msg_.header.stamp = ros::Time::now();\n    this->stateMachineStatusPub_.publish(status_msg_);\n}\n\nvoid ISmaccStateMachine::lockStateMachine(std::string msg)\n{\n    ROS_DEBUG(\"locking state machine: %s\", msg.c_str());\n    m_mutex_.lock();\n}\n\nvoid ISmaccStateMachine::unlockStateMachine(std::string msg)\n{\n    ROS_DEBUG(\"unlocking state machine: %s\", msg.c_str());\n    m_mutex_.unlock();\n}\n\nstd::string ISmaccStateMachine::getStateMachineName()\n{\n    return demangleSymbol(typeid(*this).name());\n}\n\nvoid ISmaccStateMachine::checkStateMachineConsistence()\n{\n    // transition from an orthogonal that doesn’t exist.\n    // transition from a source that doesn’t exist.\n\n    // std::stringstream errorbuffer;\n    // bool errorFound = false;\n\n    // for (auto &stentry : this->stateMachineInfo_->states)\n    // {\n    //     auto stinfo = stentry.second;\n\n    //     for (auto &transition : stinfo->transitions_)\n    //     {\n    //         auto evinfo = transition.eventInfo;\n    //         bool found = false;\n    //         for (auto &orthogonal : orthogonals_)\n    //         {\n    //             if (orthogonal.first == evinfo->getOrthogonalName())\n    //             {\n    //                 found = true;\n    //                 break;\n    //             }\n    //         }\n\n    //         if (!found)\n    //         {\n    //             errorbuffer << \"---------\" << std::endl\n    //                         << \"[Consistency Checking] Transition event refers not existing orthogonal.\" << std::endl\n    //                         << \"State: \" << demangleType(*stinfo->tid_) << std::endl\n    //                         << \"Transition: \" << transition.transitionTypeInfo->getFullName() << std::endl\n    //                         << \"Orthogonal: \" << evinfo->getOrthogonalName() << std::endl\n    //                         << \"---------\" << std::endl;\n\n    //             errorFound = true;\n    //         }\n    //         //std::string getEventSourceName();\n    //         //std::string getOrthogonalName();\n    //     }\n    // }\n\n    // if (errorFound)\n    // {\n    //     ROS_WARN_STREAM(\"== STATE MACHINE CONSISTENCY CHECK: ==\" << std::endl\n    //                                                              << errorbuffer.str() << std::endl\n    //                                                              << \"=================\");\n    // }\n    // cb from a client that doesn’t exist – don’t worry about making clients dynamically.\n}\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_state_machine_info.cpp",
    "content": "#include <smacc/introspection/introspection.h>\n#include <smacc/smacc_state_machine.h>\n\nnamespace smacc\n{\n    void SmaccStateMachineInfo::assembleSMStructureMessage(ISmaccStateMachine *sm)\n    {\n        ROS_INFO(\"----------- PRINT STATE MACHINE STRUCTURE -------------------\");\n        stateMsgs.clear();\n        for (auto &val : this->states)\n        {\n            smacc_msgs::SmaccState stateMsg;\n            auto state = val.second;\n            stateMsg.index = state->stateIndex_;\n\n            std::stringstream ss;\n            ss << \"**** State: \" << demangleSymbol(val.first.c_str()) << std::endl;\n\n            stateMsg.name = state->getDemangledFullName();\n            stateMsg.level = (int)state->getStateLevel();\n\n            ss << \"**** State: \" << stateMsg.name << std::endl;\n\n            ss << \"Index: \" << stateMsg.index << std::endl;\n            ss << \"StateLevel: \" << stateMsg.level << std::endl;\n\n            ss << \" Childstates:\" << std::endl;\n\n            for (auto &child : state->children_)\n            {\n                auto childStateName = child->getDemangledFullName();\n                stateMsg.children_states.push_back(childStateName);\n\n                ss << \" - \" << childStateName << std::endl;\n            }\n\n            ss << \" Transitions:\" << std::endl;\n\n            for (auto &transition : state->transitions_)\n            {\n                smacc_msgs::SmaccTransition transitionMsg;\n\n                transitionInfoToMsg(transition, transitionMsg);\n\n                ss << \" - Transition.  \" << std::endl;\n                ss << \"      - Index: \" << transitionMsg.index << std::endl;\n                ss << \"      - Transition Name: \" << transitionMsg.transition_name << std::endl;\n                ss << \"      - Transition Type: \" << transitionMsg.transition_type << std::endl;\n                ss << \"      - Event Type :\" << transitionMsg.event.event_type << std::endl;\n                ss << \"      - Event Source: \" << transitionMsg.event.event_source << std::endl;\n                ss << \"      - Event ObjectTag: \" << transitionMsg.event.event_object_tag << std::endl;\n                ss << \"      - Event Label: \" << transitionMsg.event.label << std::endl;\n                ss << \"      - Destiny State: \" << transitionMsg.destiny_state_name << std::endl;\n                ss << \"      - Owner State: \" << transitionMsg.destiny_state_name << std::endl;\n                ss << \"      - Is History Node: \" << std::to_string(transitionMsg.history_node) << std::endl;\n                ss << \"      - TransitionC++Type: \" << transition.transitionTypeInfo->getFullName() << std::endl;\n                ss << \"      - EventC++Type: \" << transition.eventInfo->eventType->getFullName() << std::endl;\n\n                stateMsg.transitions.push_back(transitionMsg);\n            }\n\n            const std::type_info *statetid = state->tid_;\n\n            std::map<const std::type_info *, std::vector<smacc::ClientBehaviorInfoEntry *>> smaccBehaviorInfoMappingByOrthogonalType;\n\n            ss << \" Orthogonals:\" << std::endl;\n            if (SmaccStateInfo::staticBehaviorInfo.count(statetid) > 0)\n            {\n                for (auto &bhinfo : SmaccStateInfo::staticBehaviorInfo[statetid])\n                {\n                    if (smaccBehaviorInfoMappingByOrthogonalType.count(bhinfo.orthogonalType) == 0)\n                    {\n                        smaccBehaviorInfoMappingByOrthogonalType[bhinfo.orthogonalType] = std::vector<smacc::ClientBehaviorInfoEntry *>();\n                    }\n\n                    smaccBehaviorInfoMappingByOrthogonalType[bhinfo.orthogonalType].push_back(&bhinfo);\n                }\n            }\n\n            auto &runtimeOrthogonals = sm->getOrthogonals();\n\n            for (auto &orthogonal : runtimeOrthogonals)\n            {\n                smacc_msgs::SmaccOrthogonal orthogonalMsg;\n\n                const auto *orthogonaltid = &typeid(*(orthogonal.second));\n                orthogonalMsg.name = demangleSymbol(orthogonaltid->name());\n\n                ss << \" - orthogonal: \" << orthogonalMsg.name << std::endl;\n\n                if (smaccBehaviorInfoMappingByOrthogonalType[orthogonaltid].size() > 0)\n                {\n                    auto &behaviors = smaccBehaviorInfoMappingByOrthogonalType[orthogonaltid];\n                    for (auto &bhinfo : behaviors)\n                    {\n                        auto ClientBehaviorName = demangleSymbol(bhinfo->behaviorType->name());\n                        orthogonalMsg.client_behavior_names.push_back(ClientBehaviorName);\n                        ss << \"          - client behavior: \" << ClientBehaviorName << std::endl;\n                    }\n                }\n                else\n                {\n                    ss << \"          - NO Client BEHAVIORS -\" << std::endl;\n                }\n\n                auto &clients = orthogonal.second->getClients();\n                if (clients.size() > 0)\n                {\n                    for (auto &client : clients)\n                    {\n                        auto clientTid = client->getType();\n                        auto clientName = clientTid->getNonTemplatedTypeName();\n                        orthogonalMsg.client_names.push_back(clientName);\n                        ss << \"          - client: \" << clientName << std::endl;\n                    }\n                }\n                else\n                {\n                    ss << \"          - NO CLIENTS - \" << std::endl;\n                }\n                stateMsg.orthogonals.push_back(orthogonalMsg);\n            }\n\n            ss << \" State event generators:\" << std::endl;\n            if (SmaccStateInfo::eventGeneratorsInfo.count(statetid) > 0)\n            {\n                int k = 0;\n                for (auto &eginfo : SmaccStateInfo::eventGeneratorsInfo[statetid])\n                {\n                    smacc_msgs::SmaccEventGenerator eventGeneratorMsg;\n                    eventGeneratorMsg.index = k++;\n                    eventGeneratorMsg.type_name = demangleSymbol(eginfo->eventGeneratorType->name());\n\n                    ss << \" - event generator: \" << eventGeneratorMsg.type_name << std::endl;\n                    if (eginfo->objectTagType != nullptr)\n                    {\n                        eventGeneratorMsg.object_tag = eginfo->objectTagType->getFullName();\n                        ss << \"        - object tag: \" << eventGeneratorMsg.object_tag << std::endl;\n                    }\n                    stateMsg.event_generators.push_back(eventGeneratorMsg);\n                }\n            }\n\n            ss << \" State reactors:\" << std::endl;\n            if (SmaccStateInfo::stateReactorsInfo.count(statetid) > 0)\n            {\n                int k = 0;\n                for (auto &srinfo : SmaccStateInfo::stateReactorsInfo[statetid])\n                {\n                    smacc_msgs::SmaccStateReactor stateReactorMsg;\n                    stateReactorMsg.index = k++;\n                    stateReactorMsg.type_name = demangleSymbol(srinfo->stateReactorType->name());\n\n                    ss << \" - state reactor: \" << stateReactorMsg.type_name << std::endl;\n                    if (srinfo->objectTagType != nullptr)\n                    {\n                        stateReactorMsg.object_tag = srinfo->objectTagType->getFullName();\n                        ss << \"        - object tag: \" << stateReactorMsg.object_tag << std::endl;\n                    }\n\n                    for (auto &tev : srinfo->sourceEventTypes)\n                    {\n                        // WE SHOULD CREATE A SMACC_EVENT_INFO TYPE, also using in typewalker transition\n                        auto eventTypeName = tev->getEventTypeName();\n                        smacc_msgs::SmaccEvent event;\n\n                        ss << \"             - triggering event: \" << tev->getEventTypeName() << std::endl;\n                        event.event_type = eventTypeName;\n\n                        event.event_source = tev->getEventSourceName();\n                        ss << \"                 - source type: \" << event.event_source << std::endl;\n\n                        event.event_object_tag = tev->getOrthogonalName();\n                        ss << \"                 - source object: \" << event.event_object_tag << std::endl;\n\n                        event.label = tev->label;\n                        ss << \"                 - event label: \" << event.label << std::endl;\n\n                        stateReactorMsg.event_sources.push_back(event);\n                    }\n\n                    stateMsg.state_reactors.push_back(stateReactorMsg);\n                }\n            }\n            else\n            {\n                ss << \"- NO STATE REACTORS - \" << std::endl;\n            }\n\n            ROS_INFO_STREAM(ss.str());\n            stateMsgs.push_back(stateMsg);\n        }\n\n        std::sort(stateMsgs.begin(), stateMsgs.end(), [](auto &a, auto &b) {\n            return a.index > b.index;\n        });\n    }\n} // namespace smacc\n"
  },
  {
    "path": "smacc/src/smacc/smacc_updatable.cpp",
    "content": "#include <smacc/smacc_updatable.h>\n\nnamespace smacc\n{\n\nISmaccUpdatable::ISmaccUpdatable()\n    : lastUpdate_(0)\n{\n}\n\nISmaccUpdatable::ISmaccUpdatable(ros::Duration duration)\n    : lastUpdate_(0),\n      periodDuration_(duration)\n{\n}\n\nvoid ISmaccUpdatable::setUpdatePeriod(ros::Duration duration)\n{\n    periodDuration_ = duration;\n}\n\nvoid ISmaccUpdatable::executeUpdate()\n{\n    bool update = true;\n    if (periodDuration_)\n    {\n        auto now = ros::Time::now();\n        auto elapsed = now - this->lastUpdate_;\n        update = elapsed > *periodDuration_;\n        if(update)\n        {\n            this->lastUpdate_ = now;\n        }\n    }\n\n    if (update)\n    {\n        this->update();\n    }\n}\n}\n"
  },
  {
    "path": "smacc/src/smacc/state_reactor.cpp",
    "content": "#include <smacc/smacc_state_reactor.h>\n#include <ros/ros.h>\n\nnamespace smacc\n{\n\nStateReactor::StateReactor()\n{\n}\n\nvoid StateReactor::initialize(smacc::ISmaccState *ownerState)\n{\n    this->ownerState = ownerState;\n    this->onInitialized();\n}\n\nvoid StateReactor::onInitialized()\n{\n}\n\nvoid StateReactor::onEventNotified(const std::type_info *eventType)\n{\n}\n\nvoid StateReactor::onEntry()\n{\n\n}\n\nvoid StateReactor::onExit()\n{\n\n}\n\nvoid StateReactor::update()\n{\n    if (this->triggers())\n    {\n        ROS_INFO(\"State reactor base REALLY TRIGGERS!!\");\n        this->postEventFn();\n    }\n}\n\nnamespace introspection\n{\nvoid StateReactorHandler::configureStateReactor(std::shared_ptr<smacc::StateReactor> sb)\n{\n    for (auto callback : this->callbacks_)\n    {\n        callback.fn(sb);\n    }\n}\n\nvoid EventGeneratorHandler::configureEventGenerator(std::shared_ptr<smacc::SmaccEventGenerator> eg)\n{\n    for (auto callback : this->callbacks_)\n    {\n        callback.fn(eg);\n    }\n}\n} // namespace introspection\n} // namespace smacc\n"
  },
  {
    "path": "smacc/test/type_info_unit_test.cpp",
    "content": "// Bring in my package's API, which is what I'm testing\n#include <smacc/introspection/string_type_walker.h>\n// Bring in gtest\n#include <gtest/gtest.h>\n\nusing namespace smacc::introspection;\n\n// Declare a test\nTEST(TestSuite, testCase2)\n{\n  auto t = TypeInfo::getTypeInfoFromString(\"u0<u1,u2,u3,u4,u5,u6,u7,u8,u9>\");\n\n  ASSERT_EQ(t->templateParameters.size(), 9);\n}\n\nTEST(TestSuite, testCase1)\n{\n  std::stringstream buffer;\n\n  // Save cout's buffer here\n  std::streambuf *sbuf = std::cout.rdbuf();\n\n  // Redirect cout to our stringstream buffer or any other ostream\n  std::cout.rdbuf(buffer.rdbuf());\n  // Use cout as usual\n  std::cout.rdbuf(sbuf);\n\n  auto t = TypeInfo::getTypeInfoFromString(\"u0<u1,u2,u3,u4,u5,u6,u7,u8,u9,u10, u11<u12,u13>>\");\n\n  ASSERT_EQ(t->templateParameters.size(), 11);\n\n  // When done redirect cout to its old self\n\n  ASSERT_EQ(t->templateParameters[10]->templateParameters.size(), 2);\n}\n\n// Run all the tests that were declared with TEST()\nint main(int argc, char **argv)\n{\n  testing::InitGoogleTest(&argc, argv);\n  //ros::init(argc, argv, \"tester\");\n  //ros::NodeHandle nh;\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "smacc_ci/.gitignore",
    "content": "token_file.json\n"
  },
  {
    "path": "smacc_ci/Doxyfile",
    "content": "# Doxyfile 1.8.11\n\n# This file describes the settings to be used by the documentation system\n# doxygen (www.doxygen.org) for a project.\n#\n# All text after a double hash (##) is considered a comment and is placed in\n# front of the TAG it is preceding.\n#\n# All text after a single hash (#) is considered a comment and will be ignored.\n# The format is:\n# TAG = value [value, ...]\n# For lists, items can also be appended using:\n# TAG += value [value, ...]\n# Values that contain spaces should be placed between quotes (\\\" \\\").\n\n#---------------------------------------------------------------------------\n# Project related configuration options\n#---------------------------------------------------------------------------\n\n# This tag specifies the encoding used for all characters in the config file\n# that follow. The default is UTF-8 which is also the encoding used for all text\n# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv\n# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv\n# for the list of possible encodings.\n# The default value is: UTF-8.\n\nDOXYFILE_ENCODING      = UTF-8\n\n# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by\n# double-quotes, unless you are using Doxywizard) that should identify the\n# project for which the documentation is generated. This name is used in the\n# title of most generated pages and in a few other places.\n# The default value is: My Project.\n\nPROJECT_NAME           = \"SMACC\"\n\n# The PROJECT_NUMBER tag can be used to enter a project or revision number. This\n# could be handy for archiving the generated documentation or if some version\n# control system is used.\n\nPROJECT_NUMBER         =\n\n# Using the PROJECT_BRIEF tag one can provide an optional one line description\n# for a project that appears at the top of each page and should give viewer a\n# quick idea about the purpose of the project. Keep the description short.\n\nPROJECT_BRIEF          =\n\n# With the PROJECT_LOGO tag one can specify a logo or an icon that is included\n# in the documentation. The maximum height of the logo should not exceed 55\n# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy\n# the logo to the output directory.\n\nPROJECT_LOGO           =\n\n# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path\n# into which the generated documentation will be written. If a relative path is\n# entered, it will be relative to the location where doxygen was started. If\n# left blank the current directory will be used.\n\nOUTPUT_DIRECTORY       = docs/\n\n# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub-\n# directories (in 2 levels) under the output directory of each output format and\n# will distribute the generated files over these directories. Enabling this\n# option can be useful when feeding doxygen a huge amount of source files, where\n# putting all generated files in the same directory would otherwise causes\n# performance problems for the file system.\n# The default value is: NO.\n\nCREATE_SUBDIRS         = NO\n\n# If the ALLOW_UNICODE_NAMES tag is set to YES, doxygen will allow non-ASCII\n# characters to appear in the names of generated files. If set to NO, non-ASCII\n# characters will be escaped, for example _xE3_x81_x84 will be used for Unicode\n# U+3044.\n# The default value is: NO.\n\nALLOW_UNICODE_NAMES    = NO\n\n# The OUTPUT_LANGUAGE tag is used to specify the language in which all\n# documentation generated by doxygen is written. Doxygen will use this\n# information to generate all constant output in the proper language.\n# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese,\n# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States),\n# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian,\n# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages),\n# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian,\n# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian,\n# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish,\n# Ukrainian and Vietnamese.\n# The default value is: English.\n\nOUTPUT_LANGUAGE        = English\n\n# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member\n# descriptions after the members that are listed in the file and class\n# documentation (similar to Javadoc). Set to NO to disable this.\n# The default value is: YES.\n\nBRIEF_MEMBER_DESC      = YES\n\n# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief\n# description of a member or function before the detailed description\n#\n# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the\n# brief descriptions will be completely suppressed.\n# The default value is: YES.\n\nREPEAT_BRIEF           = YES\n\n# This tag implements a quasi-intelligent brief description abbreviator that is\n# used to form the text in various listings. Each string in this list, if found\n# as the leading text of the brief description, will be stripped from the text\n# and the result, after processing the whole list, is used as the annotated\n# text. Otherwise, the brief description is used as-is. If left blank, the\n# following values are used ($name is automatically replaced with the name of\n# the entity):The $name class, The $name widget, The $name file, is, provides,\n# specifies, contains, represents, a, an and the.\n\nABBREVIATE_BRIEF       =\n\n# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then\n# doxygen will generate a detailed section even if there is only a brief\n# description.\n# The default value is: NO.\n\nALWAYS_DETAILED_SEC    = NO\n\n# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all\n# inherited members of a class in the documentation of that class as if those\n# members were ordinary class members. Constructors, destructors and assignment\n# operators of the base classes will not be shown.\n# The default value is: NO.\n\nINLINE_INHERITED_MEMB  = NO\n\n# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path\n# before files name in the file list and in the header files. If set to NO the\n# shortest path that makes the file name unique will be used\n# The default value is: YES.\n\nFULL_PATH_NAMES        = YES\n\n# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path.\n# Stripping is only done if one of the specified strings matches the left-hand\n# part of the path. The tag can be used to show relative paths in the file list.\n# If left blank the directory from which doxygen is run is used as the path to\n# strip.\n#\n# Note that you can specify absolute paths here, but also relative paths, which\n# will be relative from the directory where doxygen is started.\n# This tag requires that the tag FULL_PATH_NAMES is set to YES.\n\nSTRIP_FROM_PATH        =\n\n# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the\n# path mentioned in the documentation of a class, which tells the reader which\n# header file to include in order to use a class. If left blank only the name of\n# the header file containing the class definition is used. Otherwise one should\n# specify the list of include paths that are normally passed to the compiler\n# using the -I flag.\n\nSTRIP_FROM_INC_PATH    =\n\n# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but\n# less readable) file names. This can be useful is your file systems doesn't\n# support long names like on DOS, Mac, or CD-ROM.\n# The default value is: NO.\n\nSHORT_NAMES            = NO\n\n# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the\n# first line (until the first dot) of a Javadoc-style comment as the brief\n# description. If set to NO, the Javadoc-style will behave just like regular Qt-\n# style comments (thus requiring an explicit @brief command for a brief\n# description.)\n# The default value is: NO.\n\nJAVADOC_AUTOBRIEF      = NO\n\n# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first\n# line (until the first dot) of a Qt-style comment as the brief description. If\n# set to NO, the Qt-style will behave just like regular Qt-style comments (thus\n# requiring an explicit \\brief command for a brief description.)\n# The default value is: NO.\n\nQT_AUTOBRIEF           = NO\n\n# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a\n# multi-line C++ special comment block (i.e. a block of //! or /// comments) as\n# a brief description. This used to be the default behavior. The new default is\n# to treat a multi-line C++ comment block as a detailed description. Set this\n# tag to YES if you prefer the old behavior instead.\n#\n# Note that setting this tag to YES also means that rational rose comments are\n# not recognized any more.\n# The default value is: NO.\n\nMULTILINE_CPP_IS_BRIEF = NO\n\n# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the\n# documentation from any documented member that it re-implements.\n# The default value is: YES.\n\nINHERIT_DOCS           = YES\n\n# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new\n# page for each member. If set to NO, the documentation of a member will be part\n# of the file/class/namespace that contains it.\n# The default value is: NO.\n\nSEPARATE_MEMBER_PAGES  = NO\n\n# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen\n# uses this value to replace tabs by spaces in code fragments.\n# Minimum value: 1, maximum value: 16, default value: 4.\n\nTAB_SIZE               = 4\n\n# This tag can be used to specify a number of aliases that act as commands in\n# the documentation. An alias has the form:\n# name=value\n# For example adding\n# \"sideeffect=@par Side Effects:\\n\"\n# will allow you to put the command \\sideeffect (or @sideeffect) in the\n# documentation, which will result in a user-defined paragraph with heading\n# \"Side Effects:\". You can put \\n's in the value part of an alias to insert\n# newlines.\n\nALIASES                =\n\n# This tag can be used to specify a number of word-keyword mappings (TCL only).\n# A mapping has the form \"name=value\". For example adding \"class=itcl::class\"\n# will allow you to use the command class in the itcl::class meaning.\n\nTCL_SUBST              =\n\n# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources\n# only. Doxygen will then generate output that is more tailored for C. For\n# instance, some of the names that are used will be different. The list of all\n# members will be omitted, etc.\n# The default value is: NO.\n\nOPTIMIZE_OUTPUT_FOR_C  = NO\n\n# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or\n# Python sources only. Doxygen will then generate output that is more tailored\n# for that language. For instance, namespaces will be presented as packages,\n# qualified scopes will look different, etc.\n# The default value is: NO.\n\nOPTIMIZE_OUTPUT_JAVA   = NO\n\n# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran\n# sources. Doxygen will then generate output that is tailored for Fortran.\n# The default value is: NO.\n\nOPTIMIZE_FOR_FORTRAN   = NO\n\n# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL\n# sources. Doxygen will then generate output that is tailored for VHDL.\n# The default value is: NO.\n\nOPTIMIZE_OUTPUT_VHDL   = NO\n\n# Doxygen selects the parser to use depending on the extension of the files it\n# parses. With this tag you can assign which parser to use for a given\n# extension. Doxygen has a built-in mapping, but you can override or extend it\n# using this tag. The format is ext=language, where ext is a file extension, and\n# language is one of the parsers supported by doxygen: IDL, Java, Javascript,\n# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran:\n# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran:\n# Fortran. In the later case the parser tries to guess whether the code is fixed\n# or free formatted code, this is the default for Fortran type files), VHDL. For\n# instance to make doxygen treat .inc files as Fortran files (default is PHP),\n# and .f files as C (default is Fortran), use: inc=Fortran f=C.\n#\n# Note: For files without extension you can use no_extension as a placeholder.\n#\n# Note that for custom extensions you also need to set FILE_PATTERNS otherwise\n# the files are not read by doxygen.\n\nEXTENSION_MAPPING      =\n\n# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments\n# according to the Markdown format, which allows for more readable\n# documentation. See http://daringfireball.net/projects/markdown/ for details.\n# The output of markdown processing is further processed by doxygen, so you can\n# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in\n# case of backward compatibilities issues.\n# The default value is: YES.\n\nMARKDOWN_SUPPORT       = YES\n\n# When enabled doxygen tries to link words that correspond to documented\n# classes, or namespaces to their corresponding documentation. Such a link can\n# be prevented in individual cases by putting a % sign in front of the word or\n# globally by setting AUTOLINK_SUPPORT to NO.\n# The default value is: YES.\n\nAUTOLINK_SUPPORT       = YES\n\n# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want\n# to include (a tag file for) the STL sources as input, then you should set this\n# tag to YES in order to let doxygen match functions declarations and\n# definitions whose arguments contain STL classes (e.g. func(std::string);\n# versus func(std::string) {}). This also make the inheritance and collaboration\n# diagrams that involve STL classes more complete and accurate.\n# The default value is: NO.\n\nBUILTIN_STL_SUPPORT    = NO\n\n# If you use Microsoft's C++/CLI language, you should set this option to YES to\n# enable parsing support.\n# The default value is: NO.\n\nCPP_CLI_SUPPORT        = NO\n\n# Set the SIP_SUPPORT tag to YES if your project consists of sip (see:\n# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen\n# will parse them like normal C++ but will assume all classes use public instead\n# of private inheritance when no explicit protection keyword is present.\n# The default value is: NO.\n\nSIP_SUPPORT            = NO\n\n# For Microsoft's IDL there are propget and propput attributes to indicate\n# getter and setter methods for a property. Setting this option to YES will make\n# doxygen to replace the get and set methods by a property in the documentation.\n# This will only work if the methods are indeed getting or setting a simple\n# type. If this is not the case, or you want to show the methods anyway, you\n# should set this option to NO.\n# The default value is: YES.\n\nIDL_PROPERTY_SUPPORT   = YES\n\n# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC\n# tag is set to YES then doxygen will reuse the documentation of the first\n# member in the group (if any) for the other members of the group. By default\n# all members of a group must be documented explicitly.\n# The default value is: NO.\n\nDISTRIBUTE_GROUP_DOC   = NO\n\n# If one adds a struct or class to a group and this option is enabled, then also\n# any nested class or struct is added to the same group. By default this option\n# is disabled and one has to add nested compounds explicitly via \\ingroup.\n# The default value is: NO.\n\nGROUP_NESTED_COMPOUNDS = NO\n\n# Set the SUBGROUPING tag to YES to allow class member groups of the same type\n# (for instance a group of public functions) to be put as a subgroup of that\n# type (e.g. under the Public Functions section). Set it to NO to prevent\n# subgrouping. Alternatively, this can be done per class using the\n# \\nosubgrouping command.\n# The default value is: YES.\n\nSUBGROUPING            = YES\n\n# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions\n# are shown inside the group in which they are included (e.g. using \\ingroup)\n# instead of on a separate page (for HTML and Man pages) or section (for LaTeX\n# and RTF).\n#\n# Note that this feature does not work in combination with\n# SEPARATE_MEMBER_PAGES.\n# The default value is: NO.\n\nINLINE_GROUPED_CLASSES = NO\n\n# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions\n# with only public data fields or simple typedef fields will be shown inline in\n# the documentation of the scope in which they are defined (i.e. file,\n# namespace, or group documentation), provided this scope is documented. If set\n# to NO, structs, classes, and unions are shown on a separate page (for HTML and\n# Man pages) or section (for LaTeX and RTF).\n# The default value is: NO.\n\nINLINE_SIMPLE_STRUCTS  = NO\n\n# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or\n# enum is documented as struct, union, or enum with the name of the typedef. So\n# typedef struct TypeS {} TypeT, will appear in the documentation as a struct\n# with name TypeT. When disabled the typedef will appear as a member of a file,\n# namespace, or class. And the struct will be named TypeS. This can typically be\n# useful for C code in case the coding convention dictates that all compound\n# types are typedef'ed and only the typedef is referenced, never the tag name.\n# The default value is: NO.\n\nTYPEDEF_HIDES_STRUCT   = NO\n\n# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This\n# cache is used to resolve symbols given their name and scope. Since this can be\n# an expensive process and often the same symbol appears multiple times in the\n# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small\n# doxygen will become slower. If the cache is too large, memory is wasted. The\n# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range\n# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536\n# symbols. At the end of a run doxygen will report the cache usage and suggest\n# the optimal cache size from a speed point of view.\n# Minimum value: 0, maximum value: 9, default value: 0.\n\nLOOKUP_CACHE_SIZE      = 0\n\n#---------------------------------------------------------------------------\n# Build related configuration options\n#---------------------------------------------------------------------------\n\n# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in\n# documentation are documented, even if no documentation was available. Private\n# class members and static file members will be hidden unless the\n# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES.\n# Note: This will also disable the warnings about undocumented members that are\n# normally produced when WARNINGS is set to YES.\n# The default value is: NO.\n\nEXTRACT_ALL            = YES\n\n# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will\n# be included in the documentation.\n# The default value is: NO.\n\nEXTRACT_PRIVATE        = YES\n\n# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal\n# scope will be included in the documentation.\n# The default value is: NO.\n\nEXTRACT_PACKAGE        = YES\n\n# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be\n# included in the documentation.\n# The default value is: NO.\n\nEXTRACT_STATIC         = YES\n\n# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined\n# locally in source files will be included in the documentation. If set to NO,\n# only classes defined in header files are included. Does not have any effect\n# for Java sources.\n# The default value is: YES.\n\nEXTRACT_LOCAL_CLASSES  = YES\n\n# This flag is only useful for Objective-C code. If set to YES, local methods,\n# which are defined in the implementation section but not in the interface are\n# included in the documentation. If set to NO, only methods in the interface are\n# included.\n# The default value is: NO.\n\nEXTRACT_LOCAL_METHODS  = YES\n\n# If this flag is set to YES, the members of anonymous namespaces will be\n# extracted and appear in the documentation as a namespace called\n# 'anonymous_namespace{file}', where file will be replaced with the base name of\n# the file that contains the anonymous namespace. By default anonymous namespace\n# are hidden.\n# The default value is: NO.\n\nEXTRACT_ANON_NSPACES   = YES\n\n# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all\n# undocumented members inside documented classes or files. If set to NO these\n# members will be included in the various overviews, but no documentation\n# section is generated. This option has no effect if EXTRACT_ALL is enabled.\n# The default value is: NO.\n\nHIDE_UNDOC_MEMBERS     = NO\n\n# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all\n# undocumented classes that are normally visible in the class hierarchy. If set\n# to NO, these classes will be included in the various overviews. This option\n# has no effect if EXTRACT_ALL is enabled.\n# The default value is: NO.\n\nHIDE_UNDOC_CLASSES     = NO\n\n# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend\n# (class|struct|union) declarations. If set to NO, these declarations will be\n# included in the documentation.\n# The default value is: NO.\n\nHIDE_FRIEND_COMPOUNDS  = NO\n\n# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any\n# documentation blocks found inside the body of a function. If set to NO, these\n# blocks will be appended to the function's detailed documentation block.\n# The default value is: NO.\n\nHIDE_IN_BODY_DOCS      = NO\n\n# The INTERNAL_DOCS tag determines if documentation that is typed after a\n# \\internal command is included. If the tag is set to NO then the documentation\n# will be excluded. Set it to YES to include the internal documentation.\n# The default value is: NO.\n\nINTERNAL_DOCS          = NO\n\n# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file\n# names in lower-case letters. If set to YES, upper-case letters are also\n# allowed. This is useful if you have classes or files whose names only differ\n# in case and if your file system supports case sensitive file names. Windows\n# and Mac users are advised to set this option to NO.\n# The default value is: system dependent.\n\nCASE_SENSE_NAMES       = YES\n\n# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with\n# their full class and namespace scopes in the documentation. If set to YES, the\n# scope will be hidden.\n# The default value is: NO.\n\nHIDE_SCOPE_NAMES       = NO\n\n# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will\n# append additional text to a page's title, such as Class Reference. If set to\n# YES the compound reference will be hidden.\n# The default value is: NO.\n\nHIDE_COMPOUND_REFERENCE= NO\n\n# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of\n# the files that are included by a file in the documentation of that file.\n# The default value is: YES.\n\nSHOW_INCLUDE_FILES     = YES\n\n# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each\n# grouped member an include statement to the documentation, telling the reader\n# which file to include in order to use the member.\n# The default value is: NO.\n\nSHOW_GROUPED_MEMB_INC  = NO\n\n# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include\n# files with double quotes in the documentation rather than with sharp brackets.\n# The default value is: NO.\n\nFORCE_LOCAL_INCLUDES   = NO\n\n# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the\n# documentation for inline members.\n# The default value is: YES.\n\nINLINE_INFO            = YES\n\n# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the\n# (detailed) documentation of file and class members alphabetically by member\n# name. If set to NO, the members will appear in declaration order.\n# The default value is: YES.\n\nSORT_MEMBER_DOCS       = YES\n\n# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief\n# descriptions of file, namespace and class members alphabetically by member\n# name. If set to NO, the members will appear in declaration order. Note that\n# this will also influence the order of the classes in the class list.\n# The default value is: NO.\n\nSORT_BRIEF_DOCS        = NO\n\n# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the\n# (brief and detailed) documentation of class members so that constructors and\n# destructors are listed first. If set to NO the constructors will appear in the\n# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS.\n# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief\n# member documentation.\n# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting\n# detailed member documentation.\n# The default value is: NO.\n\nSORT_MEMBERS_CTORS_1ST = NO\n\n# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy\n# of group names into alphabetical order. If set to NO the group names will\n# appear in their defined order.\n# The default value is: NO.\n\nSORT_GROUP_NAMES       = NO\n\n# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by\n# fully-qualified names, including namespaces. If set to NO, the class list will\n# be sorted only by class name, not including the namespace part.\n# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES.\n# Note: This option applies only to the class list, not to the alphabetical\n# list.\n# The default value is: NO.\n\nSORT_BY_SCOPE_NAME     = NO\n\n# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper\n# type resolution of all parameters of a function it will reject a match between\n# the prototype and the implementation of a member function even if there is\n# only one candidate or it is obvious which candidate to choose by doing a\n# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still\n# accept a match between prototype and implementation in such cases.\n# The default value is: NO.\n\nSTRICT_PROTO_MATCHING  = NO\n\n# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo\n# list. This list is created by putting \\todo commands in the documentation.\n# The default value is: YES.\n\nGENERATE_TODOLIST      = YES\n\n# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test\n# list. This list is created by putting \\test commands in the documentation.\n# The default value is: YES.\n\nGENERATE_TESTLIST      = YES\n\n# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug\n# list. This list is created by putting \\bug commands in the documentation.\n# The default value is: YES.\n\nGENERATE_BUGLIST       = YES\n\n# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO)\n# the deprecated list. This list is created by putting \\deprecated commands in\n# the documentation.\n# The default value is: YES.\n\nGENERATE_DEPRECATEDLIST= YES\n\n# The ENABLED_SECTIONS tag can be used to enable sr_conditional documentation\n# sections, marked by \\if <section_label> ... \\endif and \\cond <section_label>\n# ... \\endcond blocks.\n\nENABLED_SECTIONS       =\n\n# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the\n# initial value of a variable or macro / define can have for it to appear in the\n# documentation. If the initializer consists of more lines than specified here\n# it will be hidden. Use a value of 0 to hide initializers completely. The\n# appearance of the value of individual variables and macros / defines can be\n# controlled using \\showinitializer or \\hideinitializer command in the\n# documentation regardless of this setting.\n# Minimum value: 0, maximum value: 10000, default value: 30.\n\nMAX_INITIALIZER_LINES  = 30\n\n# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at\n# the bottom of the documentation of classes and structs. If set to YES, the\n# list will mention the files that were used to generate the documentation.\n# The default value is: YES.\n\nSHOW_USED_FILES        = YES\n\n# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This\n# will remove the Files entry from the Quick Index and from the Folder Tree View\n# (if specified).\n# The default value is: YES.\n\nSHOW_FILES             = YES\n\n# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces\n# page. This will remove the Namespaces entry from the Quick Index and from the\n# Folder Tree View (if specified).\n# The default value is: YES.\n\nSHOW_NAMESPACES        = YES\n\n# The FILE_VERSION_FILTER tag can be used to specify a program or script that\n# doxygen should invoke to get the current version for each file (typically from\n# the version control system). Doxygen will invoke the program by executing (via\n# popen()) the command command input-file, where command is the value of the\n# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided\n# by doxygen. Whatever the program writes to standard output is used as the file\n# version. For an example see the documentation.\n\nFILE_VERSION_FILTER    =\n\n# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed\n# by doxygen. The layout file controls the global structure of the generated\n# output files in an output format independent way. To create the layout file\n# that represents doxygen's defaults, run doxygen with the -l option. You can\n# optionally specify a file name after the option, if omitted DoxygenLayout.xml\n# will be used as the name of the layout file.\n#\n# Note that if you run doxygen from a directory containing a file called\n# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE\n# tag is left empty.\n\nLAYOUT_FILE            =\n\n# The CITE_BIB_FILES tag can be used to specify one or more bib files containing\n# the reference definitions. This must be a list of .bib files. The .bib\n# extension is automatically appended if omitted. This requires the bibtex tool\n# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info.\n# For LaTeX the style of the bibliography can be controlled using\n# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the\n# search path. See also \\cite for info how to create references.\n\nCITE_BIB_FILES         =\n\n#---------------------------------------------------------------------------\n# Configuration options related to warning and progress messages\n#---------------------------------------------------------------------------\n\n# The QUIET tag can be used to turn on/off the messages that are generated to\n# standard output by doxygen. If QUIET is set to YES this implies that the\n# messages are off.\n# The default value is: NO.\n\nQUIET                  = YES\n\n# The WARNINGS tag can be used to turn on/off the warning messages that are\n# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES\n# this implies that the warnings are on.\n#\n# Tip: Turn warnings on while writing the documentation.\n# The default value is: YES.\n\nWARNINGS               = YES\n\n# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate\n# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag\n# will automatically be disabled.\n# The default value is: YES.\n\nWARN_IF_UNDOCUMENTED   = YES\n\n# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for\n# potential errors in the documentation, such as not documenting some parameters\n# in a documented function, or documenting parameters that don't exist or using\n# markup commands wrongly.\n# The default value is: YES.\n\nWARN_IF_DOC_ERROR      = YES\n\n# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that\n# are documented, but have no documentation for their parameters or return\n# value. If set to NO, doxygen will only warn about wrong or incomplete\n# parameter documentation, but not about the absence of documentation.\n# The default value is: NO.\n\nWARN_NO_PARAMDOC       = NO\n\n# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when\n# a warning is encountered.\n# The default value is: NO.\n\nWARN_AS_ERROR          = NO\n\n# The WARN_FORMAT tag determines the format of the warning messages that doxygen\n# can produce. The string should contain the $file, $line, and $text tags, which\n# will be replaced by the file and line number from which the warning originated\n# and the warning text. Optionally the format may contain $version, which will\n# be replaced by the version of the file (if it could be obtained via\n# FILE_VERSION_FILTER)\n# The default value is: $file:$line: $text.\n\nWARN_FORMAT            = \"$file:$line: $text\"\n\n# The WARN_LOGFILE tag can be used to specify a file to which warning and error\n# messages should be written. If left blank the output is written to standard\n# error (stderr).\n\nWARN_LOGFILE           =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the input files\n#---------------------------------------------------------------------------\n\n# The INPUT tag is used to specify the files and/or directories that contain\n# documented source files. You may enter file names like myfile.cpp or\n# directories like /usr/src/myproject. Separate the files or directories with\n# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING\n# Note: If this tag is empty the current directory is searched.\n\nINPUT                  =\n\n# This tag can be used to specify the character encoding of the source files\n# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses\n# libiconv (or the iconv built into libc) for the transcoding. See the libiconv\n# documentation (see: http://www.gnu.org/software/libiconv) for the list of\n# possible encodings.\n# The default value is: UTF-8.\n\nINPUT_ENCODING         = UTF-8\n\n# If the value of the INPUT tag contains directories, you can use the\n# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and\n# *.h) to filter out the source-files in the directories.\n#\n# Note that for custom extensions or not directly supported extensions you also\n# need to set EXTENSION_MAPPING for the extension otherwise the files are not\n# read by doxygen.\n#\n# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp,\n# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h,\n# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc,\n# *.m, *.markdown, *.md, *.mm, *.dox, *.py, *.pyw, *.f90, *.f, *.for, *.tcl,\n# *.vhd, *.vhdl, *.ucf, *.qsf, *.as and *.js.\n\nFILE_PATTERNS          =  *.c, *.cc, *.cxx, *.cpp, *.c++, *.hh, *.hxx, *.hpp, *.h++, *.h\n\n# The RECURSIVE tag can be used to specify whether or not subdirectories should\n# be searched for input files as well.\n# The default value is: NO.\n\nRECURSIVE              = YES\n\n# The EXCLUDE tag can be used to specify files and/or directories that should be\n# excluded from the INPUT source files. This way you can easily exclude a\n# subdirectory from a directory tree whose root is specified with the INPUT tag.\n#\n# Note that relative paths are relative to the directory from which doxygen is\n# run.\n\nEXCLUDE                =\n\n# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or\n# directories that are symbolic links (a Unix file system feature) are excluded\n# from the input.\n# The default value is: NO.\n\nEXCLUDE_SYMLINKS       = NO\n\n# If the value of the INPUT tag contains directories, you can use the\n# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude\n# certain files from those directories.\n#\n# Note that the wildcards are matched against the file with absolute path, so to\n# exclude all test directories for example use the pattern */test/*\n\nEXCLUDE_PATTERNS       = */test/* */rosdoc_lite/* */smacc_diagnostics/scripts/* */smacc_sm_reference_library/* *.py\n\n\n\n# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names\n# (namespaces, classes, functions, etc.) that should be excluded from the\n# output. The symbol name can be a fully qualified name, a word, or if the\n# wildcard * is used, a substring. Examples: ANamespace, AClass,\n# AClass::ANamespace, ANamespace::*Test\n#\n# Note that the wildcards are matched against the file with absolute path, so to\n# exclude all test directories use the pattern */test/*\n\nEXCLUDE_SYMBOLS        =\n\n# The EXAMPLE_PATH tag can be used to specify one or more files or directories\n# that contain example code fragments that are included (see the \\include\n# command).\n\nEXAMPLE_PATH           =\n\n# If the value of the EXAMPLE_PATH tag contains directories, you can use the\n# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and\n# *.h) to filter out the source-files in the directories. If left blank all\n# files are included.\n\nEXAMPLE_PATTERNS       =\n\n# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be\n# searched for input files to be used with the \\include or \\dontinclude commands\n# irrespective of the value of the RECURSIVE tag.\n# The default value is: NO.\n\nEXAMPLE_RECURSIVE      = NO\n\n# The IMAGE_PATH tag can be used to specify one or more files or directories\n# that contain images that are to be included in the documentation (see the\n# \\image command).\n\nIMAGE_PATH             =\n\n# The INPUT_FILTER tag can be used to specify a program that doxygen should\n# invoke to filter for each input file. Doxygen will invoke the filter program\n# by executing (via popen()) the command:\n#\n# <filter> <input-file>\n#\n# where <filter> is the value of the INPUT_FILTER tag, and <input-file> is the\n# name of an input file. Doxygen will then use the output that the filter\n# program writes to standard output. If FILTER_PATTERNS is specified, this tag\n# will be ignored.\n#\n# Note that the filter must not add or remove lines; it is applied before the\n# code is scanned, but not when the output code is generated. If lines are added\n# or removed, the anchors will not be placed correctly.\n#\n# Note that for custom extensions or not directly supported extensions you also\n# need to set EXTENSION_MAPPING for the extension otherwise the files are not\n# properly processed by doxygen.\n\nINPUT_FILTER           =\n\n# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern\n# basis. Doxygen will compare the file name with each pattern and apply the\n# filter if there is a match. The filters are a list of the form: pattern=filter\n# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how\n# filters are used. If the FILTER_PATTERNS tag is empty or if none of the\n# patterns match the file name, INPUT_FILTER is applied.\n#\n# Note that for custom extensions or not directly supported extensions you also\n# need to set EXTENSION_MAPPING for the extension otherwise the files are not\n# properly processed by doxygen.\n\nFILTER_PATTERNS        =\n\n# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using\n# INPUT_FILTER) will also be used to filter the input files that are used for\n# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES).\n# The default value is: NO.\n\nFILTER_SOURCE_FILES    = NO\n\n# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file\n# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and\n# it is also possible to disable source filtering for a specific pattern using\n# *.ext= (so without naming a filter).\n# This tag requires that the tag FILTER_SOURCE_FILES is set to YES.\n\nFILTER_SOURCE_PATTERNS =\n\n# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that\n# is part of the input, its contents will be placed on the main page\n# (index.html). This can be useful if you have a project on for instance GitHub\n# and want to reuse the introduction page also for the doxygen output.\n\nUSE_MDFILE_AS_MAINPAGE =\n\n#---------------------------------------------------------------------------\n# Configuration options related to source browsing\n#---------------------------------------------------------------------------\n\n# If the SOURCE_BROWSER tag is set to YES then a list of source files will be\n# generated. Documented entities will be cross-referenced with these sources.\n#\n# Note: To get rid of all source code in the generated output, make sure that\n# also VERBATIM_HEADERS is set to NO.\n# The default value is: NO.\n\nSOURCE_BROWSER         = YES\n\n# Setting the INLINE_SOURCES tag to YES will include the body of functions,\n# classes and enums directly into the documentation.\n# The default value is: NO.\n\nINLINE_SOURCES         = YES\n\n# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any\n# special comment blocks from generated source code fragments. Normal C, C++ and\n# Fortran comments will always remain visible.\n# The default value is: YES.\n\nSTRIP_CODE_COMMENTS    = YES\n\n# If the REFERENCED_BY_RELATION tag is set to YES then for each documented\n# function all documented functions referencing it will be listed.\n# The default value is: NO.\n\nREFERENCED_BY_RELATION = YES\n\n# If the REFERENCES_RELATION tag is set to YES then for each documented function\n# all documented entities called/used by that function will be listed.\n# The default value is: NO.\n\nREFERENCES_RELATION    = YES\n\n# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set\n# to YES then the hyperlinks from functions in REFERENCES_RELATION and\n# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will\n# link to the documentation.\n# The default value is: YES.\n\nREFERENCES_LINK_SOURCE = YES\n\n# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the\n# source code will show a tooltip with additional information such as prototype,\n# brief description and links to the definition and documentation. Since this\n# will make the HTML file larger and loading of large files a bit slower, you\n# can opt to disable this feature.\n# The default value is: YES.\n# This tag requires that the tag SOURCE_BROWSER is set to YES.\n\nSOURCE_TOOLTIPS        = YES\n\n# If the USE_HTAGS tag is set to YES then the references to source code will\n# point to the HTML generated by the htags(1) tool instead of doxygen built-in\n# source browser. The htags tool is part of GNU's global source tagging system\n# (see http://www.gnu.org/software/global/global.html). You will need version\n# 4.8.6 or higher.\n#\n# To use it do the following:\n# - Install the latest version of global\n# - Enable SOURCE_BROWSER and USE_HTAGS in the config file\n# - Make sure the INPUT points to the root of the source tree\n# - Run doxygen as normal\n#\n# Doxygen will invoke htags (and that will in turn invoke gtags), so these\n# tools must be available from the command line (i.e. in the search path).\n#\n# The result: instead of the source browser generated by doxygen, the links to\n# source code will now point to the output of htags.\n# The default value is: NO.\n# This tag requires that the tag SOURCE_BROWSER is set to YES.\n\nUSE_HTAGS              = NO\n\n# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a\n# verbatim copy of the header file for each class for which an include is\n# specified. Set to NO to disable this.\n# See also: Section \\class.\n# The default value is: YES.\n\nVERBATIM_HEADERS       = YES\n\n# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the\n# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the\n# cost of reduced performance. This can be particularly helpful with template\n# rich C++ code for which doxygen's built-in parser lacks the necessary type\n# information.\n# Note: The availability of this option depends on whether or not doxygen was\n# generated with the -Duse-libclang=ON option for CMake.\n# The default value is: NO.\n\nCLANG_ASSISTED_PARSING = NO\n\n# If clang assisted parsing is enabled you can provide the compiler with command\n# line options that you would normally use when invoking the compiler. Note that\n# the include paths will already be set by doxygen for the files and directories\n# specified with INPUT and INCLUDE_PATH.\n# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES.\n\nCLANG_OPTIONS          =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the alphabetical class index\n#---------------------------------------------------------------------------\n\n# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all\n# compounds will be generated. Enable this if the project contains a lot of\n# classes, structs, unions or interfaces.\n# The default value is: YES.\n\nALPHABETICAL_INDEX     = YES\n\n# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in\n# which the alphabetical index list will be split.\n# Minimum value: 1, maximum value: 20, default value: 5.\n# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.\n\nCOLS_IN_ALPHA_INDEX    = 5\n\n# In case all classes in a project start with a common prefix, all classes will\n# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag\n# can be used to specify a prefix (or a list of prefixes) that should be ignored\n# while generating the index headers.\n# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.\n\nIGNORE_PREFIX          =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the HTML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output\n# The default value is: YES.\n\nGENERATE_HTML          = YES\n\n# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a\n# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of\n# it.\n# The default directory is: html.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_OUTPUT            = html\n\n# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each\n# generated HTML page (for example: .htm, .php, .asp).\n# The default value is: .html.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_FILE_EXTENSION    = .html\n\n# The HTML_HEADER tag can be used to specify a user-defined HTML header file for\n# each generated HTML page. If the tag is left blank doxygen will generate a\n# standard header.\n#\n# To get valid HTML the header file that includes any scripts and style sheets\n# that doxygen needs, which is dependent on the configuration options used (e.g.\n# the setting GENERATE_TREEVIEW). It is highly recommended to start with a\n# default header using\n# doxygen -w html new_header.html new_footer.html new_stylesheet.css\n# YourConfigFile\n# and then modify the file new_header.html. See also section \"Doxygen usage\"\n# for information on how to generate the default header that doxygen normally\n# uses.\n# Note: The header is subject to change so you typically have to regenerate the\n# default header when upgrading to a newer version of doxygen. For a description\n# of the possible markers and block names see the documentation.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_HEADER            =\n\n# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each\n# generated HTML page. If the tag is left blank doxygen will generate a standard\n# footer. See HTML_HEADER for more information on how to generate a default\n# footer and what special commands can be used inside the footer. See also\n# section \"Doxygen usage\" for information on how to generate the default footer\n# that doxygen normally uses.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_FOOTER            =\n\n# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style\n# sheet that is used by each HTML page. It can be used to fine-tune the look of\n# the HTML output. If left blank doxygen will generate a default style sheet.\n# See also section \"Doxygen usage\" for information on how to generate the style\n# sheet that doxygen normally uses.\n# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as\n# it is more robust and this tag (HTML_STYLESHEET) will in the future become\n# obsolete.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_STYLESHEET        =\n\n# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined\n# cascading style sheets that are included after the standard style sheets\n# created by doxygen. Using this option one can overrule certain style aspects.\n# This is preferred over using HTML_STYLESHEET since it does not replace the\n# standard style sheet and is therefore more robust against future updates.\n# Doxygen will copy the style sheet files to the output directory.\n# Note: The order of the extra style sheet files is of importance (e.g. the last\n# style sheet in the list overrules the setting of the previous ones in the\n# list). For an example see the documentation.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_EXTRA_STYLESHEET  =\n\n# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or\n# other source files which should be copied to the HTML output directory. Note\n# that these files will be copied to the base HTML output directory. Use the\n# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these\n# files. In the HTML_STYLESHEET file, use the file name only. Also note that the\n# files will be copied as-is; there are no commands or markers available.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_EXTRA_FILES       =\n\n# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen\n# will adjust the colors in the style sheet and background images according to\n# this color. Hue is specified as an angle on a colorwheel, see\n# http://en.wikipedia.org/wiki/Hue for more information. For instance the value\n# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300\n# purple, and 360 is red again.\n# Minimum value: 0, maximum value: 359, default value: 220.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_COLORSTYLE_HUE    = 220\n\n# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors\n# in the HTML output. For a value of 0 the output will use grayscales only. A\n# value of 255 will produce the most vivid colors.\n# Minimum value: 0, maximum value: 255, default value: 100.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_COLORSTYLE_SAT    = 100\n\n# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the\n# luminance component of the colors in the HTML output. Values below 100\n# gradually make the output lighter, whereas values above 100 make the output\n# darker. The value divided by 100 is the actual gamma applied, so 80 represents\n# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not\n# change the gamma.\n# Minimum value: 40, maximum value: 240, default value: 80.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_COLORSTYLE_GAMMA  = 80\n\n# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML\n# page will contain the date and time when the page was generated. Setting this\n# to YES can help to show when doxygen was last run and thus if the\n# documentation is up to date.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_TIMESTAMP         = NO\n\n# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML\n# documentation will contain sections that can be hidden and shown after the\n# page has loaded.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_DYNAMIC_SECTIONS  = NO\n\n# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries\n# shown in the various tree structured indices initially; the user can expand\n# and collapse entries dynamically later on. Doxygen will expand the tree to\n# such a level that at most the specified number of entries are visible (unless\n# a fully collapsed tree already exceeds this amount). So setting the number of\n# entries 1 will produce a full collapsed tree by default. 0 is a special value\n# representing an infinite number of entries and will result in a full expanded\n# tree by default.\n# Minimum value: 0, maximum value: 9999, default value: 100.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nHTML_INDEX_NUM_ENTRIES = 100\n\n# If the GENERATE_DOCSET tag is set to YES, additional index files will be\n# generated that can be used as input for Apple's Xcode 3 integrated development\n# environment (see: http://developer.apple.com/tools/xcode/), introduced with\n# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a\n# Makefile in the HTML output directory. Running make will produce the docset in\n# that directory and running make install will install the docset in\n# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at\n# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html\n# for more information.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nGENERATE_DOCSET        = NO\n\n# This tag determines the name of the docset feed. A documentation feed provides\n# an umbrella under which multiple documentation sets from a single provider\n# (such as a company or product suite) can be grouped.\n# The default value is: Doxygen generated docs.\n# This tag requires that the tag GENERATE_DOCSET is set to YES.\n\nDOCSET_FEEDNAME        = \"Doxygen generated docs\"\n\n# This tag specifies a string that should uniquely identify the documentation\n# set bundle. This should be a reverse domain-name style string, e.g.\n# com.mycompany.MyDocSet. Doxygen will append .docset to the name.\n# The default value is: org.doxygen.Project.\n# This tag requires that the tag GENERATE_DOCSET is set to YES.\n\nDOCSET_BUNDLE_ID       = org.doxygen.Project\n\n# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify\n# the documentation publisher. This should be a reverse domain-name style\n# string, e.g. com.mycompany.MyDocSet.documentation.\n# The default value is: org.doxygen.Publisher.\n# This tag requires that the tag GENERATE_DOCSET is set to YES.\n\nDOCSET_PUBLISHER_ID    = org.doxygen.Publisher\n\n# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher.\n# The default value is: Publisher.\n# This tag requires that the tag GENERATE_DOCSET is set to YES.\n\nDOCSET_PUBLISHER_NAME  = Publisher\n\n# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three\n# additional HTML index files: index.hhp, index.hhc, and index.hhk. The\n# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop\n# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on\n# Windows.\n#\n# The HTML Help Workshop contains a compiler that can convert all HTML output\n# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML\n# files are now used as the Windows 98 help format, and will replace the old\n# Windows help format (.hlp) on all Windows platforms in the future. Compressed\n# HTML files also contain an index, a table of contents, and you can search for\n# words in the documentation. The HTML workshop also contains a viewer for\n# compressed HTML files.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nGENERATE_HTMLHELP      = NO\n\n# The CHM_FILE tag can be used to specify the file name of the resulting .chm\n# file. You can add a path in front of the file if the result should not be\n# written to the html output directory.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nCHM_FILE               =\n\n# The HHC_LOCATION tag can be used to specify the location (absolute path\n# including file name) of the HTML help compiler (hhc.exe). If non-empty,\n# doxygen will try to run the HTML help compiler on the generated index.hhp.\n# The file has to be specified with full path.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nHHC_LOCATION           =\n\n# The GENERATE_CHI flag controls if a separate .chi index file is generated\n# (YES) or that it should be included in the master .chm file (NO).\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nGENERATE_CHI           = NO\n\n# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc)\n# and project file content.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nCHM_INDEX_ENCODING     =\n\n# The BINARY_TOC flag controls whether a binary table of contents is generated\n# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it\n# enables the Previous and Next buttons.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nBINARY_TOC             = NO\n\n# The TOC_EXPAND flag can be set to YES to add extra items for group members to\n# the table of contents of the HTML help documentation and to the tree view.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTMLHELP is set to YES.\n\nTOC_EXPAND             = NO\n\n# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and\n# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that\n# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help\n# (.qch) of the generated HTML documentation.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nGENERATE_QHP           = NO\n\n# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify\n# the file name of the resulting .qch file. The path specified is relative to\n# the HTML output folder.\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQCH_FILE               =\n\n# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help\n# Project output. For more information please see Qt Help Project / Namespace\n# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace).\n# The default value is: org.doxygen.Project.\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHP_NAMESPACE          = org.doxygen.Project\n\n# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt\n# Help Project output. For more information please see Qt Help Project / Virtual\n# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual-\n# folders).\n# The default value is: doc.\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHP_VIRTUAL_FOLDER     = doc\n\n# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom\n# filter to add. For more information please see Qt Help Project / Custom\n# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-\n# filters).\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHP_CUST_FILTER_NAME   =\n\n# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the\n# custom filter to add. For more information please see Qt Help Project / Custom\n# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-\n# filters).\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHP_CUST_FILTER_ATTRS  =\n\n# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this\n# project's filter section matches. Qt Help Project / Filter Attributes (see:\n# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes).\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHP_SECT_FILTER_ATTRS  =\n\n# The QHG_LOCATION tag can be used to specify the location of Qt's\n# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the\n# generated .qhp file.\n# This tag requires that the tag GENERATE_QHP is set to YES.\n\nQHG_LOCATION           =\n\n# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be\n# generated, together with the HTML files, they form an Eclipse help plugin. To\n# install this plugin and make it available under the help contents menu in\n# Eclipse, the contents of the directory containing the HTML and XML files needs\n# to be copied into the plugins directory of eclipse. The name of the directory\n# within the plugins directory should be the same as the ECLIPSE_DOC_ID value.\n# After copying Eclipse needs to be restarted before the help appears.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nGENERATE_ECLIPSEHELP   = NO\n\n# A unique identifier for the Eclipse help plugin. When installing the plugin\n# the directory name containing the HTML and XML files should also have this\n# name. Each documentation set should have its own identifier.\n# The default value is: org.doxygen.Project.\n# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES.\n\nECLIPSE_DOC_ID         = org.doxygen.Project\n\n# If you want full control over the layout of the generated HTML pages it might\n# be necessary to disable the index and replace it with your own. The\n# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top\n# of each HTML page. A value of NO enables the index and the value YES disables\n# it. Since the tabs in the index contain the same information as the navigation\n# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nDISABLE_INDEX          = NO\n\n# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index\n# structure should be generated to display hierarchical information. If the tag\n# value is set to YES, a side panel will be generated containing a tree-like\n# index structure (just like the one that is generated for HTML Help). For this\n# to work a browser that supports JavaScript, DHTML, CSS and frames is required\n# (i.e. any modern browser). Windows users are probably better off using the\n# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can\n# further fine-tune the look of the index. As an example, the default style\n# sheet generated by doxygen has an example that shows how to put an image at\n# the root of the tree instead of the PROJECT_NAME. Since the tree basically has\n# the same information as the tab index, you could consider setting\n# DISABLE_INDEX to YES when enabling this option.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nGENERATE_TREEVIEW      = NO\n\n# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that\n# doxygen will group on one line in the generated HTML documentation.\n#\n# Note that a value of 0 will completely suppress the enum values from appearing\n# in the overview section.\n# Minimum value: 0, maximum value: 20, default value: 4.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nENUM_VALUES_PER_LINE   = 4\n\n# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used\n# to set the initial width (in pixels) of the frame in which the tree is shown.\n# Minimum value: 0, maximum value: 1500, default value: 250.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nTREEVIEW_WIDTH         = 250\n\n# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to\n# external symbols imported via tag files in a separate window.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nEXT_LINKS_IN_WINDOW    = NO\n\n# Use this tag to change the font size of LaTeX formulas included as images in\n# the HTML documentation. When you change the font size after a successful\n# doxygen run you need to manually remove any form_*.png images from the HTML\n# output directory to force them to be regenerated.\n# Minimum value: 8, maximum value: 50, default value: 10.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nFORMULA_FONTSIZE       = 10\n\n# Use the FORMULA_TRANPARENT tag to determine whether or not the images\n# generated for formulas are transparent PNGs. Transparent PNGs are not\n# supported properly for IE 6.0, but are supported on all modern browsers.\n#\n# Note that when changing this option you need to delete any form_*.png files in\n# the HTML output directory before the changes have effect.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nFORMULA_TRANSPARENT    = YES\n\n# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see\n# http://www.mathjax.org) which uses client side Javascript for the rendering\n# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX\n# installed or if you want to formulas look prettier in the HTML output. When\n# enabled you may also need to install MathJax separately and configure the path\n# to it using the MATHJAX_RELPATH option.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nUSE_MATHJAX            = NO\n\n# When MathJax is enabled you can set the default output format to be used for\n# the MathJax output. See the MathJax site (see:\n# http://docs.mathjax.org/en/latest/output.html) for more details.\n# Possible values are: HTML-CSS (which is slower, but has the best\n# compatibility), NativeMML (i.e. MathML) and SVG.\n# The default value is: HTML-CSS.\n# This tag requires that the tag USE_MATHJAX is set to YES.\n\nMATHJAX_FORMAT         = HTML-CSS\n\n# When MathJax is enabled you need to specify the location relative to the HTML\n# output directory using the MATHJAX_RELPATH option. The destination directory\n# should contain the MathJax.js script. For instance, if the mathjax directory\n# is located at the same level as the HTML output directory, then\n# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax\n# Content Delivery Network so you can quickly see the result without installing\n# MathJax. However, it is strongly recommended to install a local copy of\n# MathJax from http://www.mathjax.org before deployment.\n# The default value is: http://cdn.mathjax.org/mathjax/latest.\n# This tag requires that the tag USE_MATHJAX is set to YES.\n\nMATHJAX_RELPATH        = http://cdn.mathjax.org/mathjax/latest\n\n# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax\n# extension names that should be enabled during MathJax rendering. For example\n# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols\n# This tag requires that the tag USE_MATHJAX is set to YES.\n\nMATHJAX_EXTENSIONS     =\n\n# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces\n# of code that will be used on startup of the MathJax code. See the MathJax site\n# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an\n# example see the documentation.\n# This tag requires that the tag USE_MATHJAX is set to YES.\n\nMATHJAX_CODEFILE       =\n\n# When the SEARCHENGINE tag is enabled doxygen will generate a search box for\n# the HTML output. The underlying search engine uses javascript and DHTML and\n# should work on any modern browser. Note that when using HTML help\n# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET)\n# there is already a search function so this one should typically be disabled.\n# For large projects the javascript based search engine can be slow, then\n# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to\n# search using the keyboard; to jump to the search box use <access key> + S\n# (what the <access key> is depends on the OS and browser, but it is typically\n# <CTRL>, <ALT>/<option>, or both). Inside the search box use the <cursor down\n# key> to jump into the search results window, the results can be navigated\n# using the <cursor keys>. Press <Enter> to select an item or <escape> to cancel\n# the search. The filter options can be selected when the cursor is inside the\n# search box by pressing <Shift>+<cursor down>. Also here use the <cursor keys>\n# to select a filter and <Enter> or <escape> to activate or cancel the filter\n# option.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_HTML is set to YES.\n\nSEARCHENGINE           = YES\n\n# When the SERVER_BASED_SEARCH tag is enabled the search engine will be\n# implemented using a web server instead of a web client using Javascript. There\n# are two flavors of web server based searching depending on the EXTERNAL_SEARCH\n# setting. When disabled, doxygen will generate a PHP script for searching and\n# an index file used by the script. When EXTERNAL_SEARCH is enabled the indexing\n# and searching needs to be provided by external tools. See the section\n# \"External Indexing and Searching\" for details.\n# The default value is: NO.\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nSERVER_BASED_SEARCH    = NO\n\n# When EXTERNAL_SEARCH tag is enabled doxygen will no longer generate the PHP\n# script for searching. Instead the search results are written to an XML file\n# which needs to be processed by an external indexer. Doxygen will invoke an\n# external search engine pointed to by the SEARCHENGINE_URL option to obtain the\n# search results.\n#\n# Doxygen ships with an example indexer (doxyindexer) and search engine\n# (doxysearch.cgi) which are based on the open source search engine library\n# Xapian (see: http://xapian.org/).\n#\n# See the section \"External Indexing and Searching\" for details.\n# The default value is: NO.\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nEXTERNAL_SEARCH        = NO\n\n# The SEARCHENGINE_URL should point to a search engine hosted by a web server\n# which will return the search results when EXTERNAL_SEARCH is enabled.\n#\n# Doxygen ships with an example indexer (doxyindexer) and search engine\n# (doxysearch.cgi) which are based on the open source search engine library\n# Xapian (see: http://xapian.org/). See the section \"External Indexing and\n# Searching\" for details.\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nSEARCHENGINE_URL       =\n\n# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed\n# search data is written to a file for indexing by an external tool. With the\n# SEARCHDATA_FILE tag the name of this file can be specified.\n# The default file is: searchdata.xml.\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nSEARCHDATA_FILE        = searchdata.xml\n\n# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the\n# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is\n# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple\n# projects and redirect the results back to the right project.\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nEXTERNAL_SEARCH_ID     =\n\n# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen\n# projects other than the one defined by this configuration file, but that are\n# all added to the same external search index. Each project needs to have a\n# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id of\n# to a relative location where the documentation can be found. The format is:\n# EXTRA_SEARCH_MAPPINGS = tagname1=loc1 tagname2=loc2 ...\n# This tag requires that the tag SEARCHENGINE is set to YES.\n\nEXTRA_SEARCH_MAPPINGS  =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the LaTeX output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_LATEX tag is set to YES, doxygen will generate LaTeX output.\n# The default value is: YES.\n\nGENERATE_LATEX         = YES\n\n# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. If a\n# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of\n# it.\n# The default directory is: latex.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_OUTPUT           = latex\n\n# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be\n# invoked.\n#\n# Note that when enabling USE_PDFLATEX this option is only used for generating\n# bitmaps for formulas in the HTML output, but not in the Makefile that is\n# written to the output directory.\n# The default file is: latex.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_CMD_NAME         = latex\n\n# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate\n# index for LaTeX.\n# The default file is: makeindex.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nMAKEINDEX_CMD_NAME     = makeindex\n\n# If the COMPACT_LATEX tag is set to YES, doxygen generates more compact LaTeX\n# documents. This may be useful for small projects and may help to save some\n# trees in general.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nCOMPACT_LATEX          = NO\n\n# The PAPER_TYPE tag can be used to set the paper type that is used by the\n# printer.\n# Possible values are: a4 (210 x 297 mm), letter (8.5 x 11 inches), legal (8.5 x\n# 14 inches) and executive (7.25 x 10.5 inches).\n# The default value is: a4.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nPAPER_TYPE             = a4\n\n# The EXTRA_PACKAGES tag can be used to specify one or more LaTeX package names\n# that should be included in the LaTeX output. The package can be specified just\n# by its name or with the correct syntax as to be used with the LaTeX\n# \\usepackage command. To get the times font for instance you can specify :\n# EXTRA_PACKAGES=times or EXTRA_PACKAGES={times}\n# To use the option intlimits with the amsmath package you can specify:\n# EXTRA_PACKAGES=[intlimits]{amsmath}\n# If left blank no extra packages will be included.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nEXTRA_PACKAGES         =\n\n# The LATEX_HEADER tag can be used to specify a personal LaTeX header for the\n# generated LaTeX document. The header should contain everything until the first\n# chapter. If it is left blank doxygen will generate a standard header. See\n# section \"Doxygen usage\" for information on how to let doxygen write the\n# default header to a separate file.\n#\n# Note: Only use a user-defined header if you know what you are doing! The\n# following commands have a special meaning inside the header: $title,\n# $datetime, $date, $doxygenversion, $projectname, $projectnumber,\n# $projectbrief, $projectlogo. Doxygen will replace $title with the empty\n# string, for the replacement values of the other commands the user is referred\n# to HTML_HEADER.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_HEADER           =\n\n# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for the\n# generated LaTeX document. The footer should contain everything after the last\n# chapter. If it is left blank doxygen will generate a standard footer. See\n# LATEX_HEADER for more information on how to generate a default footer and what\n# special commands can be used inside the footer.\n#\n# Note: Only use a user-defined footer if you know what you are doing!\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_FOOTER           =\n\n# The LATEX_EXTRA_STYLESHEET tag can be used to specify additional user-defined\n# LaTeX style sheets that are included after the standard style sheets created\n# by doxygen. Using this option one can overrule certain style aspects. Doxygen\n# will copy the style sheet files to the output directory.\n# Note: The order of the extra style sheet files is of importance (e.g. the last\n# style sheet in the list overrules the setting of the previous ones in the\n# list).\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_EXTRA_STYLESHEET =\n\n# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images or\n# other source files which should be copied to the LATEX_OUTPUT output\n# directory. Note that the files will be copied as-is; there are no commands or\n# markers available.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_EXTRA_FILES      =\n\n# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated is\n# prepared for conversion to PDF (using ps2pdf or pdflatex). The PDF file will\n# contain links (just like the HTML output) instead of page references. This\n# makes the output suitable for online browsing using a PDF viewer.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nPDF_HYPERLINKS         = YES\n\n# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate\n# the PDF file directly from the LaTeX files. Set this option to YES, to get a\n# higher quality PDF documentation.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nUSE_PDFLATEX           = YES\n\n# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode\n# command to the generated LaTeX files. This will instruct LaTeX to keep running\n# if errors occur, instead of asking the user for help. This option is also used\n# when generating formulas in HTML.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_BATCHMODE        = NO\n\n# If the LATEX_HIDE_INDICES tag is set to YES then doxygen will not include the\n# index chapters (such as File Index, Compound Index, etc.) in the output.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_HIDE_INDICES     = NO\n\n# If the LATEX_SOURCE_CODE tag is set to YES then doxygen will include source\n# code with syntax highlighting in the LaTeX output.\n#\n# Note that which sources are shown also depends on other settings such as\n# SOURCE_BROWSER.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_SOURCE_CODE      = NO\n\n# The LATEX_BIB_STYLE tag can be used to specify the style to use for the\n# bibliography, e.g. plainnat, or ieeetr. See\n# http://en.wikipedia.org/wiki/BibTeX and \\cite for more info.\n# The default value is: plain.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_BIB_STYLE        = plain\n\n# If the LATEX_TIMESTAMP tag is set to YES then the footer of each generated\n# page will contain the date and time when the page was generated. Setting this\n# to NO can help when comparing the output of multiple runs.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_LATEX is set to YES.\n\nLATEX_TIMESTAMP        = NO\n\n#---------------------------------------------------------------------------\n# Configuration options related to the RTF output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_RTF tag is set to YES, doxygen will generate RTF output. The\n# RTF output is optimized for Word 97 and may not look too pretty with other RTF\n# readers/editors.\n# The default value is: NO.\n\nGENERATE_RTF           = NO\n\n# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. If a\n# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of\n# it.\n# The default directory is: rtf.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nRTF_OUTPUT             = rtf\n\n# If the COMPACT_RTF tag is set to YES, doxygen generates more compact RTF\n# documents. This may be useful for small projects and may help to save some\n# trees in general.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nCOMPACT_RTF            = NO\n\n# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated will\n# contain hyperlink fields. The RTF file will contain links (just like the HTML\n# output) instead of page references. This makes the output suitable for online\n# browsing using Word or some other Word compatible readers that support those\n# fields.\n#\n# Note: WordPad (write) and others do not support links.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nRTF_HYPERLINKS         = NO\n\n# Load stylesheet definitions from file. Syntax is similar to doxygen's config\n# file, i.e. a series of assignments. You only have to provide replacements,\n# missing definitions are set to their default value.\n#\n# See also section \"Doxygen usage\" for information on how to generate the\n# default style sheet that doxygen normally uses.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nRTF_STYLESHEET_FILE    =\n\n# Set optional variables used in the generation of an RTF document. Syntax is\n# similar to doxygen's config file. A template extensions file can be generated\n# using doxygen -e rtf extensionFile.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nRTF_EXTENSIONS_FILE    =\n\n# If the RTF_SOURCE_CODE tag is set to YES then doxygen will include source code\n# with syntax highlighting in the RTF output.\n#\n# Note that which sources are shown also depends on other settings such as\n# SOURCE_BROWSER.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_RTF is set to YES.\n\nRTF_SOURCE_CODE        = NO\n\n#---------------------------------------------------------------------------\n# Configuration options related to the man page output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_MAN tag is set to YES, doxygen will generate man pages for\n# classes and files.\n# The default value is: NO.\n\nGENERATE_MAN           = NO\n\n# The MAN_OUTPUT tag is used to specify where the man pages will be put. If a\n# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of\n# it. A directory man3 will be created inside the directory specified by\n# MAN_OUTPUT.\n# The default directory is: man.\n# This tag requires that the tag GENERATE_MAN is set to YES.\n\nMAN_OUTPUT             = man\n\n# The MAN_EXTENSION tag determines the extension that is added to the generated\n# man pages. In case the manual section does not start with a number, the number\n# 3 is prepended. The dot (.) at the beginning of the MAN_EXTENSION tag is\n# optional.\n# The default value is: .3.\n# This tag requires that the tag GENERATE_MAN is set to YES.\n\nMAN_EXTENSION          = .3\n\n# The MAN_SUBDIR tag determines the name of the directory created within\n# MAN_OUTPUT in which the man pages are placed. If defaults to man followed by\n# MAN_EXTENSION with the initial . removed.\n# This tag requires that the tag GENERATE_MAN is set to YES.\n\nMAN_SUBDIR             =\n\n# If the MAN_LINKS tag is set to YES and doxygen generates man output, then it\n# will generate one additional man file for each entity documented in the real\n# man page(s). These additional files only source the real man page, but without\n# them the man command would be unable to find the correct page.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_MAN is set to YES.\n\nMAN_LINKS              = NO\n\n#---------------------------------------------------------------------------\n# Configuration options related to the XML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_XML tag is set to YES, doxygen will generate an XML file that\n# captures the structure of the code including all documentation.\n# The default value is: NO.\n\nGENERATE_XML           = NO\n\n# The XML_OUTPUT tag is used to specify where the XML pages will be put. If a\n# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of\n# it.\n# The default directory is: xml.\n# This tag requires that the tag GENERATE_XML is set to YES.\n\nXML_OUTPUT             = xml\n\n# If the XML_PROGRAMLISTING tag is set to YES, doxygen will dump the program\n# listings (including syntax highlighting and cross-referencing information) to\n# the XML output. Note that enabling this will significantly increase the size\n# of the XML output.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_XML is set to YES.\n\nXML_PROGRAMLISTING     = YES\n\n#---------------------------------------------------------------------------\n# Configuration options related to the DOCBOOK output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_DOCBOOK tag is set to YES, doxygen will generate Docbook files\n# that can be used to generate PDF.\n# The default value is: NO.\n\nGENERATE_DOCBOOK       = NO\n\n# The DOCBOOK_OUTPUT tag is used to specify where the Docbook pages will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in\n# front of it.\n# The default directory is: docbook.\n# This tag requires that the tag GENERATE_DOCBOOK is set to YES.\n\nDOCBOOK_OUTPUT         = docbook\n\n# If the DOCBOOK_PROGRAMLISTING tag is set to YES, doxygen will include the\n# program listings (including syntax highlighting and cross-referencing\n# information) to the DOCBOOK output. Note that enabling this will significantly\n# increase the size of the DOCBOOK output.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_DOCBOOK is set to YES.\n\nDOCBOOK_PROGRAMLISTING = NO\n\n#---------------------------------------------------------------------------\n# Configuration options for the AutoGen Definitions output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_AUTOGEN_DEF tag is set to YES, doxygen will generate an\n# AutoGen Definitions (see http://autogen.sf.net) file that captures the\n# structure of the code including all documentation. Note that this feature is\n# still experimental and incomplete at the moment.\n# The default value is: NO.\n\nGENERATE_AUTOGEN_DEF   = NO\n\n#---------------------------------------------------------------------------\n# Configuration options related to the Perl module output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_PERLMOD tag is set to YES, doxygen will generate a Perl module\n# file that captures the structure of the code including all documentation.\n#\n# Note that this feature is still experimental and incomplete at the moment.\n# The default value is: NO.\n\nGENERATE_PERLMOD       = NO\n\n# If the PERLMOD_LATEX tag is set to YES, doxygen will generate the necessary\n# Makefile rules, Perl scripts and LaTeX code to be able to generate PDF and DVI\n# output from the Perl module output.\n# The default value is: NO.\n# This tag requires that the tag GENERATE_PERLMOD is set to YES.\n\nPERLMOD_LATEX          = NO\n\n# If the PERLMOD_PRETTY tag is set to YES, the Perl module output will be nicely\n# formatted so it can be parsed by a human reader. This is useful if you want to\n# understand what is going on. On the other hand, if this tag is set to NO, the\n# size of the Perl module output will be much smaller and Perl will parse it\n# just the same.\n# The default value is: YES.\n# This tag requires that the tag GENERATE_PERLMOD is set to YES.\n\nPERLMOD_PRETTY         = YES\n\n# The names of the make variables in the generated doxyrules.make file are\n# prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. This is useful\n# so different doxyrules.make files included by the same Makefile don't\n# overwrite each other's variables.\n# This tag requires that the tag GENERATE_PERLMOD is set to YES.\n\nPERLMOD_MAKEVAR_PREFIX =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the preprocessor\n#---------------------------------------------------------------------------\n\n# If the ENABLE_PREPROCESSING tag is set to YES, doxygen will evaluate all\n# C-preprocessor directives found in the sources and include files.\n# The default value is: YES.\n\nENABLE_PREPROCESSING   = YES\n\n# If the MACRO_EXPANSION tag is set to YES, doxygen will expand all macro names\n# in the source code. If set to NO, only sr_conditional compilation will be\n# performed. Macro expansion can be done in a controlled way by setting\n# EXPAND_ONLY_PREDEF to YES.\n# The default value is: NO.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nMACRO_EXPANSION        = NO\n\n# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES then\n# the macro expansion is limited to the macros specified with the PREDEFINED and\n# EXPAND_AS_DEFINED tags.\n# The default value is: NO.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nEXPAND_ONLY_PREDEF     = NO\n\n# If the SEARCH_INCLUDES tag is set to YES, the include files in the\n# INCLUDE_PATH will be searched if a #include is found.\n# The default value is: YES.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nSEARCH_INCLUDES        = YES\n\n# The INCLUDE_PATH tag can be used to specify one or more directories that\n# contain include files that are not input files but should be processed by the\n# preprocessor.\n# This tag requires that the tag SEARCH_INCLUDES is set to YES.\n\nINCLUDE_PATH           =\n\n# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard\n# patterns (like *.h and *.hpp) to filter out the header-files in the\n# directories. If left blank, the patterns specified with FILE_PATTERNS will be\n# used.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nINCLUDE_FILE_PATTERNS  =\n\n# The PREDEFINED tag can be used to specify one or more macro names that are\n# defined before the preprocessor is started (similar to the -D option of e.g.\n# gcc). The argument of the tag is a list of macros of the form: name or\n# name=definition (no spaces). If the definition and the \"=\" are omitted, \"=1\"\n# is assumed. To prevent a macro definition from being undefined via #undef or\n# recursively expanded use the := operator instead of the = operator.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nPREDEFINED             =\n\n# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this\n# tag can be used to specify a list of macro names that should be expanded. The\n# macro definition that is found in the sources will be used. Use the PREDEFINED\n# tag if you want to use a different macro definition that overrules the\n# definition found in the source code.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nEXPAND_AS_DEFINED      =\n\n# If the SKIP_FUNCTION_MACROS tag is set to YES then doxygen's preprocessor will\n# remove all references to function-like macros that are alone on a line, have\n# an all uppercase name, and do not end with a semicolon. Such function macros\n# are typically used for boiler-plate code, and will confuse the parser if not\n# removed.\n# The default value is: YES.\n# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.\n\nSKIP_FUNCTION_MACROS   = YES\n\n#---------------------------------------------------------------------------\n# Configuration options related to external references\n#---------------------------------------------------------------------------\n\n# The TAGFILES tag can be used to specify one or more tag files. For each tag\n# file the location of the external documentation should be added. The format of\n# a tag file without this location is as follows:\n# TAGFILES = file1 file2 ...\n# Adding location for the tag files is done as follows:\n# TAGFILES = file1=loc1 \"file2 = loc2\" ...\n# where loc1 and loc2 can be relative or absolute paths or URLs. See the\n# section \"Linking to external documentation\" for more information about the use\n# of tag files.\n# Note: Each tag file must have a unique name (where the name does NOT include\n# the path). If a tag file is not located in the directory in which doxygen is\n# run, you must also specify the path to the tagfile here.\n\nTAGFILES               =\n\n# When a file name is specified after GENERATE_TAGFILE, doxygen will create a\n# tag file that is based on the input files it reads. See section \"Linking to\n# external documentation\" for more information about the usage of tag files.\n\nGENERATE_TAGFILE       =\n\n# If the ALLEXTERNALS tag is set to YES, all external class will be listed in\n# the class index. If set to NO, only the inherited external classes will be\n# listed.\n# The default value is: NO.\n\nALLEXTERNALS           = NO\n\n# If the EXTERNAL_GROUPS tag is set to YES, all external groups will be listed\n# in the modules index. If set to NO, only the current project's groups will be\n# listed.\n# The default value is: YES.\n\nEXTERNAL_GROUPS        = YES\n\n# If the EXTERNAL_PAGES tag is set to YES, all external pages will be listed in\n# the related pages index. If set to NO, only the current project's pages will\n# be listed.\n# The default value is: YES.\n\nEXTERNAL_PAGES         = YES\n\n# The PERL_PATH should be the absolute path and name of the perl script\n# interpreter (i.e. the result of 'which perl').\n# The default file (with absolute path) is: /usr/bin/perl.\n\nPERL_PATH              = /usr/bin/perl\n\n#---------------------------------------------------------------------------\n# Configuration options related to the dot tool\n#---------------------------------------------------------------------------\n\n# If the CLASS_DIAGRAMS tag is set to YES, doxygen will generate a class diagram\n# (in HTML and LaTeX) for classes with base or super classes. Setting the tag to\n# NO turns the diagrams off. Note that this option also works with HAVE_DOT\n# disabled, but it is recommended to install and use dot, since it yields more\n# powerful graphs.\n# The default value is: YES.\n\nCLASS_DIAGRAMS         = YES\n\n# You can define message sequence charts within doxygen comments using the \\msc\n# command. Doxygen will then run the mscgen tool (see:\n# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the\n# documentation. The MSCGEN_PATH tag allows you to specify the directory where\n# the mscgen tool resides. If left empty the tool is assumed to be found in the\n# default search path.\n\nMSCGEN_PATH            =\n\n# You can include diagrams made with dia in doxygen documentation. Doxygen will\n# then run dia to produce the diagram and insert it in the documentation. The\n# DIA_PATH tag allows you to specify the directory where the dia binary resides.\n# If left empty dia is assumed to be found in the default search path.\n\nDIA_PATH               =\n\n# If set to YES the inheritance and collaboration graphs will hide inheritance\n# and usage relations if the target is undocumented or is not a class.\n# The default value is: YES.\n\nHIDE_UNDOC_RELATIONS   = NO\n\n# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is\n# available from the path. This tool is part of Graphviz (see:\n# http://www.graphviz.org/), a graph visualization toolkit from AT&T and Lucent\n# Bell Labs. The other options in this section have no effect if this option is\n# set to NO\n# The default value is: YES.\n\nHAVE_DOT               = YES\n\n# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed\n# to run in parallel. When set to 0 doxygen will base this on the number of\n# processors available in the system. You can set it explicitly to a value\n# larger than 0 to get control over the balance between CPU load and processing\n# speed.\n# Minimum value: 0, maximum value: 32, default value: 0.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_NUM_THREADS        = 0\n\n# When you want a differently looking font in the dot files that doxygen\n# generates you can specify the font name using DOT_FONTNAME. You need to make\n# sure dot is able to find the font, which can be done by putting it in a\n# standard location or by setting the DOTFONTPATH environment variable or by\n# setting DOT_FONTPATH to the directory containing the font.\n# The default value is: Helvetica.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_FONTNAME           = Helvetica\n\n# The DOT_FONTSIZE tag can be used to set the size (in points) of the font of\n# dot graphs.\n# Minimum value: 4, maximum value: 24, default value: 10.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_FONTSIZE           = 10\n\n# By default doxygen will tell dot to use the default font as specified with\n# DOT_FONTNAME. If you specify a different font using DOT_FONTNAME you can set\n# the path where dot can find it using this tag.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_FONTPATH           =\n\n# If the CLASS_GRAPH tag is set to YES then doxygen will generate a graph for\n# each documented class showing the direct and indirect inheritance relations.\n# Setting this tag to YES will force the CLASS_DIAGRAMS tag to NO.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nCLASS_GRAPH            = YES\n\n# If the COLLABORATION_GRAPH tag is set to YES then doxygen will generate a\n# graph for each documented class showing the direct and indirect implementation\n# dependencies (inheritance, containment, and class references variables) of the\n# class with other documented classes.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nCOLLABORATION_GRAPH    = YES\n\n# If the GROUP_GRAPHS tag is set to YES then doxygen will generate a graph for\n# groups, showing the direct groups dependencies.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nGROUP_GRAPHS           = YES\n\n# If the UML_LOOK tag is set to YES, doxygen will generate inheritance and\n# collaboration diagrams in a style similar to the OMG's Unified Modeling\n# Language.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nUML_LOOK               = YES\n\n# If the UML_LOOK tag is enabled, the fields and methods are shown inside the\n# class node. If there are many fields or methods and many nodes the graph may\n# become too big to be useful. The UML_LIMIT_NUM_FIELDS threshold limits the\n# number of items for each type to make the size more manageable. Set this to 0\n# for no limit. Note that the threshold may be exceeded by 50% before the limit\n# is enforced. So when you set the threshold to 10, up to 15 fields may appear,\n# but if the number exceeds 15, the total amount of fields shown is limited to\n# 10.\n# Minimum value: 0, maximum value: 100, default value: 10.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nUML_LIMIT_NUM_FIELDS   = 50\n\n# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and\n# collaboration graphs will show the relations between templates and their\n# instances.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nTEMPLATE_RELATIONS     = YES\n\n# If the INCLUDE_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are set to\n# YES then doxygen will generate a graph for each documented file showing the\n# direct and indirect include dependencies of the file with other documented\n# files.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nINCLUDE_GRAPH          = YES\n\n# If the INCLUDED_BY_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are\n# set to YES then doxygen will generate a graph for each documented file showing\n# the direct and indirect include dependencies of the file with other documented\n# files.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nINCLUDED_BY_GRAPH      = YES\n\n# If the CALL_GRAPH tag is set to YES then doxygen will generate a call\n# dependency graph for every global function or class method.\n#\n# Note that enabling this option will significantly increase the time of a run.\n# So in most cases it will be better to enable call graphs for selected\n# functions only using the \\callgraph command. Disabling a call graph can be\n# accomplished by means of the command \\hidecallgraph.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nCALL_GRAPH             = YES\n\n# If the CALLER_GRAPH tag is set to YES then doxygen will generate a caller\n# dependency graph for every global function or class method.\n#\n# Note that enabling this option will significantly increase the time of a run.\n# So in most cases it will be better to enable caller graphs for selected\n# functions only using the \\callergraph command. Disabling a caller graph can be\n# accomplished by means of the command \\hidecallergraph.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nCALLER_GRAPH           = YES\n\n# If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical\n# hierarchy of all classes instead of a textual one.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nGRAPHICAL_HIERARCHY    = YES\n\n# If the DIRECTORY_GRAPH tag is set to YES then doxygen will show the\n# dependencies a directory has on other directories in a graphical way. The\n# dependency relations are determined by the #include relations between the\n# files in the directories.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDIRECTORY_GRAPH        = YES\n\n# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images\n# generated by dot. For an explanation of the image formats see the section\n# output formats in the documentation of the dot tool (Graphviz (see:\n# http://www.graphviz.org/)).\n# Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order\n# to make the SVG files visible in IE 9+ (other browsers do not have this\n# requirement).\n# Possible values are: png, png:cairo, png:cairo:cairo, png:cairo:gd, png:gd,\n# png:gd:gd, jpg, jpg:cairo, jpg:cairo:gd, jpg:gd, jpg:gd:gd, gif, gif:cairo,\n# gif:cairo:gd, gif:gd, gif:gd:gd, svg, png:gd, png:gd:gd, png:cairo,\n# png:cairo:gd, png:cairo:cairo, png:cairo:gdiplus, png:gdiplus and\n# png:gdiplus:gdiplus.\n# The default value is: png.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_IMAGE_FORMAT       = png\n\n# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to\n# enable generation of interactive SVG images that allow zooming and panning.\n#\n# Note that this requires a modern browser other than Internet Explorer. Tested\n# and working are Firefox, Chrome, Safari, and Opera.\n# Note: For IE 9+ you need to set HTML_FILE_EXTENSION to xhtml in order to make\n# the SVG files visible. Older versions of IE do not have SVG support.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nINTERACTIVE_SVG        = NO\n\n# The DOT_PATH tag can be used to specify the path where the dot tool can be\n# found. If left blank, it is assumed the dot tool can be found in the path.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_PATH               =\n\n# The DOTFILE_DIRS tag can be used to specify one or more directories that\n# contain dot files that are included in the documentation (see the \\dotfile\n# command).\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOTFILE_DIRS           =\n\n# The MSCFILE_DIRS tag can be used to specify one or more directories that\n# contain msc files that are included in the documentation (see the \\mscfile\n# command).\n\nMSCFILE_DIRS           =\n\n# The DIAFILE_DIRS tag can be used to specify one or more directories that\n# contain dia files that are included in the documentation (see the \\diafile\n# command).\n\nDIAFILE_DIRS           =\n\n# When using plantuml, the PLANTUML_JAR_PATH tag should be used to specify the\n# path where java can find the plantuml.jar file. If left blank, it is assumed\n# PlantUML is not used or called during a preprocessing step. Doxygen will\n# generate a warning when it encounters a \\startuml command in this case and\n# will not generate output for the diagram.\n\nPLANTUML_JAR_PATH      =\n\n# When using plantuml, the specified paths are searched for files specified by\n# the !include statement in a plantuml block.\n\nPLANTUML_INCLUDE_PATH  =\n\n# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes\n# that will be shown in the graph. If the number of nodes in a graph becomes\n# larger than this value, doxygen will truncate the graph, which is visualized\n# by representing a node as a red box. Note that doxygen if the number of direct\n# children of the root node in a graph is already larger than\n# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note that\n# the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.\n# Minimum value: 0, maximum value: 10000, default value: 50.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_GRAPH_MAX_NODES    = 150\n\n# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the graphs\n# generated by dot. A depth value of 3 means that only nodes reachable from the\n# root by following a path via at most 3 edges will be shown. Nodes that lay\n# further from the root node will be omitted. Note that setting this option to 1\n# or 2 may greatly reduce the computation time needed for large code bases. Also\n# note that the size of a graph can be further restricted by\n# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.\n# Minimum value: 0, maximum value: 1000, default value: 0.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nMAX_DOT_GRAPH_DEPTH    = 0\n\n# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent\n# background. This is disabled by default, because dot on Windows does not seem\n# to support this out of the box.\n#\n# Warning: Depending on the platform used, enabling this option may lead to\n# badly anti-aliased labels on the edges of a graph (i.e. they become hard to\n# read).\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_TRANSPARENT        = NO\n\n# Set the DOT_MULTI_TARGETS tag to YES to allow dot to generate multiple output\n# files in one run (i.e. multiple -o and -T options on the command line). This\n# makes dot run faster, but since only newer versions of dot (>1.8.10) support\n# this, this feature is disabled by default.\n# The default value is: NO.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_MULTI_TARGETS      = NO\n\n# If the GENERATE_LEGEND tag is set to YES doxygen will generate a legend page\n# explaining the meaning of the various boxes and arrows in the dot generated\n# graphs.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nGENERATE_LEGEND        = YES\n\n# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate dot\n# files that are used to generate the various graphs.\n# The default value is: YES.\n# This tag requires that the tag HAVE_DOT is set to YES.\n\nDOT_CLEANUP            = YES\n"
  },
  {
    "path": "smacc_ci/docker/ros_kinetic_ubuntu_16.04/Dockerfile",
    "content": "FROM ros:kinetic-robot\n\nENV PATH /usr/local/nvidia/bin:${PATH}\nENV LD_LIBRARY_PATH /usr/local/nvidia/lib:/usr/local/nvidia/lib64:${LD_LIBRARY_PATH}\n\nENV HOME /root\nENV DEBIAN_FRONTEND noninteractive\n\n# install ros packages\nRUN apt-get update && apt-get install -y \\\n    ros-kinetic-robot \\\n    && rm -rf /var/lib/apt/lists/*\n\n# SYSTEM DEPENDENCIES\n#----------------------------------------------------------\nRUN export DEBIAN_FRONTEND=\"noninteractive\"; apt-get update && apt-get install -y apt-utils && apt-get install -y git python-catkin-tools curl\n\nRUN curl -s https://packagecloud.io/install/repositories/robosoft-ai/SMACC/script.deb.sh | sudo bash\nRUN apt-get install -y ros-kinetic-smacc ros-kinetic-sm-dance-bot-strikes-back ros-kinetic-sm-atomic\n\nRUN curl -s  https://b0e12e65a4f16bfc4594206c69dce2a49a5eabd04efb7540:@packagecloud.io/install/repositories/robosoft-ai/SMACC_viewer/script.deb.sh  | bash\nRUN apt-get install -y ros-kinetic-smacc-viewer\n\nWORKDIR /root\n"
  },
  {
    "path": "smacc_ci/docker/ros_kinetic_ubuntu_16.04/build.sh",
    "content": "#!/bin/bash\nsudo docker build -t smacc_kinetic_ubuntu_1604 .\n"
  },
  {
    "path": "smacc_ci/docker/ros_kinetic_ubuntu_16.04/examples/run_sm_atomic.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_kinetic_ubuntu_1604 bash -c \"source /opt/ros/kinetic/setup.bash; roslaunch sm_atomic sm_atomic.launch & rosrun smacc_viewer smacc_viewer_node.py\"\n"
  },
  {
    "path": "smacc_ci/docker/ros_kinetic_ubuntu_16.04/run_bash.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run --gpus device=0 -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_kinetic_ubuntu_1604 bash\n"
  },
  {
    "path": "smacc_ci/docker/ros_melodic_ubuntu_18.04/Dockerfile",
    "content": "FROM ros:melodic-ros-base-bionic\n\nENV PATH /usr/local/nvidia/bin:${PATH}\nENV LD_LIBRARY_PATH /usr/local/nvidia/lib:/usr/local/nvidia/lib64:${LD_LIBRARY_PATH}\n\nENV HOME /root\nENV DEBIAN_FRONTEND noninteractive\n\n# install ros packages\nRUN apt-get update && apt-get install -y \\\n    ros-melodic-robot=1.4.1-0* \\\n    && rm -rf /var/lib/apt/lists/*\n\n# SYSTEM DEPENDENCIES\n#----------------------------------------------------------\nRUN echo \"regen\"\nRUN export DEBIAN_FRONTEND=\"noninteractive\"; apt-get update && apt-get install -y apt-utils && apt-get install -y curl\n\nRUN curl -s https://packagecloud.io/install/repositories/robosoft-ai/SMACC/script.deb.sh | sudo bash\nRUN apt-get install -y ros-melodic-smacc ros-melodic-sm-dance-bot-strikes-back ros-melodic-sm-atomic\n\nRUN curl -s https://b0e12e65a4f16bfc4594206c69dce2a49a5eabd04efb7540:@packagecloud.io/install/repositories/robosoft-ai/SMACC_viewer/script.deb.sh  | bash\nRUN apt-get -y install ros-melodic-smacc-viewer\n\nWORKDIR /root\n"
  },
  {
    "path": "smacc_ci/docker/ros_melodic_ubuntu_18.04/build.sh",
    "content": "#!/bin/bash\nsudo docker build -t smacc_melodic_ubuntu_1804 .\n"
  },
  {
    "path": "smacc_ci/docker/ros_melodic_ubuntu_18.04/examples/run_sm_atomic.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_kinetic_ubuntu_1604 bash -c \"source /opt/ros/melodic/setup.bash; roslaunch sm_atomic sm_atomic.launch & rosrun smacc_viewer smacc_viewer_node.py\"\n"
  },
  {
    "path": "smacc_ci/docker/ros_melodic_ubuntu_18.04/run_bash.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_melodic_ubuntu_1804 bash\n"
  },
  {
    "path": "smacc_ci/docker/ros_noetic_ubuntu_20.04/Dockerfile",
    "content": "FROM ros:noetic-ros-base-focal\n\nENV PATH /usr/local/nvidia/bin:${PATH}\nENV LD_LIBRARY_PATH /usr/local/nvidia/lib:/usr/local/nvidia/lib64:${LD_LIBRARY_PATH}\n\nENV HOME /root\nENV DEBIAN_FRONTEND noninteractive\n\n# install ros packages\nRUN apt-get update && apt-get install -y \\\n    ros-noetic-robot=1.4.1-0* \\\n    && rm -rf /var/lib/apt/lists/*\n\n# SYSTEM DEPENDENCIES\n#----------------------------------------------------------\nRUN echo \"regen\"\nRUN export DEBIAN_FRONTEND=\"noninteractive\"; apt-get update && apt-get install -y apt-utils && apt-get install -y curl\n\nRUN curl -s https://packagecloud.io/install/repositories/robosoft-ai/SMACC/script.deb.sh | sudo bash\nRUN apt-get install -y ros-noetic-smacc ros-melodic-sm-dance-bot-strikes-back ros-melodic-sm-atomic\n\nRUN curl -s https://b0e12e65a4f16bfc4594206c69dce2a49a5eabd04efb7540:@packagecloud.io/install/repositories/robosoft-ai/SMACC_viewer/script.deb.sh  | bash\nRUN apt-get -y install ros-noetic-smacc-viewer\n\nWORKDIR /root\n"
  },
  {
    "path": "smacc_ci/docker/ros_noetic_ubuntu_20.04/build.sh",
    "content": "#!/bin/bash\nsudo docker build -t smacc_noetic_ubuntu_2004 .\n"
  },
  {
    "path": "smacc_ci/docker/ros_noetic_ubuntu_20.04/examples/run_sm_atomic.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_kinetic_ubuntu_1604 bash -c \"source /opt/ros/melodic/setup.bash; roslaunch sm_atomic sm_atomic.launch & rosrun smacc_viewer smacc_viewer_node.py\"\n"
  },
  {
    "path": "smacc_ci/docker/ros_noetic_ubuntu_20.04/run_bash.sh",
    "content": "#!/bin/bash\n./build.sh\nxhost +\nsudo docker run -e DISPLAY=$DISPLAY -v /tmp/.X11-unix:/tmp/.X11-unix -it smacc_noetic_ubuntu_2004 bash\n"
  },
  {
    "path": "smacc_ci/gh-pages.sh",
    "content": "#!/bin/bash\n\nDIR=\"$( cd \"$( dirname \"${BASH_SOURCE[0]}\" )\" && pwd )\"\n\nGITHUB_USER=robosoft-ai\nCATKIN_WORKSPACE_ROOT=`realpath $DIR/..`\nGITHUB_TOKEN=$1\n\n#---- TEST GHPAGES LOCALLY VARIABLES------\n# uncomment this for local testing and comment the TRAVIS BLOCK\n#GITHUB_USER=\n#GIT_BRANCH=master\n#TRAVIS_REPO_SLUG=smacc\n#GITHUB_TOKEN=\n#CATKIN_WORKSPACE_ROOT=`pwd`/../..\n# ----------- TRAVIS --------------------------\n# industrial_ci catkin workspace\n#CATKIN_WORKSPACE_ROOT=/root/target_ws\n#---------------------------------------\nREPO_URL=github.com/robosoft-ai/smacc_doxygen.git\n\nDIRECTORY=$(cd `dirname $0` && pwd)\necho $DIRECTORY\n\necho \"GH-PAGES\"\nif [ -n \"$GITHUB_TOKEN\" ]; then\n    ROOT_DIR= `pwd`\n    echo \"GH - PAGES script working directory: $ROOT_DIR\"\n    cd \"$ROOT_DIR\"\n\n    #find / | grep SMACC\n\n    # apt-get install -y git\n\n    # source $CATKIN_WORKSPACE_ROOT/install/setup.bash\n    #source /root/catkin_ws/install/setup.bash\n\n    #remove cloned folder just in case it already existed\n    mkdir -p $CATKIN_WORKSPACE_ROOT/tmp/doc\n    rm -R $CATKIN_WORKSPACE_ROOT/tmp/doc\n\n    # This generates a `web` directory containing the website.\n    echo \"cloning gh-pages\"\n    git clone https://robosoft-ai:$GITHUB_TOKEN@$REPO_URL --branch gh-pages $CATKIN_WORKSPACE_ROOT/tmp/doc\n\n    echo \"removing specific branch folder from repo clone..\"\n    cd $CATKIN_WORKSPACE_ROOT/tmp/doc\n    rm -r $GIT_BRANCH >/dev/null\n    mkdir -p $GIT_BRANCH\n\n    echo \"cd $CATKIN_WORKSPACE_ROOT\"\n    ls $CATKIN_WORKSPACE_ROOT/src\n\n    cd $CATKIN_WORKSPACE_ROOT/src/SMACC\n    ls\n\n    echo \"executing doxygen command\"\n    doxygen smacc_ci/Doxyfile\n\n    echo \"moving result files to branch directory...\"\n    stat $CATKIN_WORKSPACE_ROOT/tmp/doc\n    stat $CATKIN_WORKSPACE_ROOT/tmp/doc/$GIT_BRANCH\n    ls $CATKIN_WORKSPACE_ROOT/tmp\n    mv $CATKIN_WORKSPACE_ROOT/tmp/html $CATKIN_WORKSPACE_ROOT/tmp/doc/$GIT_BRANCH\n    mv $CATKIN_WORKSPACE_ROOT/tmp/latex $CATKIN_WORKSPACE_ROOT/tmp/doc/$GIT_BRANCH\n\n    #git init\n    #git checkout -b gh-pages\n    echo \"cd $CATKIN_WORKSPACE_ROOT/tmp/doc/$GIT_BRANCH -> directories:\"\n    ls $CATKIN_WORKSPACE_ROOT/tmp/doc\n    cd $CATKIN_WORKSPACE_ROOT/tmp/doc/$GIT_BRANCH\n\n    git add .\n    #git add -f $CATKIN_WORKSPACE_ROOT/tmp/doc/index.html\n    #echo \"------LIST OF FILES ------\"\n    #find .\n    echo \"committing new documentation\"\n\n    echo `which git`\n    echo $(git -c user.name='travis' -c user.email='travis' commit -q -m \"gh-pages travis\")\n    git -c user.name='travis' -c user.email='travis' commit -q -m \"gh-pages travis\"\n\n    #git diff origin/master..HEAD\n    echo \"pushing new documentation\"\n    echo \"GITHUB USER: $GITHUB_USER\"\n\n    # Make sure to make the output quiet, or else the API token will leak!\n    # This works because the API key can replace your password.\n    git push -f -v https://robosoft-ai:$GITHUB_TOKEN@$REPO_URL gh-pages #> pushout.txt\n    #cat pushout.txt\n\n    # going back to travis build dir\n    cd \"$ROOT_DIR\"\nfi\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/.gitignore",
    "content": "*.private.sh\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/Dockerfile",
    "content": "\nARG ROS_DOCKER_BASE\nFROM $ROS_DOCKER_BASE\n\nARG UBUNTU_VERSION\nARG ROS_VERSION_NAME\nARG GITHUB_USER\nARG GITHUB_TOKEN\nARG PACKAGE_CLOUD_USER\nARG PACKAGE_CLOUD_TOKEN\n\n# PYTHON_VERSION could be empty, or \"3\"\nARG PYTHON_VERSION=\"\"\n\nENV PATH /usr/local/nvidia/bin:${PATH}\nENV LD_LIBRARY_PATH /usr/local/nvidia/lib:/usr/local/nvidia/lib64:${LD_LIBRARY_PATH}\n\nENV GITHUB_USER=$GITHUB_USER\nENV GITHUB_TOKEN=$GITHUB_TOKEN\nENV PACKAGE_CLOUD_USER=$PACKAGE_CLOUD_USER\nENV PACKAGE_CLOUD_TOKEN=$PACKAGE_CLOUD_TOKEN\nENV UBUNTU_VERSION=$UBUNTU_VERSION\nENV ROS_VERSION_NAME=$ROS_VERSION_NAME\n\nRUN echo \"rosversion: $ROS_VERSION_NAME\"\nRUN echo \"pythonversion: $ROS_VERSION_NAME\"\nRUN echo \"ubuntu version: $UBUNTU_VERSION\"\nRUN echo \"github user: $GITHUB_USER\"\nRUN echo \"github token: $GITHUB_TOKEN\"\nRUN echo \"packagecloud user: $PACKAGE_CLOUD_USER\"\nRUN echo \"packagecloud token: $PACKAGE_CLOUD_TOKEN\"\n\nENV HOME /root\nENV DEBIAN_FRONTEND noninteractive\n\nRUN apt-get update && apt-get -y install curl\nRUN curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -\n\nRUN apt-get update && apt-get install -y \\\n    ros-$ROS_VERSION_NAME-robot \\\n&& rm -rf /var/lib/apt/lists/*\n\n# SYSTEM DEPENDENCIES\n#----------------------------------------------------------\nRUN export DEBIAN_FRONTEND=\"noninteractive\"; apt-get update && apt-get install -y apt-utils && apt-get install -y git fakeroot\n\nRUN apt-get update\nRUN apt-get upgrade -y\nRUN apt-get install -y python$PYTHON_VERSION-argcomplete python$PYTHON_VERSION-bloom dh-make\n\n# INSTALL PACKAGE CLOUD SOFTWARE\n# --------------------------------------------------------------\nRUN apt-get -y install ruby-dev nano\nRUN gem install rake\nRUN gem install package_cloud\n\n# DOWNLOAD MAIN REPOSITORY\n#----------------------------------------------------------\nRUN echo \"regen\"\nRUN echo \"downloading smacc repo: \"\nRUN echo \"branch name: $ROS_VERSION_NAME\"\nRUN git clone --single-branch --branch $ROS_VERSION_NAME-devel https://github.com/robosoft-ai/SMACC.git /root/src/SMACC\nWORKDIR /root/src/SMACC\nRUN git submodule init\nRUN git submodule update\n\nWORKDIR /root/src\nRUN echo \"downloading smacc_viewer repo with github user: ${GITHUB_USER}\"\nRUN git clone https://github.com/robosoft-ai/robosoft-ai_msgs.git /root/src/robosoft-ai_msgs\nWORKDIR /root\n\n\n#workaround for noetic, that should work just with rosdep\nRUN apt-get install -y libpcl-dev ros-$ROS_VERSION_NAME-lms1xx ros-$ROS_VERSION_NAME-pcl-ros\n#RUN echo \"regen\"\n# BUILD SMACC\n# -----------------------------------------------------------------\nRUN bash -c \"source /opt/ros/$ROS_VERSION_NAME/setup.bash; cd /root; rosdep install --from-paths src --ignore-src -r -y; \"\n\nRUN apt-get install -y libpcl-dev ros-$ROS_VERSION_NAME-pcl-ros\nRUN bash -c \"source /opt/ros/$ROS_VERSION_NAME/setup.bash; cd /root; catkin_make -j 1\"\n\n# BUILD DEBIAN FILES\n# ------------------------------------------------------------------------\n\nRUN echo \"yaml file:/root/src/SMACC/smacc_ci/rosdep_${ROS_VERSION_NAME}.yaml\" > /etc/ros/rosdep/sources.list.d/50-my-packages.list\nRUN rosdep update\n\n\nWORKDIR /root\nRUN echo \"regen1\"\nADD generate_debs.py /root/src/SMACC/smacc_ci/packagecloud_docker/generate_debs.py\nADD generate_smacc_debs.bash /root/src/SMACC/smacc_ci/packagecloud_docker/generate_smacc_debs.bash\n\nWORKDIR /root\nRUN echo \"... ROS_VERSION: $ROS_VERSION_NAME\"\nRUN echo \"... UBUNTU_VERSION, $UBUNTU_VERSION\"\n\nRUN bash -c \"source devel/setup.bash; ./src/SMACC/smacc_ci/packagecloud_docker/generate_smacc_debs.bash $ROS_VERSION_NAME src $UBUNTU_VERSION $PACKAGE_CLOUD_TOKEN $PACKAGE_CLOUD_USER\"\n#RUN bash -c 'source devel/setup.bash; python$PYTHON_VERSION  src/SMACC/smacc_ci/packagecloud_docker/generate_debs.py -ros_version=\"$ROS_VERSION_NAME\" -src_folder=\"src/SMACC\" -token=\"$PACKAGE_CLOUD_TOKEN\" -repo_owner=\"$PACKAGE_CLOUD_USER\" -ubuntu_version=\"$UBUNTU_VERSION\"'\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/build_ubuntu_16_04_kinetic.sh",
    "content": "#!/bin/bash\necho \"build docker image with github user: $1\"\necho \"build docker image with packagecloud user: $3\"\nsudo docker build --build-arg ROS_DOCKER_BASE=\"ros:kinetic-robot\" --build-arg ROS_VERSION_NAME=\"kinetic\" --build-arg UBUNTU_VERSION=\"xenial\" --build-arg GITHUB_USER=\"$1\" --build-arg GITHUB_TOKEN=\"$2\" --build-arg PACKAGE_CLOUD_USER=\"$3\" --build-arg PACKAGE_CLOUD_TOKEN=\"$4\" -t package_cloud_tool_docker .\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/build_ubuntu_18_04_melodic.sh",
    "content": "#!/bin/bash\necho \"build docker image with github user: $1\"\necho \"build docker image with packagecloud user: $3\"\nsudo docker build --build-arg ROS_DOCKER_BASE=\"ros:melodic-robot\" --build-arg ROS_VERSION_NAME=\"melodic\" --build-arg UBUNTU_VERSION=\"bionic\" --build-arg GITHUB_USER=\"$1\" --build-arg GITHUB_TOKEN=\"$2\" --build-arg PACKAGE_CLOUD_USER=\"$3\" --build-arg PACKAGE_CLOUD_TOKEN=\"$4\" -t package_cloud_tool_docker .\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/build_ubuntu_20_04_noetic.sh",
    "content": "#!/bin/bash\necho \"build docker image with github user: $1\"\necho \"build docker image with packagecloud user: $3\"\nsudo docker build --build-arg ROS_DOCKER_BASE=\"ros:noetic-robot\" --build-arg ROS_VERSION_NAME=\"noetic\" --build-arg UBUNTU_VERSION=\"focal\" --build-arg GITHUB_USER=\"$1\" --build-arg GITHUB_TOKEN=\"$2\" --build-arg PACKAGE_CLOUD_USER=\"$3\" --build-arg PACKAGE_CLOUD_TOKEN=\"$4\" --build-arg PYTHON_VERSION=\"3\" -t package_cloud_tool_docker .\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/generate_debs.py",
    "content": "# Copyright 2021 RobosoftAI Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\n# /bin/python\n# Author: Pablo Iñigo Blasco (github: pabloinigoblasco) 2019\n\n\nimport rospkg\nimport subprocess\nimport os\nimport shutil\nimport re\n\n# src/smacc_ci/generate_debs.py -src_folder src\n\n\ndef build_deb_package(\n    workspace_source_folder, package_name, packagepath, ubuntu_version, ros_distro, already_visited\n):\n    os.chdir(workspace_source_folder)\n    print(\"------------------------------------------------------------\")\n    print(\"Working folder: \" + str(os.getcwd()))\n    print(\"Building debian package: \" + str(package_name))\n    cmd = (\n        \"bloom-generate rosdebian --os-name ubuntu --os-version \"\n        + str(ubuntu_version)\n        + \" --ros-distro \"\n        + str(ros_distro)\n        + \" \"\n        + str(packagepath)\n    )\n\n    # finding actual source package directory of the package in the workspace\n    develpackagefolder = None\n    for root, dirs, files in os.walk(workspace_source_folder, topdown=False):\n        if \"package.xml\" in files and package_name == root.split(\"/\")[-1] and \"debian\" not in root:\n            print(root)\n            develpackagefolder = root\n            break\n\n    if develpackagefolder is None:\n        print(\"ERROR: package \" + str(package_name) + \" not found in workspace\")\n\n    localpackagepath = develpackagefolder\n    print(f\"local package path: {localpackagepath} \")\n\n    # cleaning possible previous wrong builds\n    if os.path.exists(os.path.join(localpackagepath, \"debian\")):\n        shutil.rmtree(os.path.join(localpackagepath, \"debian\"))\n\n    # executing bloom to generate debian-fakeroot build data\n    print(cmd)\n    bloomprocess = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE)\n    bloomprocess.wait()\n    print(\"bloom process finished: \" + str(bloomprocess.returncode))\n\n    for line in bloomprocess.stdout:\n        print(str(line))\n\n    print(\"------------------------------------------------------------\")\n    os.chdir(workspace_source_folder)\n    print(\" - Local package path: \" + localpackagepath)\n    print(\" - Workspace directory:\")\n    print(os.getcwd())\n    print(\" - list localpackagepath:\")\n    print(os.listdir(localpackagepath))\n\n    # copy the debian folder generated by bloom inside the package\n    shutil.move(\"debian\", os.path.join(localpackagepath, \"debian\"))\n\n    os.chdir(localpackagepath)\n    fakerootprocess = subprocess.Popen(\"fakeroot debian/rules binary\", shell=True)\n    (result, err) = fakerootprocess.communicate()\n\n    print(\"--------------------\")\n    os.chdir(workspace_source_folder)\n\n    firstregexstr = \".*ros-\" + ros_distro + r\"-.*\\.deb$\"\n    regexstr = \".*ros-\" + ros_distro + \"-\" + package_name.replace(\"_\", \"-\") + r\"_.*\\.deb$\"\n    print(\"Finding deb package: \" + str(regexstr))\n\n    thisfolderfiles = []\n    for root, dirs, files in os.walk(workspace_source_folder, topdown=False):\n        thisfolderfiles = thisfolderfiles + [os.path.join(root, f) for f in files]\n\n    debianfiles = [f for f in thisfolderfiles if re.search(firstregexstr, f)]\n    print(\"DETECTED DEBIAN FILES:\")\n    for d in debianfiles:\n        print(f\"- {d}\")\n\n    visited_debian_files = [\n        f for f in debianfiles if re.search(regexstr, f) and f not in already_visited\n    ]\n    debianfilename = visited_debian_files[0]\n    print(\"VISITED DEBIAN FILES:\")\n    for d in visited_debian_files:\n        print(f\"- {d}\")\n\n    print(\"Debian file found: \")\n    print(debianfilename)\n\n    os.chdir(localpackagepath)\n    shutil.rmtree(\".obj-x86_64-linux-gnu\")\n    shutil.rmtree(\"debian\")\n\n    print(\"installing debian package (required to build new debs): \" + debianfilename)\n    installdebiantask = subprocess.Popen(\"sudo dpkg -i \" + debianfilename, shell=True)\n    installdebiantask.wait()\n\n    return debianfilename\n\n\ndef iterate_debian_generation(\n    workspace_source_folder, package_names, identified_install_packages, osversion, rosversion\n):\n    os.chdir(workspace_source_folder)\n    debianfiles = []\n    for pname in package_names:\n        try:\n            debianfiles.append(\n                build_deb_package(\n                    workspace_source_folder,\n                    pname,\n                    identified_install_packages[pname],\n                    osversion,\n                    rosversion,\n                    debianfiles,\n                )\n            )\n        except Exception as ex:\n            print(ex)\n            print(\"ERROR: package \" + str(pname) + \" could not be built\")\n            print(\"existing packages: \" + str(identified_install_packages.keys()))\n            raise ex\n\n    return debianfiles\n\n\ndef get_identified_packages(workspace_folder):\n    print(\"finding packages in workspace folder:\" + workspace_folder)\n\n    rospack = rospkg.RosPack()\n    packages = rospack.list()\n    packagesl = list(packages)\n    identified_install_packages = {}\n\n    print(\"packages2: \" + str(packagesl))\n    exclude_with_words = [\"ridgeback\", \"mecanum\", \"catkin\"]\n    for pname in packagesl:\n        packpath = rospack.get_path(pname)\n        print(pname)\n        if workspace_folder in packpath:\n            if any([True for excludedword in exclude_with_words if excludedword in pname]):\n                continue\n\n            identified_install_packages[pname] = packpath\n    return identified_install_packages\n\n\ndef push_debian_files_package_cloud(repo_owner, reponame, osname, osversion, debianfiles):\n    for debf in debianfiles:\n        print(\"pushing debfile\")\n        cmd = (\n            \"package_cloud push \"\n            + repo_owner\n            + \"/\"\n            + reponame\n            + \"/\"\n            + osname\n            + \"/\"\n            + osversion\n            + \" \"\n            + debf\n        )\n        print(cmd)\n        push_debian_task = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE)\n\n        push_debian_task.wait()\n\n        for line in push_debian_task.stdout:\n            print(str(line))\n\n\ndef remove_debian_files(repo_owner, reponame, osname, osversion, debianfiles):\n    for debf in debianfiles:\n        shortdebfile = debf.split(\"/\")[-1]\n        print(\"removing/yanking debfile\")\n        push_debian_task = subprocess.Popen(\n            \"package_cloud yank \"\n            + repo_owner\n            + \"/\"\n            + reponame\n            + \"/\"\n            + osname\n            + \"/\"\n            + osversion\n            + \" \"\n            + shortdebfile,\n            shell=True,\n        )\n        push_debian_task.wait()\n\n\n# ------------------------ SMACC PACKAGES -----------------------\n\n\ndef create_and_push_smacc_debians(osname, osversion, rosversion, reponame, action, packages: list):\n    workspace_source_folder = os.path.join(workspace_folder, relative_smacc_folder)\n    identified_install_packages = get_identified_packages(workspace_folder)\n\n    print(\"workspace source folder: \" + workspace_source_folder)\n    print(\"packages: \" + str(packages))\n    print(\"--\")\n    print(\"identified packages: \" + str(identified_install_packages.keys()))\n\n    if \"build\" in action:\n        smacc_debian_files = iterate_debian_generation(\n            workspace_source_folder, packages, identified_install_packages, osversion, rosversion\n        )\n    else:\n        smacc_debian_files = []\n        for package_name in packages:\n            firstregexstr = \".*ros-\" + rosversion + r\"-.*\\.deb$\"\n            regexstr = \".*ros-\" + rosversion + \"-\" + package_name.replace(\"_\", \"-\") + r\"_.*\\.deb$\"\n            print(\"Finding deb package: \" + str(regexstr))\n\n            thisfolderfiles = []\n            for root, dirs, files in os.walk(workspace_source_folder, topdown=False):\n                thisfolderfiles = thisfolderfiles + [os.path.join(root, f) for f in files]\n\n            debianfiles = [f for f in thisfolderfiles if re.search(firstregexstr, f)]\n            print(\"DETECTED DEBIAN FILES:\")\n            for d in debianfiles:\n                print(f\"- {d}\")\n                smacc_debian_files.append(d)\n\n    if \"push\" in action:\n        if reponame is None:\n            print(\"ERROR: reponame is required for push action\")\n            raise Exception(\"reponame is required for push action\")\n\n        create_repo_task = subprocess.Popen(\"package_cloud repository create smacc\", shell=True)\n        create_repo_task.wait()\n\n        # ----- PUSHING TO SMACC --------------\n        remove_debian_files(repo_owner, \"smacc\", osname, osversion, smacc_debian_files)\n        push_debian_files_package_cloud(\n            repo_owner, reponame, osname, osversion, smacc_debian_files\n        )\n\n    return smacc_debian_files\n\n\nif __name__ == \"__main__\":\n    # === requirements for the build machine ==\n    # sudo apt-get install ruby-dev rake\n    # sudo gem update --system\n    # sudo gem install package_cloud\n    # == OR ==\n    # curl -s https://packagecloud.io/install/repositories/fdio/tutorial/script.deb.sh | sudo bash\n\n    import argparse\n    import argcomplete\n\n    rospack = rospkg.RosPack()\n    packages = rospack.list()\n    packagesl = list(packages)\n\n    parser = argparse.ArgumentParser()\n\n    parser.add_argument(\"-src_folder\", help=\"smacc workspace folder\", required=True)\n\n    parser.add_argument(\n        \"-ros_version\", help=\"The version of ros, ie: noetic\", default=\"noetic\", type=str\n    )\n\n    parser.add_argument(\n        \"-ubuntu_version\", help=\"The version of ros, ie: focal\", default=\"focal\", type=str\n    )\n\n    parser.add_argument(\"-repo_owner\", help=\"Package cloud repo owner\", required=True)\n    parser.add_argument(\"-repo_name\", help=\"Package cloud repo name\", default=None)\n    parser.add_argument(\"-token\", help=\"Package cloud repo token\", default=\"\")\n\n    parser.add_argument(\"-packages\", help=\"packages\", nargs=\"+\", required=True)\n\n    parser.add_argument(\"-action\", default=\"build_push\", help=\"build|push|build_push\")\n\n    parser.add_argument(\"-help\", help=\"Help command\")\n\n    argcomplete.autocomplete(parser)\n\n    args = parser.parse_args()\n\n    osname = \"ubuntu\"\n    osversion = args.ubuntu_version\n    ros_version = args.ros_version\n\n    print(\"args:\" + str(args))\n    print(\"rosversion: \" + ros_version)\n    print(\"ubuntu: \" + osversion)\n\n    relative_smacc_folder = args.src_folder\n    workspace_folder = os.path.abspath(os.path.join(os.getcwd(), \".\"))\n\n    repo_owner = args.repo_owner\n\n    print(\"CREATING TOKEN FILE FOR PACKAGE CLOUD:\")\n    homefolder = \"/tmp\"  # os.getenv(\"HOME\")\n    packagecloud_token_filepath = os.path.join(homefolder, \".packagecloud\")\n\n    outfile = open(packagecloud_token_filepath, \"w\")\n    outfile.write('{\"token\":\"%s\"}' % args.token)\n    outfile.close()\n\n    smacc_debians = create_and_push_smacc_debians(\n        osname, osversion, ros_version, args.repo_name, args.action, args.packages\n    )\n    print(\"SMACC DEBIAN'S: \" + str(smacc_debians))\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/generate_smacc_debs.bash",
    "content": "#!/bin/bash\n\nSCRIPT_DIR=\"$( cd \"$( dirname \"${BASH_SOURCE[0]}\" )\" >/dev/null 2>&1 && pwd )\"\n\nROS_VERSION_NAME=$1\nSOURCE_FOLDER=$2\nUBUNTU_VERSION=$3\nPACKAGE_CLOUD_TOKEN=$4\nPACKAGE_CLOUD_USER=$5\n\necho \"ROS_VERSION_NAME: $ROS_VERSION_NAME\"\necho \"SOURCE_FOLDER: $SOURCE_FOLDER\"\necho \"PACKAGE_CLOUD_TOKEN: $PACKAGE_CLOUD_TOKEN\"\necho \"PACKAGE_CLOUD_USER: $PACKAGE_CLOUD_USER\"\necho \"UBUNTU_VERSION: $UBUNTU_VERSION\"\n\npython3 $SCRIPT_DIR/generate_debs.py -repo_name smacc -ros_version=$ROS_VERSION_NAME -src_folder=$SOURCE_FOLDER -token=$PACKAGE_CLOUD_TOKEN -repo_owner=$PACKAGE_CLOUD_USER -ubuntu_version=$UBUNTU_VERSION -packages forward_global_planner smacc_msgs smacc smacc_runtime_test sr_all_events_go sr_conditional sr_event_countdown keyboard_client multirole_sensor_client ros_publisher_client ros_timer_client move_base_z_client_plugin forward_local_planner backward_global_planner undo_path_global_planner backward_local_planner move_group_interface_client\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/local_build_18_04_melodic.sh",
    "content": "export ROS_VERSION_NAME=\"melodic\"\nexport UBUNTU_VERSION=\"bionic\"\nGITHUB_USER=\"$1\"\nGITHUB_TOKEN=\"$2\"\nPACKAGE_CLOUD_USER=\"$3\"\nPACKAGE_CLOUD_TOKEN=\"$4\"\n\nsource /opt/ros/melodic/setup.bash --extend\nDIR=\"$( cd \"$( dirname \"${BASH_SOURCE[0]}\" )\" >/dev/null 2>&1 && pwd )\"\n\nexport SMACC_SRC_FOLDER=`realpath $DIR/../..`\necho $SMACC_SRC_FOLDER\nsource $SMACC_SRC_FOLDER/../../devel/setup.bash\npython  $SMACC_SRC_FOLDER/smacc_ci/packagecloud_docker/generate_debs.py -ros_version=\"$ROS_VERSION_NAME\" -src_folder=\"$SMACC_SRC_FOLDER\" -smacc_viewer_src_folder=\"src/SMACC_Viewer\" -token=\"$PACKAGE_CLOUD_TOKEN\" -repo_owner=\"$PACKAGE_CLOUD_USER\" -ubuntu_version=\"$UBUNTU_VERSION\"\n"
  },
  {
    "path": "smacc_ci/packagecloud_docker/local_build_20_04_noetic.sh",
    "content": "export ROS_VERSION_NAME=\"noetic\"\nexport UBUNTU_VERSION=\"bionic\"\nGITHUB_USER=\"$1\"\nGITHUB_TOKEN=\"$2\"\nPACKAGE_CLOUD_USER=\"$3\"\nPACKAGE_CLOUD_TOKEN=\"$4\"\n\nsource /opt/ros/noetic/setup.bash --extend\nDIR=\"$( cd \"$( dirname \"${BASH_SOURCE[0]}\" )\" >/dev/null 2>&1 && pwd )\"\n\nexport SMACC_SRC_FOLDER=`realpath $DIR/../..`\necho $SMACC_SRC_FOLDER\nsource $SMACC_SRC_FOLDER/../../devel/setup.bash\npython  $SMACC_SRC_FOLDER/smacc_ci/packagecloud_docker/generate_debs.py -ros_version=\"$ROS_VERSION_NAME\" -src_folder=\"$SMACC_SRC_FOLDER\" -smacc_viewer_src_folder=\"src/SMACC_Viewer\" -token=\"$PACKAGE_CLOUD_TOKEN\" -repo_owner=\"$PACKAGE_CLOUD_USER\" -ubuntu_version=\"$UBUNTU_VERSION\"\n"
  },
  {
    "path": "smacc_ci/rosdep_kinetic.yaml",
    "content": "smacc_msgs:\n  ubuntu: [ros-kinetic-smacc-msgs]\nsmacc:\n  ubuntu: [ros-kinetic-smacc]\nsmacc_navigation_plugin:\n  ubuntu: [ros-kinetic-smacc-navigation-plugin]\nsmacc_sensors:\n  ubuntu: [ros-kinetic-smacc-sensors]\nmove_base_z_client_plugin:\n  ubuntu: [ros-kinetic-move-base-z-client-plugin]\nmove_group_interface_client:\n  ubuntu: [ros-kinetic-moveit-z-client]\nros_timer_client:\n    ubuntu: [ros-kinetic-ros-timer-client]\nros_publisher_client:\n    ubuntu: [ros-kinetic-ros-publisher-client]\nmultirole_sensor_client:\n  ubuntu: [ros-kinetic-multirole-sensor-client]\nsr_all_events_go:\n  ubuntu: [ros-kinetic-sr-all-events-go]\nsr_event_countdown:\n  ubuntu: [ros-kinetic-sr-event-countdown]\neg_random_generator:\n  ubuntu: [ros-kinetic-sr-random-generator]\nsr_conditional:\n  ubuntu: [ros-kinetic-sr-conditional]\nforward_global_planner:\n  ubuntu: [ros-kinetic-forward-global-planner]\nsm_dance_bot:\n  ubuntu: [ros-kinetic-sm-dance-bot]\nsmacc_runtime_test:\n   ubuntu: [ros-kinetic-smacc-runtime-test]\n"
  },
  {
    "path": "smacc_ci/rosdep_melodic.yaml",
    "content": "smacc_msgs:\n  ubuntu: [ros-melodic-smacc-msgs]\nsmacc:\n  ubuntu: [ros-melodic-smacc]\nsmacc_navigation_plugin:\n  ubuntu: [ros-melodic-smacc-navigation-plugin]\nsmacc_sensors:\n  ubuntu: [ros-melodic-smacc-sensors]\nmove_base_z_client_plugin:\n  ubuntu: [ros-melodic-move-base-z-client-plugin]\nmove_group_interface_client:\n  ubuntu: [ros-melodic-moveit-z-client]\nros_timer_client:\n  ubuntu: [ros-melodic-ros-timer-client]\nros_publisher_client:\n  ubuntu: [ros-melodic-ros-publisher-client]\nmultirole_sensor_client:\n  ubuntu: [ros-melodic-multirole-sensor-client]\nsr_all_events_go:\n  ubuntu: [ros-melodic-sr-all-events-go]\nsr_event_countdown:\n  ubuntu: [ros-melodic-sr-event-countdown]\nsr_conditional:\n  ubuntu: [ros-melodic-sr-conditional]\nsm_dance_bot:\n  ubuntu: [ros-melodic-sm-dance-bot]\nforward_global_planner:\n  ubuntu: [ros-melodic-forward-global-planner]\nsmacc_runtime_test:\n   ubuntu: [ros-melodic-smacc-runtime-test]\n"
  },
  {
    "path": "smacc_ci/rosdep_noetic.yaml",
    "content": "smacc_msgs:\n  ubuntu: [ros-noetic-smacc-msgs]\nsmacc:\n  ubuntu: [ros-noetic-smacc]\nsmacc_navigation_plugin:\n  ubuntu: [ros-noetic-smacc-navigation-plugin]\nsmacc_sensors:\n  ubuntu: [ros-noetic-smacc-sensors]\nmove_base_z_client_plugin:\n  ubuntu: [ros-noetic-move-base-z-client-plugin]\nmove_group_interface_client:\n  ubuntu: [ros-noetic-moveit-z-client]\nros_timer_client:\n  ubuntu: [ros-noetic-ros-timer-client]\nros_publisher_client:\n  ubuntu: [ros-noetic-ros-publisher-client]\nmultirole_sensor_client:\n  ubuntu: [ros-noetic-multirole-sensor-client]\nsr_all_events_go:\n  ubuntu: [ros-noetic-sr-all-events-go]\nsr_event_countdown:\n  ubuntu: [ros-noetic-sr-event-countdown]\nsr_conditional:\n  ubuntu: [ros-noetic-sr-conditional]\nsm_dance_bot:\n  ubuntu: [ros-noetic-sm-dance-bot]\nforward_global_planner:\n  ubuntu: [ros-noetic-forward-global-planner]\nsmacc_runtime_test:\n   ubuntu: [ros-noetic-smacc-runtime-test]\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package battery_monitor_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* added server folders to client library\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* some refactoring in orthogonals relation with clients\n* lord microstrain client, subscriber component\n* missed a step\n* last few touchups\n* battery monitor client, and minor change on the smaccsubscriber base client\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(battery_monitor_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES battery_monitor_client\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/cl_battery_monitor.cpp\n )\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n)\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_battery_monitor_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/README.md",
    "content": ""
  },
  {
    "path": "smacc_client_library/battery_monitor_client/include/battery_monitor_client/cl_battery_monitor.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <sensor_msgs/BatteryState.h>\n\n#include <boost/asio/posix/stream_descriptor.hpp>\n#include <boost/asio.hpp>\n#include <iostream>\n#include <thread>\n\n#include <std_msgs/UInt16.h>\n\nnamespace cl_battery_monitor\n{\nclass ClBatteryMonitor : public smacc::client_bases::SmaccSubscriberClient<sensor_msgs::BatteryState>\n{\npublic:\n    ClBatteryMonitor();\n    ClBatteryMonitor(std::string topicname);\n\n    virtual ~ClBatteryMonitor();\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        smacc::client_bases::SmaccSubscriberClient<sensor_msgs::BatteryState>::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>battery_monitor_client</name>\n    <version>1.4.16</version>\n  <description>The battery_monitor_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/battery_monitor_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/server/battery_monitor_node.py",
    "content": "#!/usr/bin/env python\nimport rospy\nimport numpy\n\nfrom sensor_msgs.msg import BatteryState\n\nif __name__ == \"__main__\":\n    rospy.init_node(\"battery_node\")\n    pub = rospy.Publisher(\"battery\", BatteryState, queue_size=1)\n    tinit = rospy.Time.now().to_time()\n    speed = 0.05\n\n    try:\n        while not rospy.is_shutdown():\n            msg = BatteryState()\n\n            t = rospy.Time.now().to_time()\n            msg.charge = 10 * numpy.exp(speed * (tinit - t)) - 1.0\n\n            rospy.sleep(0.5)\n            pub.publish(msg)\n\n    except Exception as e:\n        print(e)\n"
  },
  {
    "path": "smacc_client_library/battery_monitor_client/src/battery_monitor_client/cl_battery_monitor.cpp",
    "content": "#include <battery_monitor_client/cl_battery_monitor.h>\n\nnamespace cl_battery_monitor\n{\n\nClBatteryMonitor::ClBatteryMonitor()\n{\n}\n\nClBatteryMonitor::ClBatteryMonitor(std::string topicname)\n    : smacc::client_bases::SmaccSubscriberClient<sensor_msgs::BatteryState>(topicname)\n{\n\n}\n\nClBatteryMonitor::~ClBatteryMonitor()\n{\n}\n\n}\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package keyboard_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* added server folders to client library\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* smacc improvements\n* improving/fixing bugs on smacc signals related with the smacc objects life-time. Also clients improved in the related to this.\n* battery monitor client, and minor change on the smaccsubscriber base client\n* unpushed code\n* sm_dance_bot_2\n* fixing broken build\n* second pass refactoring namespaces\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n\n* added server folders to client library\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* smacc improvements\n* improving/fixing bugs on smacc signals related with the smacc objects life-time. Also clients improved in the related to this.\n* battery monitor client, and minor change on the smaccsubscriber base client\n* unpushed code\n* sm_dance_bot_2\n* fixing broken build\n* second pass refactoring namespaces\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n\n* added server folders to client library\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* smacc improvements\n* improving/fixing bugs on smacc signals related with the smacc objects life-time. Also clients improved in the related to this.\n* battery monitor client, and minor change on the smaccsubscriber base client\n* unpushed code\n* sm_dance_bot_2\n* fixing broken build\n* second pass refactoring namespaces\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n\n* added server folders to client library\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* smacc improvements\n* improving/fixing bugs on smacc signals related with the smacc objects life-time. Also clients improved in the related to this.\n* battery monitor client, and minor change on the smaccsubscriber base client\n* unpushed code\n* sm_dance_bot_2\n* fixing broken build\n* second pass refactoring namespaces\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(keyboard_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES keyboard_client\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/cl_keyboard.cpp\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/keyboard_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\ninstall(PROGRAMS\n   server/keyboard_server_node/keyboard_server_node.py\n   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n install(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_keyboard_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/README.md",
    "content": ""
  },
  {
    "path": "smacc_client_library/keyboard_client/include/keyboard_client/cl_keyboard.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <smacc/client_bases/smacc_subscriber_client.h>\n\n#include <boost/asio/posix/stream_descriptor.hpp>\n#include <boost/asio.hpp>\n#include <iostream>\n#include <thread>\n\n#include <std_msgs/UInt16.h>\n\nnamespace cl_keyboard\n{\n//----------------- TIMER sc::event DEFINITION ----------------------------------------------\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressA : sc::event<EvKeyPressA<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressB : sc::event<EvKeyPressB<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressC : sc::event<EvKeyPressC<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressD : sc::event<EvKeyPressD<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressE : sc::event<EvKeyPressE<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressF : sc::event<EvKeyPressF<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressG : sc::event<EvKeyPressG<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressH : sc::event<EvKeyPressH<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressI : sc::event<EvKeyPressI<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressJ : sc::event<EvKeyPressJ<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressK : sc::event<EvKeyPressK<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressL : sc::event<EvKeyPressL<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressM : sc::event<EvKeyPressM<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressN : sc::event<EvKeyPressN<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressO : sc::event<EvKeyPressO<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressP : sc::event<EvKeyPressP<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressQ : sc::event<EvKeyPressQ<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressR : sc::event<EvKeyPressR<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressS : sc::event<EvKeyPressS<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressT : sc::event<EvKeyPressT<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressU : sc::event<EvKeyPressU<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressV : sc::event<EvKeyPressV<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressW : sc::event<EvKeyPressW<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressX : sc::event<EvKeyPressX<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressY : sc::event<EvKeyPressY<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvKeyPressZ : sc::event<EvKeyPressZ<TSource, TOrthogonal>>\n{\n};\n\n//------------------  KEYBOARD CLIENT ---------------------------------------------\n\nclass ClKeyboard : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\npublic:\n        smacc::SmaccSignal<void(char keypress)> OnKeyPress_;\n\n        template <typename T>\n        void OnKeyPress(void (T::*callback)(char keypress), T *object)\n        {\n                //this->connectSignal(OnKeyPress_, callback, object);\n                this->getStateMachine()->createSignalConnection(OnKeyPress_, callback, object);\n        }\n\n        ClKeyboard();\n\n        virtual ~ClKeyboard();\n\n        virtual void initialize() override;\n\n        std::function<void(std_msgs::UInt16)> postEventKeyPress;\n\n        template <typename TOrthogonal, typename TSourceObject>\n        void onOrthogonalAllocation()\n        {\n                // call to the base configuration to properly handling the message and initial message smacc events\n                smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n\n                postEventKeyPress = [=](auto unicode_keychar) {\n                        char character = (char)unicode_keychar.data;\n                        ROS_WARN(\"detected keyboard: %c\", character);\n\n                        if (character == 'a')\n                                this->postKeyEvent<EvKeyPressA<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'b')\n                                this->postKeyEvent<EvKeyPressB<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'c')\n                                this->postKeyEvent<EvKeyPressC<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'd')\n                                this->postKeyEvent<EvKeyPressD<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'e')\n                                this->postKeyEvent<EvKeyPressE<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'f')\n                                this->postKeyEvent<EvKeyPressF<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'g')\n                                this->postKeyEvent<EvKeyPressG<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'h')\n                                this->postKeyEvent<EvKeyPressH<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'y')\n                                this->postKeyEvent<EvKeyPressI<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'j')\n                                this->postKeyEvent<EvKeyPressJ<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'k')\n                                this->postKeyEvent<EvKeyPressK<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'l')\n                                this->postKeyEvent<EvKeyPressL<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'm')\n                                this->postKeyEvent<EvKeyPressM<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'n')\n                                this->postKeyEvent<EvKeyPressN<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'o')\n                                this->postKeyEvent<EvKeyPressO<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'p')\n                                this->postKeyEvent<EvKeyPressP<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'q')\n                                this->postKeyEvent<EvKeyPressQ<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'r')\n                                this->postKeyEvent<EvKeyPressR<ClKeyboard, TOrthogonal>>();\n                        else if (character == 's')\n                                this->postKeyEvent<EvKeyPressS<ClKeyboard, TOrthogonal>>();\n                        else if (character == 't')\n                                this->postKeyEvent<EvKeyPressT<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'u')\n                                this->postKeyEvent<EvKeyPressU<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'v')\n                                this->postKeyEvent<EvKeyPressV<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'w')\n                                this->postKeyEvent<EvKeyPressW<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'x')\n                                this->postKeyEvent<EvKeyPressX<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'y')\n                                this->postKeyEvent<EvKeyPressY<ClKeyboard, TOrthogonal>>();\n                        else if (character == 'z')\n                                this->postKeyEvent<EvKeyPressZ<ClKeyboard, TOrthogonal>>();\n                        OnKeyPress_(character); /*  */\n                };\n        }\n\n        void onKeyboardMessage(const std_msgs::UInt16 &unicode_keychar);\n\n        template <typename TEv>\n        void postKeyEvent()\n        {\n                ROS_WARN(\"ClKeyboard ev: %s\", smacc::demangleSymbol(typeid(TEv).name()).c_str());\n                this->postEvent<TEv>();\n        }\n\nprivate:\n        bool initialized_;\n};\n} // namespace cl_keyboard\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/include/keyboard_client/client_behaviors/cb_default_keyboard_behavior.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_client_behavior.h>\n\n#include <std_msgs/UInt16.h>\n\nnamespace cl_keyboard\n{\nclass CbDefaultKeyboardBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    ClKeyboard *ClKeyboard_;\n    std::function<void(char)> postEventKeyPress;\n\n    void onEntry()\n    {\n        this->requiresClient(ClKeyboard_);\n        this->ClKeyboard_->OnKeyPress(&CbDefaultKeyboardBehavior::OnKeyPress, this);\n    }\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        postEventKeyPress = [=](char character) {\n            if (character == 'a')\n                postKeyEvent<EvKeyPressA<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'b')\n                postKeyEvent<EvKeyPressB<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'c')\n                postKeyEvent<EvKeyPressC<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'd')\n                postKeyEvent<EvKeyPressD<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'e')\n                postKeyEvent<EvKeyPressE<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'f')\n                postKeyEvent<EvKeyPressF<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'g')\n                postKeyEvent<EvKeyPressG<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'h')\n                postKeyEvent<EvKeyPressH<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'i')\n                postKeyEvent<EvKeyPressI<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'j')\n                postKeyEvent<EvKeyPressJ<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'k')\n                postKeyEvent<EvKeyPressK<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'l')\n                postKeyEvent<EvKeyPressL<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'm')\n                postKeyEvent<EvKeyPressM<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'n')\n                postKeyEvent<EvKeyPressN<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'o')\n                postKeyEvent<EvKeyPressO<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'p')\n                postKeyEvent<EvKeyPressP<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'q')\n                postKeyEvent<EvKeyPressQ<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'r')\n                postKeyEvent<EvKeyPressR<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 's')\n                postKeyEvent<EvKeyPressS<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 't')\n                postKeyEvent<EvKeyPressT<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'u')\n                postKeyEvent<EvKeyPressU<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'v')\n                postKeyEvent<EvKeyPressV<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'w')\n                postKeyEvent<EvKeyPressW<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'x')\n                postKeyEvent<EvKeyPressX<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'y')\n                postKeyEvent<EvKeyPressY<CbDefaultKeyboardBehavior, TOrthogonal>>();\n            else if (character == 'z')\n                postKeyEvent<EvKeyPressZ<CbDefaultKeyboardBehavior, TOrthogonal>>();\n        };\n    }\n\n    void OnKeyPress(char character)\n    {\n        postEventKeyPress(character);\n    }\n\n    template <typename TEv>\n    void postKeyEvent()\n    {\n        ROS_WARN(\"CbDefaultKeyboardBehavior %ld ev: %s\", (long)(void *)this, smacc::demangleSymbol(typeid(TEv).name()).c_str());\n        auto event = new TEv();\n        this->postEvent(event);\n    }\n};\n} // namespace cl_keyboard\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>keyboard_client</name>\n    <version>1.4.16</version>\n  <description>The keyboard_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/keyboard_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/server/keyboard_server_node/keyboard_server_node.py",
    "content": "#!/usr/bin/env python\nimport rospy\nfrom std_msgs.msg import UInt16\n\nimport sys\nimport select\nimport termios\nimport tty\n\n\ndef getKey():\n    tty.setraw(sys.stdin.fileno())\n    select.select([sys.stdin], [], [], 0)\n    key = sys.stdin.read(1)\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n    return key\n\n\nif __name__ == \"__main__\":\n    settings = termios.tcgetattr(sys.stdin)\n\n    pub = rospy.Publisher(\"keyboard_unicode\", UInt16, queue_size=1)\n    rospy.init_node(\"keyboard_node\")\n\n    try:\n        while 1:\n            key = getKey()\n            # rospy.loginfo(type(key))\n            msg = UInt16()\n            msg.data = ord(key)\n\n            pub.publish(msg)\n\n    except Exception as e:\n        print(e)\n\n    finally:\n        termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n"
  },
  {
    "path": "smacc_client_library/keyboard_client/src/keyboard_client/cl_keyboard.cpp",
    "content": "#include <keyboard_client/cl_keyboard.h>\n\nnamespace cl_keyboard {\nClKeyboard::ClKeyboard() {\n  initialized_ = false;\n  topicName = \"/keyboard_unicode\";\n}\n\nClKeyboard::~ClKeyboard()\n{\n\n}\n\nvoid ClKeyboard::initialize() {\n\n  SmaccSubscriberClient<std_msgs::UInt16>::initialize();\n\n  if (!this->initialized_) {\n    this->onMessageReceived(&ClKeyboard::onKeyboardMessage, this);\n    this->initialized_ = true;\n  }\n}\n\nvoid ClKeyboard::onKeyboardMessage(const std_msgs::UInt16 &unicode_keychar) {\n\n  postEventKeyPress(unicode_keychar);\n}\n} // namespace cl_keyboard\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/README.md",
    "content": "<h2>Description</h2>\nThe MoveBaseZ client extends the ROS navigation stack in a high level way. It provides specialized navigation planners (for the ROS Navigation Stack) that navigate only using pure spinning motions and straight motions. Implements some mechanism to perform motions recording the path and undoing them later. These can be very useful in some industrial applications where the knowledge or certainty on the environment is higher (ros planners are focused on cluttered and dynamic environments).\n\n<h2>Author</h2>\nPablo Inigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package backward_global_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(backward_global_planner)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED\n  forward_global_planner\n  costmap_2d\n  geometry_msgs\n  std_msgs\n  message_generation\n  nav_core\n  nav_msgs\n  roscpp\n  tf\n)\n\nset_source_files_properties(\n  src/backward_global_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter\"\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES backward_global_planner\n  CATKIN_DEPENDS costmap_2d geometry_msgs nav_core nav_msgs roscpp tf forward_global_planner\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n ${forward_global_planner_INCLUDE_DIRS}}\n)\n\nadd_library(${PROJECT_NAME}\n  src/backward_global_planner.cpp\n)\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/backward_global_planner_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   bgp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_backward_global_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/bgp_plugin.xml",
    "content": "<library path=\"libbackward_global_planner\">\n  <class name=\"backward_global_planner/BackwardGlobalPlanner\" type=\"cl_move_base_z::backward_global_planner::BackwardGlobalPlanner\" base_class_type=\"nav_core::BaseGlobalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/include/backward_global_planner/backward_global_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <nav_core/base_global_planner.h>\n#include <nav_msgs/GetPlan.h>\n#include <nav_msgs/Path.h>\n#include <ros/ros.h>\n\nnamespace cl_move_base_z\n{\nnamespace backward_global_planner\n{\nclass BackwardGlobalPlanner : public nav_core::BaseGlobalPlanner\n{\npublic:\n    BackwardGlobalPlanner();\n\n    virtual ~BackwardGlobalPlanner();\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                  double &cost);\n\n    virtual bool createDefaultBackwardPath(const geometry_msgs::PoseStamped &start,\n                                           const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);\n\n    virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_) override;\n\nprivate:\n    ros::NodeHandle nh_;\n\n    ros::Publisher planPub_;\n\n    ros::Publisher markersPub_;\n\n    costmap_2d::Costmap2DROS *costmap_ros_;\n\n    void onForwardTrailMsg(const nav_msgs::Path::ConstPtr &trailMessage);\n\n    void publishGoalMarker(const geometry_msgs::Pose &pose, double r, double g, double b);\n\n    double skip_straight_motion_distance_; //meters\n\n    double puresSpinningRadStep_; // rads\n};\n} // namespace backward_global_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>backward_global_planner</name>\n    <version>1.4.16</version>\n  <description>The backward_global_planner package.</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n\n  <license>BSDv3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>geometry_msgs</depend>\n  <depend>message_generation</depend>\n  <depend>message_runtime</depend>\n  <depend>nav_core</depend>\n  <depend>nav_msgs</depend>\n  <depend>roscpp</depend>\n  <depend>tf</depend>\n  <depend>costmap_2d</depend>\n  <depend>dynamic_reconfigure</depend>\n  <depend>forward_global_planner</depend>\n\n  <export>\n      <nav_core plugin=\"${prefix}/bgp_plugin.xml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_global_planner/src/backward_global_planner.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <boost/assign.hpp>\n#include <boost/range/adaptor/reversed.hpp>\n#include <boost/range/algorithm/copy.hpp>\n#include <pluginlib/class_list_macros.h>\n#include <backward_global_planner/backward_global_planner.h>\n#include <fstream>\n#include <streambuf>\n#include <nav_msgs/Path.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <tf/tf.h>\n#include <tf/transform_datatypes.h>\n#include <angles/angles.h>\n#include <forward_global_planner/move_base_z_client_tools.h>\n\n//register this planner as a BaseGlobalPlanner plugin\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::backward_global_planner::BackwardGlobalPlanner, nav_core::BaseGlobalPlanner);\n\nnamespace cl_move_base_z\n{\nnamespace backward_global_planner\n{\n/**\n******************************************************************************************************************\n* Constructor()\n******************************************************************************************************************\n*/\nBackwardGlobalPlanner::BackwardGlobalPlanner()\n{\n    skip_straight_motion_distance_ = 0.2;\n}\n\nBackwardGlobalPlanner::~BackwardGlobalPlanner()\n{\n    //clear\n    nav_msgs::Path planMsg;\n    planMsg.header.stamp = ros::Time::now();\n    planPub_.publish(planMsg);\n}\n\n/**\n******************************************************************************************************************\n* initialize()\n******************************************************************************************************************\n*/\nvoid BackwardGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)\n{\n    //ROS_INFO_NAMED(\"Backwards\", \"BackwardGlobalPlanner initialize\");\n    costmap_ros_ = costmap_ros;\n    //ROS_WARN_NAMED(\"Backwards\", \"initializating global planner, costmap address: %ld\", (long)costmap_ros);\n\n    ros::NodeHandle nh;\n    planPub_ = nh.advertise<nav_msgs::Path>(\"backward_planner/global_plan\", 1);\n    markersPub_ = nh.advertise<visualization_msgs::MarkerArray>(\"backward_planner/markers\", 1);\n}\n\n/**\n******************************************************************************************************************\n* publishGoalMarker()\n******************************************************************************************************************\n*/\nvoid BackwardGlobalPlanner::publishGoalMarker(const geometry_msgs::Pose &pose, double r, double g, double b)\n{\n    double phi = tf::getYaw(pose.orientation);\n    visualization_msgs::Marker marker;\n    marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();\n    marker.header.stamp = ros::Time::now();\n    marker.ns = \"my_namespace2\";\n    marker.id = 0;\n    marker.type = visualization_msgs::Marker::ARROW;\n    marker.action = visualization_msgs::Marker::ADD;\n    marker.scale.x = 0.1;\n    marker.scale.y = 0.3;\n    marker.scale.z = 0.1;\n    marker.color.a = 1.0;\n    marker.color.r = r;\n    marker.color.g = g;\n    marker.color.b = b;\n\n    geometry_msgs::Point start, end;\n    start.x = pose.position.x;\n    start.y = pose.position.y;\n\n    end.x = pose.position.x + 0.5 * cos(phi);\n    end.y = pose.position.y + 0.5 * sin(phi);\n\n    marker.points.push_back(start);\n    marker.points.push_back(end);\n\n    visualization_msgs::MarkerArray ma;\n    ma.markers.push_back(marker);\n\n    markersPub_.publish(ma);\n}\n\n/**\n******************************************************************************************************************\n* defaultBackwardPath()\n******************************************************************************************************************\n*/\nbool BackwardGlobalPlanner::createDefaultBackwardPath(const geometry_msgs::PoseStamped &start,\n                                                      const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan)\n{\n    auto q = start.pose.orientation;\n\n    geometry_msgs::PoseStamped pose;\n    pose = start;\n\n    double dx = start.pose.position.x - goal.pose.position.x;\n    double dy = start.pose.position.y - goal.pose.position.y;\n\n    double length = sqrt(dx * dx + dy * dy);\n\n    geometry_msgs::PoseStamped prevState;\n    if (length > skip_straight_motion_distance_)\n    {\n        // skip initial pure spinning and initial straight motion\n        //ROS_INFO(\"1 - heading to goal position pure spinning\");\n        double heading_direction = atan2(dy, dx);\n        double startyaw = tf::getYaw(q);\n        double offset = angles::shortest_angular_distance(startyaw, heading_direction);\n        heading_direction = startyaw + offset;\n\n        prevState = cl_move_base_z::makePureSpinningSubPlan(start, heading_direction, plan, puresSpinningRadStep_);\n        //ROS_INFO(\"2 - going forward keep orientation pure straight\");\n\n        prevState = cl_move_base_z::makePureStraightSubPlan(prevState, goal.pose.position, length, plan);\n    }\n    else\n    {\n        prevState = start;\n    }\n\n    ROS_WARN_STREAM( \"[BackwardGlobalPlanner ] backward global plan size:  \" <<plan.size());\n    return true;\n}\n\n/**\n******************************************************************************************************************\n* makePlan()\n******************************************************************************************************************\n*/\nbool BackwardGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                     const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan)\n{\n    //ROS_WARN_NAMED(\"Backwards\", \"Backwards global planner: Generating global plan \");\n    //ROS_WARN_NAMED(\"Backwards\", \"Clearing...\");\n\n    plan.clear();\n\n    this->createDefaultBackwardPath(start, goal, plan);\n    //this->createPureSpiningAndStragihtLineBackwardPath(start, goal, plan);\n\n    //ROS_INFO_STREAM(\" start - \" << start);\n    //ROS_INFO_STREAM(\" end - \" << goal.pose.position);\n\n    //ROS_INFO(\"3 - heading to goal orientation\");\n    //double goalOrientation = angles::normalize_angle(tf::getYaw(goal.pose.orientation));\n    //cl_move_base_z::makePureSpinningSubPlan(prevState,goalOrientation,plan);\n\n    //ROS_WARN_STREAM( \"MAKE PLAN INVOKED, plan size:\"<< plan.size());\n    publishGoalMarker(goal.pose, 1.0, 0, 1.0);\n\n    nav_msgs::Path planMsg;\n    planMsg.poses = plan;\n    planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();\n\n        // check plan rejection\n    bool acceptedGlobalPlan = true;\n\n    // static const unsigned char NO_INFORMATION = 255;\n    // static const unsigned char LETHAL_OBSTACLE = 254;\n    // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;\n    // static const unsigned char FREE_SPACE = 0;\n\n    costmap_2d::Costmap2D *costmap2d = this->costmap_ros_->getCostmap();\n    for (auto &p : plan)\n    {\n        uint32_t mx, my;\n        costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);\n        auto cost = costmap2d->getCost(mx, my);\n\n        if (cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)\n        {\n            acceptedGlobalPlan = false;\n            break;\n        }\n    }\n\n    planPub_.publish(planMsg);\n\n    // this was previously set to size() <= 1, but a plan with a single point is also a valid plan (the goal)\n    return true;\n}\n\n/**\n******************************************************************************************************************\n* makePlan()\n******************************************************************************************************************\n*/\nbool BackwardGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                     const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                                     double &cost)\n{\n    cost = 0;\n    makePlan(start, goal, plan);\n    return true;\n}\n\n} // namespace backward_global_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package backward_local_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(backward_local_planner)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED\n  costmap_2d\n  geometry_msgs\n  dynamic_reconfigure\n  nav_core\n  nav_msgs\n  rosconsole\n  roscpp\n  tf\n  base_local_planner\n  move_base_msgs\n)\n\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\nset_source_files_properties(\n  src/backward_local_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter -Wno-pedantic\"\n)\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\ngenerate_dynamic_reconfigure_options(\n  cfg/BackwardLocalPlanner.cfg\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES backward_local_planner\n#  CATKIN_DEPENDS geometry_msgs nav_msgs rosconsole roscpp tf\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\nfile(GLOB_RECURSE ${PROJECT_NAME}_IncludeFilesPaths \"*.h\")\nadd_custom_target(${PROJECT_NAME}_IncludeFilesTarget SOURCES ${${PROJECT_NAME}_IncludeFilesPaths})\n\nfile(GLOB_RECURSE ${PROJECT_NAME}_CfgFilesPaths \"*.cfg\")\nadd_custom_target(${PROJECT_NAME}_CfgFilesTarget SOURCES ${${PROJECT_NAME}_CfgFilesPaths})\n\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n  ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   #src/backward_local_planner.cpp\n   src/backward_local_planner.cpp\n)\n\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/backward_local_planner_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   blp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/backward_local_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/blp_plugin.xml",
    "content": "<library path=\"libbackward_local_planner\">\n  <class name=\"backward_local_planner/BackwardLocalPlanner\" type=\"cl_move_base_z::backward_local_planner::BackwardLocalPlanner\" base_class_type=\"nav_core::BaseLocalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/cfg/BackwardLocalPlanner.cfg",
    "content": "#!/usr/bin/env python\nPACKAGE = \"backward_local_planner\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\n\ngen.add(\"k_rho\",   double_t,   1, \"point distance error gain\", 0.1 )\ngen.add(\"k_alpha\",   double_t,   1, \"angle to goal position error gain\", 0.05 )\ngen.add(\"k_betta\",   double_t,   1, \"goal angle error gain\", 0.1 )\n#gen.add(\"alpha_offset\",   double_t,   1, \"offset for alpha, used to reach the objetive backwards\", 0.0 )\n#gen.add(\"betta_offset\",   double_t,   1, \"offset for betta, used to reach the objetive backwards\", 0.0 )\ngen.add(\"carrot_distance\",   double_t,   1, \"meters. minimum distance to the next goal in the backward path\", 0.2 )\ngen.add(\"carrot_angular_distance\",   double_t,   1, \"rads. minimum angular distance to the next goal in the backward path\", 0.1 )\ngen.add(\"enable_obstacle_checking\",   bool_t,   1, \"bool\", True )\ngen.add(\"xy_goal_tolerance\",   double_t,   1, \"meters\", 0.025 )\ngen.add(\"yaw_goal_tolerance\",   double_t,   1, \"radians\", 0.05 )\ngen.add(\"pure_spinning_straight_line_mode\",   bool_t,   1, \"\", True )\n\nexit(gen.generate(PACKAGE, \"backward_local_planner\", \"BackwardLocalPlanner\"))\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/include/backward_local_planner/backward_local_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <backward_local_planner/BackwardLocalPlannerConfig.h>\n#include <dynamic_reconfigure/server.h>\n#include <geometry_msgs/PoseStamped.h>\n#include <nav_core/base_local_planner.h>\n#include <tf/tf.h>\n#include <tf/transform_listener.h>\n#include <tf2_ros/buffer.h>\n#include <Eigen/Eigen>\n\ntypedef double meter;\ntypedef double rad;\n\nnamespace cl_move_base_z\n{\nnamespace backward_local_planner\n{\nclass BackwardLocalPlanner : public nav_core::BaseLocalPlanner\n{\npublic:\n  BackwardLocalPlanner();\n\n  virtual ~BackwardLocalPlanner();\n\n  /**\n   * @brief  Given the current position, orientation, and velocity of the robot: compute velocity commands to send to\n   * the robot mobile base\n   * @param cmd_vel Will be filled with the velocity command to be passed to the robot base\n   * @return True if a valid velocity command was found, false otherwise\n   */\n  virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override;\n\n  /**\n   * @brief  Check if the goal pose has been achieved by the local planner\n   * @return True if achieved, false otherwise\n   */\n  virtual bool isGoalReached() override;\n\n  /**\n   * @brief  Set the plan that the local planner is following\n   * @param plan The plan to pass to the local planner\n   * @return True if the plan was updated successfully, false otherwise\n   */\n  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped> &plan) override;\n\n  /**\n   * @brief  Constructs the local planner\n   * @param name The name to give this instance of the local planner\n   * @param tf A pointer to a transform listener\n   * @param costmap_ros The cost map to use for assigning costs to local plans\n   */\n  void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos_);\n\n  void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos_);\n\n  void initialize();\n\nprivate:\n  void reconfigCB(::backward_local_planner::BackwardLocalPlannerConfig &config, uint32_t level);\n\n  // returns true if found\n  bool findInitialCarrotGoal(tf::Stamped<tf::Pose> &pose);\n\n  // returns true for a pure spining motion request\n  bool updateCarrotGoal(const tf::Stamped<tf::Pose> &tfpose);\n\n  bool resamplePrecisePlan();\n\n  void straightBackwardsAndPureSpinCmd(const tf::Stamped<tf::Pose> &tfpose, double vetta, double gamma,\n                                       double alpha_error, double betta_error, double rho_error,\n                                       geometry_msgs::Twist &cmd_vel);\n  void defaultBackwardCmd(const tf::Stamped<tf::Pose> &tfpose, double vetta, double gamma, double alpha_error,\n                          double betta_error, geometry_msgs::Twist &cmd_vel);\n\n  void publishGoalMarker(double x, double y, double phi);\n\n  void computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const tf::Stamped<tf::Pose> &tfpose, double &dist,\n                                                           double &angular_error);\n\n  bool checkCurrentPoseInGoalRange(const tf::Stamped<tf::Pose> &tfpose,  double angle_error, bool& inLinearGoal);\n\n  bool resetDivergenceDetection();\n\n  bool divergenceDetectionUpdate(const tf::Stamped<tf::Pose> &tfpose);\n\n  bool checkCarrotHalfPlainConstraint(const tf::Stamped<tf::Pose> &tfpose);\n\n  dynamic_reconfigure::Server<::backward_local_planner::BackwardLocalPlannerConfig> paramServer_;\n  dynamic_reconfigure::Server<::backward_local_planner::BackwardLocalPlannerConfig>::CallbackType f;\n\n  std::vector<geometry_msgs::PoseStamped> backwardsPlanPath_;\n  costmap_2d::Costmap2DROS *costmapRos_;\n\n  ros::Publisher goalMarkerPublisher_;\n\n  double k_rho_;\n  double k_alpha_;\n  double k_betta_;\n  double pure_spinning_allowed_betta_error_;\n  double linear_mode_rho_error_threshold_;\n\n  bool goalReached_;\n  bool initialPureSpinningStage_;\n  bool straightBackwardsAndPureSpinningMode_ = false;\n  bool enable_obstacle_checking_ = true;\n  bool inGoalPureSpinningState_ = false;\n\n  const double alpha_offset_ = M_PI;\n  const double betta_offset_ = 0;\n\n  double yaw_goal_tolerance_;  // radians\n  double xy_goal_tolerance_;   // meters\n\n  meter carrot_distance_;\n  rad carrot_angular_distance_;\n  meter divergenceDetectionLastCarrotLinearDistance_;\n\n  double max_linear_x_speed_;   // meters/sec\n  double max_angular_z_speed_;  // rads/sec\n\n  // references the current point inside the backwardsPlanPath were the robot is located\n  uint64_t currentCarrotPoseIndex_;\n\n  void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle,\n                          float maxtime, float dt, std::vector<Eigen::Vector3f> &outtraj);\n  Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt);\n\n  bool waiting_;\n  ros::Duration waitingTimeout_;\n  ros::Time waitingStamp_;\n};\n}  // namespace backward_local_planner\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n   <name>backward_local_planner</name>\n     <version>1.4.16</version>\n   <description>The backward_local_planner package.</description>\n\n   <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n   <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n\n   <license>BSDv3</license>\n\n   <buildtool_depend>catkin</buildtool_depend>\n   <build_depend>message_generation</build_depend>\n\n   <depend>base_local_planner</depend>\n   <depend>move_base_msgs</depend>\n\n   <build_depend>costmap_2d</build_depend>\n   <build_depend>geometry_msgs</build_depend>\n   <build_depend>nav_core</build_depend>\n   <build_depend>nav_msgs</build_depend>\n   <build_depend>std_msgs</build_depend>\n   <build_depend>pcl_ros</build_depend>\n   <build_depend>roscpp</build_depend>\n   <build_depend>tf</build_depend>\n   <build_depend>forward_global_planner</build_depend>\n\n   <build_export_depend>costmap_2d</build_export_depend>\n   <build_export_depend>geometry_msgs</build_export_depend>\n   <build_export_depend>nav_core</build_export_depend>\n   <build_export_depend>nav_msgs</build_export_depend>\n   <build_export_depend>pcl_ros</build_export_depend>\n   <build_export_depend>roscpp</build_export_depend>\n   <build_export_depend>tf</build_export_depend>\n\n   <exec_depend>costmap_2d</exec_depend>\n   <exec_depend>geometry_msgs</exec_depend>\n   <exec_depend>nav_core</exec_depend>\n   <exec_depend>nav_msgs</exec_depend>\n   <exec_depend>std_msgs</exec_depend>\n\n   <exec_depend>pcl_ros</exec_depend>\n   <exec_depend>roscpp</exec_depend>\n   <exec_depend>tf</exec_depend>\n   <exec_depend>message_runtime</exec_depend>\n\n   <export>\n      <nav_core plugin=\"${prefix}/blp_plugin.xml\" />\n      <rosdoc config=\"rosdoc.yaml\" />\n   </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/backward_local_planner/src/backward_local_planner.cpp",
    "content": "#include <angles/angles.h>\n#include <pluginlib/class_list_macros.h>\n#include <backward_local_planner/backward_local_planner.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <boost/intrusive_ptr.hpp>\n\n//register this planner as a BaseLocalPlanner plugin\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::backward_local_planner::BackwardLocalPlanner, nav_core::BaseLocalPlanner)\n\nnamespace cl_move_base_z\n{\n    namespace backward_local_planner\n    {\n\n        /**\n******************************************************************************************************************\n* BackwardLocalPlanner()\n******************************************************************************************************************\n*/\n        BackwardLocalPlanner::BackwardLocalPlanner()\n            : paramServer_(ros::NodeHandle(\"~BackwardLocalPlanner\"))\n        {\n        }\n\n        /**\n******************************************************************************************************************\n* ~BackwardLocalPlanner()\n******************************************************************************************************************\n*/\n        BackwardLocalPlanner::~BackwardLocalPlanner()\n        {\n        }\n\n        void BackwardLocalPlanner::initialize(std::string /*name*/, tf2_ros::Buffer */*tf*/, costmap_2d::Costmap2DROS *costmap_ros)\n        {\n            this->costmapRos_ = costmap_ros;\n            this->initialize();\n        }\n\n        void BackwardLocalPlanner::initialize()\n        {\n            k_rho_ = -1.0;\n            k_alpha_ = 0.5;\n            k_betta_ = -1.0; // set to zero means that orientation is not important\n            carrot_angular_distance_ = 0.4;\n            linear_mode_rho_error_threshold_ = 0.02;\n\n            f = boost::bind(&BackwardLocalPlanner::reconfigCB, this, _1, _2);\n            paramServer_.setCallback(f);\n            this->currentCarrotPoseIndex_ = 0;\n\n            ros::NodeHandle nh(\"~/BackwardLocalPlanner\");\n            nh.param(\"pure_spinning_straight_line_mode\", straightBackwardsAndPureSpinningMode_, true);\n            nh.param(\"yaw_goal_tolerance\", yaw_goal_tolerance_, 0.05);\n            nh.param(\"xy_goal_tolerance\", xy_goal_tolerance_, 0.10);\n            nh.param(\"k_rho\", k_rho_, k_rho_);\n            nh.param(\"k_betta\", k_betta_, k_betta_);\n            nh.param(\"linear_mode_rho_error_threshold\", linear_mode_rho_error_threshold_, linear_mode_rho_error_threshold_);\n\n            nh.param(\"carrot_distance\", carrot_distance_, carrot_distance_);\n            nh.param(\"carrot_angular_distance\", carrot_angular_distance_, carrot_angular_distance_);\n            nh.param(\"enable_obstacle_checking\", enable_obstacle_checking_, enable_obstacle_checking_);\n\n            nh.param(\"max_linear_x_speed\", max_linear_x_speed_, 1.0);\n            nh.param(\"max_angular_z_speed\", max_angular_z_speed_, 2.0);\n\n            // we have to do this, for example for the case we are refining the final orientation.\n            // se check at some point if the carrot is reached in \"goal linear distance\", then we go into\n            // some automatic pure-spinning mode where we only update the orientation\n            // This means that if we reach the carrot with precision we go into pure spinning mode but we cannot\n            // leave that point (maybe this could be improved)\n            if (carrot_angular_distance_ < yaw_goal_tolerance_)\n            {\n                ROS_WARN_STREAM(\"[BackwardLocalPlanner] carrot_angular_distance (\" << carrot_angular_distance_ << \") cannot be lower than yaw_goal_tolerance (\" << yaw_goal_tolerance_ << \") setting carrot_angular_distance = \" << yaw_goal_tolerance_);\n                carrot_angular_distance_ = yaw_goal_tolerance_;\n            }\n\n            if (carrot_distance_ < xy_goal_tolerance_)\n            {\n                ROS_WARN_STREAM(\"[BackwardLocalPlanner] carrot_linear_distance (\" << carrot_distance_ << \") cannot be lower than xy_goal_tolerance_ (\" << yaw_goal_tolerance_ << \") setting carrot_angular_distance = \" << xy_goal_tolerance_);\n                carrot_distance_ = xy_goal_tolerance_;\n            }\n\n            goalMarkerPublisher_ = nh.advertise<visualization_msgs::MarkerArray>(\"goal_marker\", 1);\n            waitingTimeout_ = ros::Duration(10);\n        }\n\n        /**\n******************************************************************************************************************\n* initialize()\n******************************************************************************************************************\n*/\n        void BackwardLocalPlanner::initialize(std::string /*name*/, tf::TransformListener */*tf*/, costmap_2d::Costmap2DROS *costmap_ros)\n        {\n            this->costmapRos_ = costmap_ros;\n            this->initialize();\n        }\n\n        void BackwardLocalPlanner::computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const tf::Stamped<tf::Pose> &tfpose, double &dist, double &angular_error)\n        {\n            double angle = tf::getYaw(tfpose.getRotation());\n            auto &carrot_pose = backwardsPlanPath_[currentCarrotPoseIndex_];\n            const geometry_msgs::Point &carrot_point = carrot_pose.pose.position;\n\n            tf::Quaternion carrot_orientation;\n            tf::quaternionMsgToTF(carrot_pose.pose.orientation, carrot_orientation);\n\n            geometry_msgs::Pose currentPoseDebugMsg;\n            tf::poseTFToMsg(tfpose, currentPoseDebugMsg);\n\n            // take error from the current position to the path point\n            double dx = carrot_point.x - tfpose.getOrigin().x();\n            double dy = carrot_point.y - tfpose.getOrigin().y();\n            dist = sqrt(dx * dx + dy * dy);\n\n            double pangle = tf::getYaw(carrot_orientation);\n            angular_error = fabs(angles::shortest_angular_distance(pangle, angle));\n\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] Compute carrot errors. (linear \" << dist << \")(angular \" << angular_error << \")\" << std::endl\n                                                                                      << \"Current carrot pose: \" << std::endl\n                                                                                      << carrot_pose << std::endl\n                                                                                      << \"Current actual pose:\" << std::endl\n                                                                                      << currentPoseDebugMsg);\n        }\n\n        /**\n******************************************************************************************************************\n* updateCarrotGoal()\n******************************************************************************************************************\n*/\n        bool BackwardLocalPlanner::updateCarrotGoal(const tf::Stamped<tf::Pose> &tfpose)\n        {\n            ROS_DEBUG(\"[BackwardsLocalPlanner] --- Computing carrot pose ---\");\n            double disterr = 0, angleerr = 0;\n            // iterate the point from the current position and backward until reaching a new goal point in the path\n            // this algorithm among other advantages has that skip the looping with an eager global planner\n            // that recalls the same plan (the already performed part of the plan in the current pose is skipped)\n            while (currentCarrotPoseIndex_ < backwardsPlanPath_.size())\n            {\n                computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, disterr, angleerr);\n\n                ROS_DEBUG_STREAM(\"[BackwardsLocalPlanner] update carrot goal: Current index: \" << currentCarrotPoseIndex_ << \"/\" << backwardsPlanPath_.size());\n                ROS_DEBUG(\"[BackwardsLocalPlanner] update carrot goal: linear error %lf, angular error: %lf\", disterr, angleerr);\n\n                // target pose found, goal carrot tries to escape!\n                if (disterr < carrot_distance_ && angleerr < carrot_angular_distance_)\n                {\n                    currentCarrotPoseIndex_++;\n                    resetDivergenceDetection();\n                    ROS_DEBUG_STREAM(\"[BackwardsLocalPlanner] fw \" << currentCarrotPoseIndex_ << \"/\" << backwardsPlanPath_.size());\n                }\n                else\n                {\n                    break;\n                }\n            }\n            //ROS_DEBUG(\"[BackwardsLocalPlanner] computing angular error\");\n            if (currentCarrotPoseIndex_ >= backwardsPlanPath_.size() && backwardsPlanPath_.size() > 0)\n            {\n                currentCarrotPoseIndex_ = backwardsPlanPath_.size() - 1;\n                computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, disterr, angleerr);\n            }\n\n            ROS_DEBUG(\"[BackwardsLocalPlanner] Current index carrot goal: %ld\", currentCarrotPoseIndex_);\n            ROS_DEBUG(\"[BackwardsLocalPlanner] Update carrot goal: linear error  %lf, angular error: %lf\", disterr, angleerr);\n            bool carrotInGoalLinear = disterr < xy_goal_tolerance_;\n            ROS_DEBUG(\"[BackwardsLocalPlanner] carrot in goal radius: %d\", carrotInGoalLinear);\n\n            ROS_DEBUG(\"[BackwardsLocalPlanner] --- Computing carrot pose ---\");\n\n            return carrotInGoalLinear;\n        }\n\n        bool BackwardLocalPlanner::resetDivergenceDetection()\n        {\n            // this function should be called always the carrot is updated\n            divergenceDetectionLastCarrotLinearDistance_ = std::numeric_limits<double>::max();\n            return true;\n        }\n\n        bool BackwardLocalPlanner::divergenceDetectionUpdate(const tf::Stamped<tf::Pose> &tfpose)\n        {\n            double disterr = 0, angleerr = 0;\n            computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, disterr, angleerr);\n\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] Divergence check. carrot goal distance. was: \" << divergenceDetectionLastCarrotLinearDistance_ << \", now it is: \" << disterr);\n            if (disterr > divergenceDetectionLastCarrotLinearDistance_)\n            {\n                // candidate of divergence, we do not throw the divergence alarm yet\n                // but we neither update the distance since it is worse than the one\n                // we had previously with the same carrot.\n                const double MARGIN_FACTOR = 1.2;\n                if (disterr > MARGIN_FACTOR * divergenceDetectionLastCarrotLinearDistance_)\n                {\n                    ROS_ERROR_STREAM(\"[BackwardLocalPlanner] Divergence detected. The same carrot goal distance was previously: \" << divergenceDetectionLastCarrotLinearDistance_ << \"but now it is: \" << disterr);\n                    return true;\n                }\n                else\n                {\n                    // divergence candidate\n                    return false;\n                }\n            }\n            else\n            {\n                //update:\n                divergenceDetectionLastCarrotLinearDistance_ = disterr;\n                return false;\n            }\n        }\n\n        bool BackwardLocalPlanner::checkCarrotHalfPlainConstraint(const tf::Stamped<tf::Pose> &tfpose)\n        {\n            // this function is specially useful when we want to reach the goal with a lot\n            // of precision. We may pass the goal and then the controller enters in some\n            // unstable state. With this, we are able to detect when stop moving.\n\n            // only apply if the carrot is in goal position and also if we are not in a pure spinning behavior v!=0\n\n            auto &carrot_pose = backwardsPlanPath_[currentCarrotPoseIndex_];\n            const geometry_msgs::Point &carrot_point = carrot_pose.pose.position;\n            double yaw = tf::getYaw(carrot_pose.pose.orientation);\n\n            // direction vector\n            double vx = cos(yaw);\n            double vy = sin(yaw);\n\n            // line implicit equation\n            // ax + by + c = 0\n            double c = -vx * carrot_point.x - vy * carrot_point.y;\n            const double C_OFFSET_METERS = 0.05; // 5 cm\n            double check = vx * tfpose.getOrigin().x() + vy * tfpose.getOrigin().y() + c + C_OFFSET_METERS;\n\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] half plane constraint:\" << vx << \"*\" << carrot_point.x << \" + \" << vy << \"*\" << carrot_point.y << \" + \" << c);\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] constraint evaluation: \" << vx << \"*\" << tfpose.getOrigin().x() << \" + \" << vy << \"*\" << tfpose.getOrigin().y() << \" + \" << c << \" = \" << check);\n\n            return check < 0;\n        }\n\n        bool BackwardLocalPlanner::checkCurrentPoseInGoalRange(const tf::Stamped<tf::Pose> &tfpose,  double angle_error, bool& linearGoalReached)\n        {\n            auto &finalgoal = backwardsPlanPath_.back();\n            double gdx = finalgoal.pose.position.x - tfpose.getOrigin().x();\n            double gdy = finalgoal.pose.position.y - tfpose.getOrigin().y();\n            double goaldist = sqrt(gdx * gdx + gdy * gdy);\n\n            auto abs_angle_error = fabs(angle_error);\n            // final_alpha_error =\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] goal check. linear dist: \" << goaldist << \"(\" << this->xy_goal_tolerance_ << \")\"\n                                                                                << \", angular dist: \" << abs_angle_error << \"(\" << this->yaw_goal_tolerance_ << \")\");\n\n            linearGoalReached = goaldist < this->xy_goal_tolerance_;\n\n            if (abs_angle_error < this->yaw_goal_tolerance_) // 5cm\n            {\n                return true;\n            }\n\n            return false;\n        }\n        /**\n******************************************************************************************************************\n* defaultBackwardCmd()\n******************************************************************************************************************\n*/\n        void BackwardLocalPlanner::defaultBackwardCmd(const tf::Stamped<tf::Pose> &/*tfpose*/, double vetta, double gamma, double /*alpha_error*/, double /*betta_error*/, geometry_msgs::Twist &cmd_vel)\n        {\n            cmd_vel.linear.x = vetta;\n            cmd_vel.angular.z = gamma;\n        }\n        /**\n******************************************************************************************************************\n* pureSpinningCmd()\n******************************************************************************************************************\n*/\n        void BackwardLocalPlanner::straightBackwardsAndPureSpinCmd(const tf::Stamped<tf::Pose> &/*tfpose*/, double vetta, double gamma, double alpha_error, double betta_error, double rho_error, geometry_msgs::Twist &cmd_vel)\n        {\n            if (rho_error > linear_mode_rho_error_threshold_) // works in straight motion mode\n            {\n                vetta = k_rho_ * rho_error;\n                gamma = k_alpha_ * alpha_error;\n            }\n            else if (fabs(betta_error) >= this->yaw_goal_tolerance_) // works in pure spinning mode\n            {\n                vetta = 0;\n                gamma = k_betta_ * betta_error;\n            }\n            /*\n            // THIS IS NOT TRUE, IF THE CARROT REACHES THE GOAL DOES NOT MEAN THE ROBOT IS\n            // IN THE CORRECT POSITION\n            else if (currentCarrotPoseIndex_ >= backwardsPlanPath_.size() - 1)\n            {\n                vetta = 0;\n                gamma = 0;\n                goalReached_ = true;\n                backwardsPlanPath_.clear();\n\n                ROS_INFO_STREAM(\"BACKWARD LOCAL PLANNER END: Goal Reached. Stop action [rhoerror: \" << rho_error<<\"]\");\n            }*/\n\n            cmd_vel.linear.x = vetta;\n            cmd_vel.angular.z = gamma;\n        }\n\n// MELODIC\n#if ROS_VERSION_MINIMUM(1, 13, 0)\n        tf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n        {\n            geometry_msgs::PoseStamped paux;\n            costmapRos->getRobotPose(paux);\n            tf::Stamped<tf::Pose> tfpose;\n            tf::poseStampedMsgToTF(paux, tfpose);\n            return tfpose;\n        }\n#else\n        // INDIGO AND PREVIOUS\n        tf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n        {\n            tf::Stamped<tf::Pose> tfpose;\n            costmapRos->getRobotPose(tfpose);\n            return tfpose;\n        }\n\n#endif\n\n        /**\n******************************************************************************************************************\n* computeVelocityCommands()\n******************************************************************************************************************\n*/\n        bool BackwardLocalPlanner::computeVelocityCommands(geometry_msgs::Twist &cmd_vel)\n        {\n            ROS_DEBUG(\"[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------\");\n            geometry_msgs::PoseStamped paux;\n            tf::Stamped<tf::Pose> tfpose = optionalRobotPose(costmapRos_);\n\n            //bool divergenceDetected = this->divergenceDetectionUpdate(tfpose);\n            // it is not working in the pure spinning reel example, maybe the hyperplane check is enough\n            bool divergenceDetected = false;\n\n            bool emergency_stop = false;\n            if (divergenceDetected)\n            {\n                ROS_ERROR(\"[BackwardLocalPlanner] Divergence detected. Sending emergency stop.\");\n                emergency_stop = true;\n            }\n\n            bool carrotInLinearGoalRange = updateCarrotGoal(tfpose);\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] carrot goal created\");\n\n            if (emergency_stop)\n            {\n                cmd_vel.linear.x = 0;\n                cmd_vel.angular.z = 0;\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] emergency stop, exit compute commands\");\n                return false;\n            }\n\n            // ------ Evaluate the current context ----\n            double rho_error, betta_error, alpha_error;\n\n\n                // getting carrot goal information\n                tf::Quaternion q = tfpose.getRotation();\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] carrot goal: \" << currentCarrotPoseIndex_ << \"/\" << backwardsPlanPath_.size());\n                const geometry_msgs::PoseStamped &carrotgoalpose = backwardsPlanPath_[currentCarrotPoseIndex_];\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] carrot goal pose current index: \" << currentCarrotPoseIndex_ << \"/\" << backwardsPlanPath_.size() << \": \" << carrotgoalpose);\n                const geometry_msgs::Point &carrotGoalPosition = carrotgoalpose.pose.position;\n\n                tf::Quaternion goalQ;\n                tf::quaternionMsgToTF(carrotgoalpose.pose.orientation, goalQ);\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] goal orientation: \" << goalQ);\n\n                //goal orientation (global frame)\n                double betta = tf::getYaw(goalQ);\n                betta = betta + betta_offset_;\n\n                double dx = carrotGoalPosition.x - tfpose.getOrigin().x();\n                double dy = carrotGoalPosition.y - tfpose.getOrigin().y();\n\n                //distance error to the targetpoint\n                rho_error = sqrt(dx * dx + dy * dy);\n\n                //heading to goal angle\n                double theta = tf::getYaw(q);\n                double alpha = atan2(dy, dx);\n                alpha = alpha + alpha_offset_;\n\n                alpha_error = angles::shortest_angular_distance(alpha, theta);\n                betta_error = angles::shortest_angular_distance(betta, theta);\n            //------------- END CONTEXT EVAL ----------\n\n            bool linearGoalReached;\n            bool currentPoseInGoal = checkCurrentPoseInGoalRange(tfpose,betta_error, linearGoalReached);\n\n            bool carrotInFinalGoal = carrotInLinearGoalRange && currentCarrotPoseIndex_ == backwardsPlanPath_.size() - 1;\n\n            if(currentPoseInGoal && carrotInFinalGoal)\n            {\n                goalReached_ = true;\n                backwardsPlanPath_.clear();\n                ROS_INFO_STREAM(\" [BackwardLocalPlanner] GOAL REACHED. Send stop command and skipping trajectory collision: \" << cmd_vel);\n                cmd_vel.linear.x =0;\n                cmd_vel.angular.z = 0;\n                return true;\n            }\n\n            if (carrotInLinearGoalRange && linearGoalReached) // we miss here and not any carrot ahead is outside goal, replacing carrotInLinearGoalRange to carrotInFinalLinearGoalRange\n            {\n                inGoalPureSpinningState_ = true;\n            }\n\n\n                double vetta = k_rho_ * rho_error;\n                double gamma = k_alpha_ * alpha_error + k_betta_ * betta_error;\n                // --------------------\n\n                if (straightBackwardsAndPureSpinningMode_)\n                {\n                    this->straightBackwardsAndPureSpinCmd(tfpose, vetta, gamma, alpha_error, betta_error, rho_error, cmd_vel);\n                }\n                else // default curved backward-free motion mode\n                {\n                    // case B: goal position reached but orientation not yet reached. deactivate linear motion.\n                    if (inGoalPureSpinningState_)\n                    {\n                        ROS_DEBUG(\"[BackwardLocalPlanner] we entered in a pure spinning state even in not pure-spining configuration, carrotDistanceGoalReached: %d\", carrotInLinearGoalRange);\n                        gamma = k_betta_ * betta_error;\n                        vetta = 0;\n                    }\n\n                    //classical control to reach a goal backwards\n                    this->defaultBackwardCmd(tfpose, vetta, gamma, alpha_error, betta_error, cmd_vel);\n                }\n\n                if (cmd_vel.linear.x > max_linear_x_speed_)\n                {\n                    cmd_vel.linear.x = max_linear_x_speed_;\n                }\n                else if (cmd_vel.linear.x < -max_linear_x_speed_)\n                {\n                    cmd_vel.linear.x = -max_linear_x_speed_;\n                }\n\n                if (cmd_vel.angular.z > max_angular_z_speed_)\n                {\n                    cmd_vel.angular.z = max_angular_z_speed_;\n                }\n                else if (cmd_vel.angular.z < -max_angular_z_speed_)\n                {\n                    cmd_vel.angular.z = -max_angular_z_speed_;\n                }\n\n                publishGoalMarker(carrotGoalPosition.x, carrotGoalPosition.y, betta);\n\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] local planner,\" << std::endl\n                                                                         << \" straightAnPureSpiningMode: \" << straightBackwardsAndPureSpinningMode_ << std::endl\n                                                                         << \" inGoalPureSpinningState: \" << inGoalPureSpinningState_ << std::endl\n                                                                         << \"carrotInLinearGoalRange: \" << carrotInLinearGoalRange << std::endl\n                                                                         << \" theta: \" << theta << std::endl\n                                                                         << \" betta: \" << theta << std::endl\n                                                                         << \" err_x: \" << dx << std::endl\n                                                                         << \" err_y:\" << dy << std::endl\n                                                                         << \" rho_error:\" << rho_error << std::endl\n                                                                         << \" alpha_error:\" << alpha_error << std::endl\n                                                                         << \" betta_error:\" << betta_error << std::endl\n                                                                         << \" vetta:\" << vetta << std::endl\n                                                                         << \" gamma:\" << gamma << std::endl\n                                                                         << \" cmd_vel.lin.x:\" << cmd_vel.linear.x << std::endl\n                                                                         << \" cmd_vel.ang.z:\" << cmd_vel.angular.z);\n\n                if (inGoalPureSpinningState_)\n                {\n                    bool carrotHalfPlaneConstraintFailure = checkCarrotHalfPlainConstraint(tfpose);\n\n                    if (carrotHalfPlaneConstraintFailure)\n                    {\n                        ROS_ERROR(\"[BackwardLocalPlanner] CarrotHalfPlaneConstraintFailure detected. Sending emergency stop and success to the planner.\");\n                        cmd_vel.linear.x = 0;\n                    }\n                }\n\n\n            // ---------------------- TRAJECTORY PREDICTION AND COLLISION AVOIDANCE ---------------------\n            //cmd_vel.linear.x=0;\n            //cmd_vel.angular.z = 0;\n            tf::Stamped<tf::Pose> global_pose = optionalRobotPose(costmapRos_);\n\n            auto *costmap2d = costmapRos_->getCostmap();\n            auto yaw = tf::getYaw(global_pose.getRotation());\n\n            auto &pos = global_pose.getOrigin();\n\n            Eigen::Vector3f currentpose(pos.x(), pos.y(), yaw);\n            Eigen::Vector3f currentvel(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);\n            std::vector<Eigen::Vector3f> trajectory;\n            this->generateTrajectory(currentpose, currentvel, 0.8 /*meters*/, M_PI / 8 /*rads*/, 3.0 /*seconds*/, 0.05 /*seconds*/, trajectory);\n\n            // check plan rejection\n            bool acceptedLocalTrajectoryFreeOfObstacles = true;\n\n            uint32_t mx, my;\n\n            if (this->enable_obstacle_checking_)\n            {\n                if (backwardsPlanPath_.size() > 0)\n                {\n                    auto &finalgoalpose = backwardsPlanPath_.back();\n\n                    int i = 0;\n                    // ROS_INFO_STREAM(\"lplanner goal: \" << finalgoalpose.pose.position);\n                    for (auto &p : trajectory)\n                    {\n                        float dx = p[0] - finalgoalpose.pose.position.x;\n                        float dy = p[1] - finalgoalpose.pose.position.y;\n\n                        float dst = sqrt(dx * dx + dy * dy);\n                        if (dst < xy_goal_tolerance_)\n                        {\n                            ROS_DEBUG(\"[BackwardLocalPlanner] trajectory simulation for collision checking: goal reached with no collision\");\n                            break;\n                        }\n\n                        costmap2d->worldToMap(p[0], p[1], mx, my);\n                        /*uint64_t cost =*/ costmap2d->getCost(mx, my);\n\n                        // ROS_DEBUG(\"[BackwardLocalPlanner] checking cost pt %d [%lf, %lf] cell[%d,%d] = %d\", i, p[0], p[1], mx, my, cost);\n                        // ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] cost: \" << cost);\n\n                        // static const unsigned char NO_INFORMATION = 255;\n                        // static const unsigned char LETHAL_OBSTACLE = 254;\n                        // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;\n                        // static const unsigned char FREE_SPACE = 0;\n\n                        if (costmap2d->getCost(mx, my) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)\n                        {\n                            acceptedLocalTrajectoryFreeOfObstacles = false;\n                            ROS_WARN_STREAM(\"[BackwardLocalPlanner] ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED at point \" << i << \"/\" << trajectory.size() << std::endl\n                                                                                                                            << p[0] << \", \" << p[1]);\n                            break;\n                        }\n                        i++;\n                    }\n                }\n                else\n                {\n                    ROS_WARN(\"[BackwardLocalPlanner] Abort local - Backwards global plan size: %ld\", backwardsPlanPath_.size());\n                    return false;\n                }\n            }\n\n            if (acceptedLocalTrajectoryFreeOfObstacles)\n            {\n                waiting_ = false;\n                ROS_DEBUG(\"[BackwardLocalPlanner] accepted local trajectory free of obstacle. Local planner continues.\");\n                return true;\n            }\n            else // that is not appceted because existence of obstacles\n            {\n                // emergency stop for collision: waiting a while before sending error\n                cmd_vel.linear.x = 0;\n                cmd_vel.angular.z = 0;\n\n                if (waiting_ == false)\n                {\n                    waiting_ = true;\n                    waitingStamp_ = ros::Time::now();\n                    ROS_WARN(\"[BackwardLocalPlanner][Not accepted local plan] starting countdown\");\n                }\n                else\n                {\n                    auto waitingduration = ros::Time::now() - waitingStamp_;\n\n                    if (waitingduration > this->waitingTimeout_)\n                    {\n                        ROS_WARN(\"[BackwardLocalPlanner][Abort local] timeout! duration %lf/%f\", waitingduration.toSec(), waitingTimeout_.toSec());\n                        return false;\n                    }\n                }\n\n                return true;\n            }\n        }\n\n        /**\n******************************************************************************************************************\n* reconfigCB()\n******************************************************************************************************************\n*/\n        void BackwardLocalPlanner::reconfigCB(::backward_local_planner::BackwardLocalPlannerConfig &config, uint32_t /*level*/)\n        {\n            ROS_INFO(\"[BackwardLocalPlanner] reconfigure Request\");\n            k_alpha_ = config.k_alpha;\n            k_betta_ = config.k_betta;\n            k_rho_ = config.k_rho;\n            enable_obstacle_checking_ = config.enable_obstacle_checking;\n\n            //alpha_offset_ = config.alpha_offset;\n            //betta_offset_ = config.betta_offset;\n\n            carrot_distance_ = config.carrot_distance;\n            carrot_angular_distance_ = config.carrot_angular_distance;\n            xy_goal_tolerance_ = config.xy_goal_tolerance;\n            yaw_goal_tolerance_ = config.yaw_goal_tolerance;\n            straightBackwardsAndPureSpinningMode_ = config.pure_spinning_straight_line_mode;\n\n            if (carrot_angular_distance_ < yaw_goal_tolerance_)\n            {\n                ROS_WARN_STREAM(\"[BackwardLocalPlanner] carrot_angular_distance (\" << carrot_angular_distance_ << \") cannot be lower than yaw_goal_tolerance (\" << yaw_goal_tolerance_ << \") setting carrot_angular_distance = \" << yaw_goal_tolerance_);\n                carrot_angular_distance_ = yaw_goal_tolerance_;\n                config.carrot_angular_distance = yaw_goal_tolerance_;\n            }\n\n            if (carrot_distance_ < xy_goal_tolerance_)\n            {\n                ROS_WARN_STREAM(\"[BackwardLocalPlanner] carrot_linear_distance (\" << carrot_distance_ << \") cannot be lower than xy_goal_tolerance_ (\" << yaw_goal_tolerance_ << \") setting carrot_angular_distance = \" << xy_goal_tolerance_);\n                carrot_distance_ = xy_goal_tolerance_;\n                config.carrot_distance = xy_goal_tolerance_;\n            }\n        }\n\n        /**\n******************************************************************************************************************\n* isGoalReached()\n******************************************************************************************************************\n*/\n        bool BackwardLocalPlanner::isGoalReached()\n        {\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] isGoalReached call: \" << goalReached_);\n            return goalReached_;\n        }\n\n        bool BackwardLocalPlanner::findInitialCarrotGoal(tf::Stamped<tf::Pose> &tfpose)\n        {\n            double lineardisterr, angleerr;\n            bool inCarrotRange = false;\n\n            // initial state check\n            computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, lineardisterr, angleerr);\n\n            // int closestIndex = -1;\n            // double minpointdist = std::numeric_limits<double>::max();\n\n            // lets set the carrot-goal in the correct place with this loop\n            while (currentCarrotPoseIndex_ < backwardsPlanPath_.size() && !inCarrotRange)\n            {\n                computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, lineardisterr, angleerr);\n\n                ROS_DEBUG(\"[BackwardLocalPlanner] Finding initial carrot goal i=%ld - error to carrot, linear = %lf (%lf), angular : %lf (%lf)\", currentCarrotPoseIndex_, lineardisterr, carrot_distance_, angleerr, carrot_angular_distance_);\n\n                // current path point is inside the carrot distance range, goal carrot tries to escape!\n                if (lineardisterr < carrot_distance_ && angleerr < carrot_angular_distance_)\n                {\n                    ROS_DEBUG(\"[BackwardLocalPlanner] Finding initial carrot goal i=%ld - in carrot Range\", currentCarrotPoseIndex_);\n                    inCarrotRange = true;\n                    // we are inside the goal range\n                }\n                else if (inCarrotRange && (lineardisterr > carrot_distance_ || angleerr > carrot_angular_distance_))\n                {\n                    // we were inside the carrot range but not anymore, now we are just leaving. we want to continue forward (currentCarrotPoseIndex_++)\n                    // unless we go out of the carrot range\n\n                    // but we rollback last index increment (to go back inside the carrot goal scope) and start motion with that carrot goal we found\n                    currentCarrotPoseIndex_--;\n                    break;\n                }\n                else\n                {\n                    ROS_DEBUG(\"[BackwardLocalPlanner] Finding initial carrot goal i=%ld - carrot out of range, searching coincidence...\", currentCarrotPoseIndex_);\n                }\n\n                currentCarrotPoseIndex_++;\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] setPlan: fw\" << currentCarrotPoseIndex_);\n            }\n\n            ROS_INFO_STREAM(\"[BackwardLocalPlanner] setPlan: (found first carrot:\" << inCarrotRange << \") initial carrot point index: \" << currentCarrotPoseIndex_ << \"/\" << backwardsPlanPath_.size());\n\n            return inCarrotRange;\n        }\n\n        bool BackwardLocalPlanner::resamplePrecisePlan()\n        {\n            // this algorithm is really important to have a precise carrot (linear or angular)\n            // and not being considered as a divergence from the path\n\n            ROS_DEBUG(\"[BackwardLocalPlanner] resample precise\");\n            if(backwardsPlanPath_.size() <=1)\n            {\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] resample precise skipping, size: \" << backwardsPlanPath_.size());\n                return false;\n            }\n\n            int counter = 0;\n            double maxallowedAngularError = 0.45 * this->carrot_angular_distance_; // nyquist\n            double maxallowedLinearError = 0.45 * this->carrot_distance_;          // nyquist\n\n            for (uint64_t i = 0; i < backwardsPlanPath_.size() - 1; i++)\n            {\n                ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] resample precise, check: \" << i);\n                auto &currpose = backwardsPlanPath_[i];\n                auto &nextpose = backwardsPlanPath_[i + 1];\n\n                tf::Quaternion qCurrent, qNext;\n                tf::quaternionMsgToTF(currpose.pose.orientation, qCurrent);\n                tf::quaternionMsgToTF(nextpose.pose.orientation, qNext);\n\n                double dx = nextpose.pose.position.x - currpose.pose.position.x;\n                double dy = nextpose.pose.position.y - currpose.pose.position.y;\n                double dist = sqrt(dx * dx + dy * dy);\n\n                bool resample = false;\n                if (dist > maxallowedLinearError)\n                {\n                    ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] resampling point, linear distance:\" << dist << \"(\" << maxallowedLinearError << \")\" << i);\n                    resample = true;\n                }\n                else\n                {\n                    double currentAngle = tf::getYaw(qCurrent);\n                    double nextAngle = tf::getYaw(qNext);\n\n                    double angularError = fabs(angles::shortest_angular_distance(currentAngle, nextAngle));\n                    if (angularError > maxallowedAngularError)\n                    {\n                        resample = true;\n                        ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] resampling point, angular distance:\" << angularError << \"(\" << maxallowedAngularError << \")\" << i);\n                    }\n                }\n\n                if (resample)\n                {\n                    geometry_msgs::PoseStamped pintermediate;\n                    auto duration = nextpose.header.stamp - currpose.header.stamp;\n                    pintermediate.header.frame_id = currpose.header.frame_id;\n                    pintermediate.header.stamp = currpose.header.stamp + duration *0.5;\n\n                    pintermediate.pose.position.x = 0.5 * (currpose.pose.position.x + nextpose.pose.position.x);\n                    pintermediate.pose.position.y = 0.5 * (currpose.pose.position.y + nextpose.pose.position.y);\n                    pintermediate.pose.position.z = 0.5 * (currpose.pose.position.z + nextpose.pose.position.z);\n                    tf::Quaternion intermediateQuat = tf::slerp(qCurrent, qNext, 0.5);\n                    tf::quaternionTFToMsg(intermediateQuat, pintermediate.pose.orientation);\n\n                    this->backwardsPlanPath_.insert(this->backwardsPlanPath_.begin() + i + 1, pintermediate);\n\n                    // retry this point\n                    i--;\n                    counter++;\n                }\n            }\n\n            ROS_DEBUG_STREAM(\"[BackwardLocalPlanner] End resampling. resampled:\" << counter << \" new inserted poses during precise resmapling.\");\n            return true;\n        }\n\n        /**\n******************************************************************************************************************\n* setPlan()\n******************************************************************************************************************\n*/\n        bool BackwardLocalPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped> &plan)\n        {\n            ROS_INFO_STREAM(\"[BackwardLocalPlanner] setPlan: new global plan received (\" << plan.size() << \")\");\n            initialPureSpinningStage_ = true;\n            goalReached_ = false;\n            backwardsPlanPath_ = plan;\n            inGoalPureSpinningState_ =false;\n\n            // find again the new carrot goal, from the destiny direction\n            tf::Stamped<tf::Pose> tfpose = optionalRobotPose(costmapRos_);\n\n            geometry_msgs::PoseStamped posestamped;\n            tf::poseStampedTFToMsg(tfpose,posestamped);\n            backwardsPlanPath_.insert(backwardsPlanPath_.begin(), posestamped);\n\n            this->resamplePrecisePlan();\n\n            currentCarrotPoseIndex_ = 0;\n            this->resetDivergenceDetection();\n\n            if (plan.size() == 0)\n            {\n                ROS_WARN(\"[BackwardLocalPlanner] received plan without any pose\");\n                return true;\n            }\n\n            bool foundInitialCarrotGoal = this->findInitialCarrotGoal(tfpose);\n            if (!foundInitialCarrotGoal)\n            {\n                ROS_ERROR(\"[BackwardLocalPlanner] new plan rejected. The initial point in the global path is too much far away from the current state (according to carrot_distance parameter)\");\n                return false; // in this case, the new plan broke the current execution\n            }\n            else\n            {\n                this->divergenceDetectionUpdate(tfpose);\n                // SANDARD AND PREFERRED CASE ON NEW PLAN\n                return true;\n            }\n        }\n\n        void BackwardLocalPlanner::generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxanglediff, float maxtime, float dt, std::vector<Eigen::Vector3f> &outtraj)\n        {\n            //simulate the trajectory and check for collisions, updating costs along the way\n            bool end = false;\n            float time = 0;\n            Eigen::Vector3f currentpos = pos;\n            int i = 0;\n            while (!end)\n            {\n                //add the point to the trajectory so we can draw it later if we want\n                //traj.addPoint(pos[0], pos[1], pos[2]);\n\n                // if (continued_acceleration_) {\n                //   //calculate velocities\n                //   loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt);\n                //   //ROS_WARN_NAMED(\"Generator\", \"Flag: %d, Loop_Vel %f, %f, %f\", continued_acceleration_, loop_vel[0], loop_vel[1], loop_vel[2]);\n                // }\n\n                auto loop_vel = vel;\n                //update the position of the robot using the velocities passed in\n                auto newpos = computeNewPositions(currentpos, loop_vel, dt);\n\n                auto dx = newpos[0] - currentpos[0];\n                auto dy = newpos[1] - currentpos[1];\n                float dist, angledist;\n\n                //ROS_INFO(\"traj point %d\", i);\n                dist = sqrt(dx * dx + dy * dy);\n                if (dist > maxdist)\n                {\n                    end = true;\n                    //ROS_INFO(\"dist break: %f\", dist);\n                }\n                else\n                {\n                    // ouble from, double to\n                    angledist = angles::shortest_angular_distance(currentpos[2], newpos[2]);\n                    if (angledist > maxanglediff)\n                    {\n                        end = true;\n                        //ROS_INFO(\"angle dist break: %f\", angledist);\n                    }\n                    else\n                    {\n                        outtraj.push_back(newpos);\n\n                        time += dt;\n                        if (time > maxtime)\n                        {\n                            end = true;\n                            //ROS_INFO(\"time break: %f\", time);\n                        }\n\n                        //ROS_INFO(\"dist: %f, angledist: %f, time: %f\", dist, angledist, time);\n                    }\n                }\n\n                currentpos = newpos;\n                i++;\n            } // end for simulation steps\n        }\n\n        Eigen::Vector3f BackwardLocalPlanner::computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)\n        {\n            Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();\n            new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;\n            new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;\n            new_pos[2] = pos[2] + vel[2] * dt;\n            return new_pos;\n        }\n\n        /**\n******************************************************************************************************************\n* publishGoalMarker()\n******************************************************************************************************************\n*/\n        void BackwardLocalPlanner::publishGoalMarker(double x, double y, double phi)\n        {\n            visualization_msgs::Marker marker;\n            marker.header.frame_id = this->costmapRos_->getGlobalFrameID();\n            marker.header.stamp = ros::Time::now();\n\n            marker.ns = \"my_namespace2\";\n            marker.id = 0;\n            marker.type = visualization_msgs::Marker::ARROW;\n            marker.action = visualization_msgs::Marker::ADD;\n            marker.pose.orientation.w = 1;\n\n            marker.scale.x = 0.05;\n            marker.scale.y = 0.15;\n            marker.scale.z = 0.05;\n            marker.color.a = 1.0;\n\n            marker.color.r = 1;\n            marker.color.g = 0;\n            marker.color.b = 0;\n\n            geometry_msgs::Point start, end;\n            start.x = x;\n            start.y = y;\n\n            end.x = x + 0.5 * cos(phi);\n            end.y = y + 0.5 * sin(phi);\n\n            marker.points.push_back(start);\n            marker.points.push_back(end);\n\n            visualization_msgs::MarkerArray ma;\n            ma.markers.push_back(marker);\n\n            goalMarkerPublisher_.publish(ma);\n        }\n    } // namespace backward_local_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package forward_global_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(forward_global_planner)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED\n  costmap_2d\n  geometry_msgs\n  nav_core\n  nav_msgs\n  roscpp\n  std_msgs\n  tf\n  dynamic_reconfigure\n)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS Eigen3)\nfind_package(Eigen3)\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\nset_source_files_properties(\n  src/forward_global_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter\"\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS}\n  LIBRARIES forward_global_planner\n  CATKIN_DEPENDS costmap_2d dynamic_reconfigure geometry_msgs nav_msgs roscpp tf\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n  include\n  ${EIGEN3_INCLUDE_DIRS}\n  ${catkin_INCLUDE_DIRS}\n)\n\nadd_library(${PROJECT_NAME}\n  src/forward_global_planner.cpp\n  src/path_tools.cpp\n)\n\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/forward_global_planner_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\n install(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(FILES\n   fgp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_forward_global_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/fgp_plugin.xml",
    "content": "<library path=\"libforward_global_planner\">\n  <class name=\"forward_global_planner/ForwardGlobalPlanner\" type=\"cl_move_base_z::forward_global_planner::ForwardGlobalPlanner\" base_class_type=\"nav_core::BaseGlobalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/include/forward_global_planner/forward_global_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <nav_core/base_global_planner.h>\n#include <nav_msgs/GetPlan.h>\n#include <nav_msgs/Path.h>\n#include <ros/ros.h>\n\nnamespace cl_move_base_z\n{\nnamespace forward_global_planner\n{\nclass ForwardGlobalPlanner : public nav_core::BaseGlobalPlanner\n{\npublic:\n    ForwardGlobalPlanner();\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                  double &cost);\n\n    void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_);\n\nprivate:\n    ros::NodeHandle nh_;\n\n    ros::Publisher planPub_;\n\n    /// stored but almost not used\n    costmap_2d::Costmap2DROS *costmap_ros_;\n\n    double skip_straight_motion_distance_; //meters\n\n    double puresSpinningRadStep_; // rads\n};\n} // namespace forward_global_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/include/forward_global_planner/move_base_z_client_tools.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <ros/ros.h>\n#include <geometry_msgs/PoseStamped.h>\n\nnamespace cl_move_base_z\n{\n\ngeometry_msgs::PoseStamped makePureSpinningSubPlan(const geometry_msgs::PoseStamped &start, double dstRads, std::vector<geometry_msgs::PoseStamped> &plan, double puresSpinningRadStep = 1000);\n\ngeometry_msgs::PoseStamped makePureStraightSubPlan(const geometry_msgs::PoseStamped &startOrientedPose,\n                                                   const geometry_msgs::Point &goal,\n                                                   double length,\n                                                   std::vector<geometry_msgs::PoseStamped> &plan);\n\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>forward_global_planner</name>\n    <version>1.4.16</version>\n  <description>The forward_global_planner package.</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n\n  <license>BSDv3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>nav_core</depend>\n  <depend>costmap_2d</depend>\n  <depend>tf</depend>\n  <depend>nav_msgs</depend>\n  <depend>dynamic_reconfigure</depend>\n  <depend>geometry_msgs</depend>\n\n\n  <export>\n    <nav_core plugin=\"${prefix}/fgp_plugin.xml\" />\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/src/forward_global_planner.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <boost/assign.hpp>\n#include <boost/range/adaptor/reversed.hpp>\n#include <boost/range/algorithm/copy.hpp>\n#include <pluginlib/class_list_macros.h>\n#include <forward_global_planner/forward_global_planner.h>\n#include <forward_global_planner/move_base_z_client_tools.h>\n#include <fstream>\n#include <streambuf>\n#include <nav_msgs/Path.h>\n#include <angles/angles.h>\n#include <tf/tf.h>\n#include <tf/transform_datatypes.h>\n\nnamespace cl_move_base_z\n{\nnamespace forward_global_planner\n{\nForwardGlobalPlanner::ForwardGlobalPlanner()\n    : nh_(\"~/ForwardGlobalPlanner\")\n{\n    skip_straight_motion_distance_ = 0.2; //meters\n    puresSpinningRadStep_ = 1000;         // rads\n}\n\nvoid ForwardGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)\n{\n    ROS_INFO(\"[Forward Global Planner] initializing\");\n    planPub_ = nh_.advertise<nav_msgs::Path>(\"global_plan\", 1);\n    skip_straight_motion_distance_ = 0.2; //meters\n    puresSpinningRadStep_ = 1000;         // rads\n    this->costmap_ros_ = costmap_ros;\n}\n\nbool ForwardGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                    const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                                    double &cost)\n{\n    ROS_INFO(\"[Forward Global Planner] planning\");\n    cost = 0;\n    return makePlan(start, goal, plan);\n}\n\nbool ForwardGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                    const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan)\n{\n    //ROS_WARN_STREAM(\"Forward global plan goal: \" << goal);\n\n    //three stages: 1 - heading to goal position, 2 - going forward keep orientation, 3 - heading to goal orientation\n\n    // 1 - heading to goal position\n    // orientation direction\n\n    double dx = goal.pose.position.x - start.pose.position.x;\n    double dy = goal.pose.position.y - start.pose.position.y;\n\n    double length = sqrt(dx * dx + dy * dy);\n\n    geometry_msgs::PoseStamped prevState;\n    if (length > skip_straight_motion_distance_)\n    {\n        // skip initial pure spinning and initial straight motion\n        //ROS_INFO(\"1 - heading to goal position pure spinning\");\n        double heading_direction = atan2(dy, dx);\n        prevState = cl_move_base_z::makePureSpinningSubPlan(start, heading_direction, plan, puresSpinningRadStep_);\n        //ROS_INFO(\"2 - going forward keep orientation pure straight\");\n        prevState = cl_move_base_z::makePureStraightSubPlan(prevState, goal.pose.position, length, plan);\n    }\n    else\n    {\n        prevState = start;\n    }\n\n    //ROS_INFO(\"3 - heading to goal orientation\");\n    double goalOrientation = angles::normalize_angle(tf::getYaw(goal.pose.orientation));\n    cl_move_base_z::makePureSpinningSubPlan(prevState, goalOrientation, plan, puresSpinningRadStep_);\n\n    nav_msgs::Path planMsg;\n    planMsg.poses = plan;\n    planMsg.header.stamp = ros::Time::now();\n\n    planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();\n\n    // check plan rejection\n    bool acceptedGlobalPlan = true;\n\n    // static const unsigned char NO_INFORMATION = 255;\n    // static const unsigned char LETHAL_OBSTACLE = 254;\n    // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;\n    // static const unsigned char FREE_SPACE = 0;\n\n    costmap_2d::Costmap2D *costmap2d = this->costmap_ros_->getCostmap();\n    for (auto &p : plan)\n    {\n        uint32_t mx, my;\n        costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);\n        auto cost = costmap2d->getCost(mx, my);\n\n        if (cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)\n        {\n            acceptedGlobalPlan = false;\n            break;\n        }\n    }\n\n    if (acceptedGlobalPlan)\n    {\n        planPub_.publish(planMsg);\n        //ROS_INFO_STREAM(\"global forward plan: \" << planMsg);\n        return true;\n    }\n    else\n    {\n        return false;\n    }\n}\n\n}; // namespace forward_global_planner\n} // namespace cl_move_base_z\n\n//register this planner as a BaseGlobalPlanner plugin\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::forward_global_planner::ForwardGlobalPlanner, nav_core::BaseGlobalPlanner);\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_global_planner/src/path_tools.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <ros/ros.h>\n#include <geometry_msgs/PoseStamped.h>\n#include <tf/transform_datatypes.h>\n#include <angles/angles.h>\n\nnamespace cl_move_base_z\n{\n    geometry_msgs::PoseStamped makePureSpinningSubPlan(const geometry_msgs::PoseStamped& start, double dstRads, std::vector<geometry_msgs::PoseStamped>& plan, double puresSpinningRadStep=1000)\n    {\n        double startYaw = tf::getYaw(start.pose.orientation);\n        //ROS_INFO(\"pure spining start yaw: %lf\", startYaw);\n        //ROS_INFO(\"pure spining goal yaw: %lf\", dstRads);\n        //ROS_WARN_STREAM(\"pure spinning start pose: \" << start);\n\n        double goalAngleOffset = angles::shortest_angular_distance(startYaw, dstRads);\n        //ROS_INFO(\"shortest angle: %lf\", goalAngleOffset);\n\n        double radstep = 0.005;\n\n        if( goalAngleOffset>=0)\n        {\n            // angle positive turn counterclockwise\n            //ROS_INFO(\"pure spining counterclockwise\");\n            for(double dangle = 0; dangle <= goalAngleOffset;dangle+=radstep )\n            {\n                geometry_msgs::PoseStamped p= start;\n                double yaw = startYaw+ dangle;\n                //ROS_INFO(\"pure spining counterclockwise, current path yaw: %lf, dangle: %lf, angleoffset %lf, radstep %lf pathsize(%ld)\", yaw, dangle, goalAngleOffset, radstep, plan.size());\n                p.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);\n                plan.push_back(p);\n            }\n        }\n        else\n        {\n            // angle positive turn clockwise\n            //ROS_INFO(\"pure spining clockwise\");\n            for(double dangle = 0; dangle >= goalAngleOffset;dangle-=radstep )\n            {\n                //ROS_INFO(\"dangle: %lf\", dangle);\n                geometry_msgs::PoseStamped p= start;\n                double yaw = startYaw+ dangle;\n                //ROS_INFO(\"pure spining clockwise, yaw: %lf, dangle: %lf, angleoffset %lf radstep %lf\", yaw, dangle, goalAngleOffset,radstep);\n                p.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);\n                plan.push_back(p);\n            }\n        }\n\n        //ROS_INFO(\"pure spining end yaw: %lf\", dstRads);\n        geometry_msgs::PoseStamped end= start;\n        end.pose.orientation = tf::createQuaternionMsgFromYaw(dstRads);\n        plan.push_back(end);\n\n        return end;\n    }\n\n    geometry_msgs::PoseStamped makePureStraightSubPlan(const geometry_msgs::PoseStamped& startOrientedPose,\n                                                        const geometry_msgs::Point& goal,\n                                                        double length,\n                                                        std::vector<geometry_msgs::PoseStamped>& plan)\n    {\n        double dx = 0.01; // 1 cm\n        double steps = length /dx;\n        double dt = 1.0/steps;\n\n        // geometry_msgs::PoseStamped end;\n        // end.pose.orientation = startOrientedPose.pose.orientation;\n        //end.pose.position = goal;\n        plan.push_back(startOrientedPose);\n\n        //ROS_INFO_STREAM(\"Pure straight, start: \" << startOrientedPose << std::endl << \"end: \" << goal);\n        for(double t=0; t <=1.0; t+=dt)\n        {\n            geometry_msgs::PoseStamped p = startOrientedPose;\n\n            p.pose.position.x =  startOrientedPose.pose.position.x *(1 - t) + goal.x * t;\n            p.pose.position.y =  startOrientedPose.pose.position.y *(1 - t) + goal.y * t;\n            p.pose.orientation = startOrientedPose.pose.orientation;\n\n            plan.push_back(p);\n        }\n\n        return plan.back();\n    }\n}\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package forward_local_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(forward_local_planner)\n\nfind_package(catkin REQUIRED\n  roscpp\n  costmap_2d\n  tf\n  nav_core\n  base_local_planner\n  nav_msgs\n  move_base_msgs\n  geometry_msgs\n  std_msgs\n)\n\n\nset_source_files_properties(\n  src/forward_local_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter\"\n)\n\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES forward_local_planner\n  CATKIN_DEPENDS costmap_2d geometry_msgs nav_core nav_msgs roscpp std_msgs tf\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n  ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   src/forward_local_planner.cpp\n)\n\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(FILES\n   flp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_forward_local_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/cfg/ForwardLocalPlanner.cfg",
    "content": "#!/usr/bin/env python\nPACKAGE = \"forward_local_planner\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\n\ngen.add(\"k_rho\",   double_t,   1, \"point distance error gain\", 0.1 )\ngen.add(\"k_alpha\",   double_t,   1, \"angle to goal position error gain\", 0.05 )\ngen.add(\"k_betta\",   double_t,   1, \"goal angle error gain\", 0.1 )\n#gen.add(\"alpha_offset\",   double_t,   1, \"offset for alpha, used to reach the objetive backwards\", 0.0 )\n#gen.add(\"betta_offset\",   double_t,   1, \"offset for betta, used to reach the objetive backwards\", 0.0 )\ngen.add(\"carrot_distance\",   double_t,   1, \"meters. minimum distance to the next goal in the retraction path\", 0.2 )\ngen.add(\"carrot_angular_distance\",   double_t,   1, \"rads. minimum angular distance to the next goal in the retraction path\", 0.1 )\n\nexit(gen.generate(PACKAGE, \"forward_local_planner\", \"ForwardLocalPlanner\"))\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/flp_plugin.xml",
    "content": "<library path=\"libforward_local_planner\">\n  <class name=\"forward_local_planner/ForwardLocalPlanner\" type=\"cl_move_base_z::forward_local_planner::ForwardLocalPlanner\" base_class_type=\"nav_core::BaseLocalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/include/forward_local_planner/forward_local_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <dynamic_reconfigure/server.h>\n#include <geometry_msgs/PoseStamped.h>\n#include <nav_core/base_local_planner.h>\n#include <tf/tf.h>\n#include <tf/transform_listener.h>\n#include <tf2_ros/buffer.h>\n#include <Eigen/Eigen>\n\ntypedef double meter;\ntypedef double rad;\n\nnamespace cl_move_base_z\n{\nnamespace forward_local_planner\n{\nclass ForwardLocalPlanner : public nav_core::BaseLocalPlanner\n{\n\npublic:\n    ForwardLocalPlanner();\n\n    virtual ~ForwardLocalPlanner();\n\n    /**\n   * @brief  Given the current position, orientation, and velocity of the robot: compute velocity commands to send to the robot mobile base\n   * @param cmd_vel Will be filled with the velocity command to be passed to the robot base\n   * @return True if a valid velocity command was found, false otherwise\n   */\n    virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override;\n\n    /**\n   * @brief  Check if the goal pose has been achieved by the local planner\n   * @return True if achieved, false otherwise\n   */\n    virtual bool isGoalReached() override;\n\n    /**\n   * @brief  Set the plan that the local planner is following\n   * @param plan The plan to pass to the local planner\n   * @return True if the plan was updated successfully, false otherwise\n   */\n    virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped> &plan) override;\n\n    /**\n   * @brief  Constructs the local planner\n   * @param name The name to give this instance of the local planner\n   * @param tf A pointer to a transform listener\n   * @param costmap_ros The cost map to use for assigning costs to local plans\n   */\n    void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos_);\n\n    void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos);\n\n    void initialize();\n\nprivate:\n    void publishGoalMarker(double x, double y, double phi);\n\n    costmap_2d::Costmap2DROS *costmapRos_;\n\n    ros::Publisher goalMarkerPublisher_;\n\n    double k_rho_;\n    double k_alpha_;\n    double k_betta_;\n    bool goalReached_;\n\n    const double alpha_offset_ = 0;\n    const double betta_offset_ = 0;\n\n    meter carrot_distance_;\n    rad carrot_angular_distance_;\n\n    double yaw_goal_tolerance_; // radians\n    double xy_goal_tolerance_;  // meters\n\n    double max_angular_z_speed_;\n    double max_linear_x_speed_;\n\n    void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector<Eigen::Vector3f> &outtraj);\n    Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt);\n\n    // references the current point inside the backwardsPlanPath were the robot is located\n    int currentPoseIndex_;\n\n    std::vector<geometry_msgs::PoseStamped> plan_;\n\n    bool waiting_;\n    ros::Duration waitingTimeout_;\n    ros::Time waitingStamp_;\n};\n} // namespace forward_local_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>forward_local_planner</name>\n    <version>1.4.16</version>\n  <description>forward_local_planner package.</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n\n  <license>BSDv3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <build_depend>message_generation</build_depend>\n\n  <depend>costmap_2d</depend>\n  <depend>geometry_msgs</depend>\n  <depend>nav_core</depend>\n  <depend>base_local_planner</depend>\n  <depend>move_base_msgs</depend>\n  <depend>nav_msgs</depend>\n  <depend>std_msgs</depend>\n  <depend>roscpp</depend>\n  <depend>tf</depend>\n\n  <export>\n    <nav_core plugin=\"${prefix}/flp_plugin.xml\" />\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/forward_local_planner/src/forward_local_planner.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <angles/angles.h>\n#include <pluginlib/class_list_macros.h>\n#include <forward_local_planner/forward_local_planner.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <boost/intrusive_ptr.hpp>\n#include <angles/angles.h>\n\n#include <base_local_planner/simple_trajectory_generator.h>\n\n//register this planner as a BaseLocalPlanner plugin\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::forward_local_planner::ForwardLocalPlanner, nav_core::BaseLocalPlanner)\n\nnamespace cl_move_base_z\n{\nnamespace forward_local_planner\n{\n/**\n******************************************************************************************************************\n* ForwardLocalPlanner()\n******************************************************************************************************************\n*/\nForwardLocalPlanner::ForwardLocalPlanner()\n{\n}\n\n/**\n******************************************************************************************************************\n* ForwardLocalPlanner()\n******************************************************************************************************************\n*/\nForwardLocalPlanner::~ForwardLocalPlanner()\n{\n}\n\nvoid ForwardLocalPlanner::initialize()\n{\n    k_rho_ = 1.0;\n    k_alpha_ = -0.4;\n    k_betta_ = -1.0; // set to zero means that orientation is not important\n    //k_betta_ = 1.0;\n    //betta_offset_=0;\n\n    goalReached_ = false;\n    carrot_distance_ = 0.4;\n\n    ros::NodeHandle private_nh(\"~\");\n\n    currentPoseIndex_ = 0;\n\n    ros::NodeHandle nh(\"~/ForwardLocalPlanner\");\n\n    nh.param(\"k_rho\", k_rho_, k_rho_);\n    nh.param(\"k_alpha\", k_alpha_, k_alpha_);\n    nh.param(\"k_betta\", k_betta_, k_betta_);\n    nh.param(\"carrot_distance\", carrot_distance_, carrot_distance_);\n\n    nh.param(\"yaw_goal_tolerance\", yaw_goal_tolerance_, 0.05);\n    nh.param(\"xy_goal_tolerance\", xy_goal_tolerance_, 0.10);\n    nh.param(\"max_linear_x_speed\", max_linear_x_speed_, 1.0);\n    nh.param(\"max_angular_z_speed\", max_angular_z_speed_, 2.0);\n\n    ROS_INFO(\"[ForwardLocalPlanner] max linear speed: %lf, max angular speed: %lf, k_rho: %lf, carrot_distance: %lf, \", max_linear_x_speed_, max_angular_z_speed_, k_rho_, carrot_distance_);\n    goalMarkerPublisher_ = nh.advertise<visualization_msgs::MarkerArray>(\"goal_marker\", 1);\n\n    waiting_ = false;\n    waitingTimeout_ = ros::Duration(10);\n    ROS_INFO(\"[ForwardLocalPlanner] initialized\");\n}\n\nvoid ForwardLocalPlanner::initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)\n{\n    costmapRos_ = costmap_ros;\n    this->initialize();\n}\n\nvoid ForwardLocalPlanner::generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxanglediff, float maxtime, float dt, std::vector<Eigen::Vector3f> &outtraj)\n{\n    //simulate the trajectory and check for collisions, updating costs along the way\n    bool end = false;\n    float time = 0;\n    Eigen::Vector3f currentpos = pos;\n    int i = 0;\n    while (!end)\n    {\n        //add the point to the trajectory so we can draw it later if we want\n        //traj.addPoint(pos[0], pos[1], pos[2]);\n\n        // if (continued_acceleration_) {\n        //   //calculate velocities\n        //   loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt);\n        //   //ROS_WARN_NAMED(\"Generator\", \"Flag: %d, Loop_Vel %f, %f, %f\", continued_acceleration_, loop_vel[0], loop_vel[1], loop_vel[2]);\n        // }\n\n        auto loop_vel = vel;\n        //update the position of the robot using the velocities passed in\n        auto newpos = computeNewPositions(currentpos, loop_vel, dt);\n\n        auto dx = newpos[0] - currentpos[0];\n        auto dy = newpos[1] - currentpos[1];\n        float dist, angledist;\n\n        //ROS_INFO(\"traj point %d\", i);\n        dist = sqrt(dx * dx + dy * dy);\n        if (dist > maxdist)\n        {\n            end = true;\n            //ROS_INFO(\"dist break: %f\", dist);\n        }\n        else\n        {\n            // ouble from, double to\n            angledist = fabs(angles::shortest_angular_distance(currentpos[2], newpos[2]));\n            if (angledist > maxanglediff)\n            {\n                end = true;\n                //ROS_INFO(\"angle dist break: %f\", angledist);\n            }\n            else\n            {\n                outtraj.push_back(newpos);\n\n                time += dt;\n                if (time > maxtime)\n                {\n                    end = true;\n                    //ROS_INFO(\"time break: %f\", time);\n                }\n\n                //ROS_INFO(\"dist: %f, angledist: %f, time: %f\", dist, angledist, time);\n            }\n        }\n\n        currentpos = newpos;\n        i++;\n    } // end for simulation steps\n}\n\nEigen::Vector3f ForwardLocalPlanner::computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)\n{\n    Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();\n    new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;\n    new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;\n    new_pos[2] = pos[2] + vel[2] * dt;\n    return new_pos;\n}\n\n/**\n******************************************************************************************************************\n* initialize()\n******************************************************************************************************************\n*/\nvoid ForwardLocalPlanner::initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)\n{\n    costmapRos_ = costmap_ros;\n    this->initialize();\n}\n\n/**\n******************************************************************************************************************\n* publishGoalMarker()\n******************************************************************************************************************\n*/\nvoid ForwardLocalPlanner::publishGoalMarker(double x, double y, double phi)\n{\n    visualization_msgs::Marker marker;\n\n    marker.header.frame_id = this->costmapRos_->getGlobalFrameID();\n    marker.header.stamp = ros::Time::now();\n    marker.ns = \"my_namespace2\";\n    marker.id = 0;\n    marker.type = visualization_msgs::Marker::ARROW;\n    marker.action = visualization_msgs::Marker::ADD;\n    marker.pose.orientation.w = 1;\n\n    marker.scale.x = 0.1;\n    marker.scale.y = 0.3;\n    marker.scale.z = 0.1;\n    marker.color.a = 1.0;\n    marker.color.r = 0;\n    marker.color.g = 0;\n    marker.color.b = 1.0;\n\n    geometry_msgs::Point start, end;\n    start.x = x;\n    start.y = y;\n\n    end.x = x + 0.5 * cos(phi);\n    end.y = y + 0.5 * sin(phi);\n\n    marker.points.push_back(start);\n    marker.points.push_back(end);\n\n    visualization_msgs::MarkerArray ma;\n    ma.markers.push_back(marker);\n\n    this->goalMarkerPublisher_.publish(ma);\n}\n\n// MELODIC\n#if ROS_VERSION_MINIMUM(1, 13, 0)\ntf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n{\n    geometry_msgs::PoseStamped paux;\n    costmapRos->getRobotPose(paux);\n    tf::Stamped<tf::Pose> tfpose;\n    tf::poseStampedMsgToTF(paux, tfpose);\n    return tfpose;\n}\n#else\n// INDIGO AND PREVIOUS\ntf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n{\n    tf::Stamped<tf::Pose> tfpose;\n    costmapRos->getRobotPose(tfpose);\n    return tfpose;\n}\n#endif\n\nvoid clamp(geometry_msgs::Twist &cmd_vel, double max_linear_x_speed_, double max_angular_z_speed_)\n{\n    if (max_angular_z_speed_ == 0 || max_linear_x_speed_ == 0)\n        return;\n\n    if (cmd_vel.angular.z == 0)\n    {\n        cmd_vel.linear.x = max_linear_x_speed_;\n    }\n    else\n    {\n        double kurvature = cmd_vel.linear.x / cmd_vel.angular.z;\n\n        double linearAuthority = fabs(cmd_vel.linear.x / max_linear_x_speed_);\n        double angularAuthority = fabs(cmd_vel.angular.z / max_angular_z_speed_);\n        if (linearAuthority < angularAuthority)\n        {\n            // lets go to maximum linear speed\n            cmd_vel.linear.x = max_linear_x_speed_;\n            cmd_vel.angular.z = kurvature / max_linear_x_speed_;\n            ROS_WARN_STREAM(\"k=\" << kurvature << \"lets go to maximum linear capacity: \" << cmd_vel);\n        }\n        else\n        {\n            // lets go with maximum angular speed\n            cmd_vel.angular.x = max_angular_z_speed_;\n            cmd_vel.linear.x = kurvature * max_angular_z_speed_;\n            ROS_WARN_STREAM(\"lets go to maximum angular capacity: \" << cmd_vel);\n        }\n    }\n}\n\n/**\n******************************************************************************************************************\n* computeVelocityCommands()\n******************************************************************************************************************\n*/\nbool ForwardLocalPlanner::computeVelocityCommands(geometry_msgs::Twist &cmd_vel)\n{\n    goalReached_ = false;\n    ROS_DEBUG(\"[ForwardLocalPlanner] ----- COMPUTE VELOCITY COMMAND LOCAL PLANNER ---\");\n\n    tf::Stamped<tf::Pose> tfpose = optionalRobotPose(costmapRos_);\n\n    geometry_msgs::PoseStamped currentPose;\n    tf::poseStampedTFToMsg(tfpose,currentPose);\n    ROS_DEBUG_STREAM(\"[ForwardLocalPlanner] current robot pose \" << currentPose);\n\n\n    bool ok = false;\n    while (!ok)\n    {\n        // iterate the point from the current position and ahead until reaching a new goal point in the path\n        while (!ok && currentPoseIndex_ < plan_.size())\n        {\n            auto &pose = plan_[currentPoseIndex_];\n            const geometry_msgs::Point &p = pose.pose.position;\n            tf::Quaternion q;\n            tf::quaternionMsgToTF(pose.pose.orientation, q);\n\n            // take error from the current position to the path point\n            double dx = p.x - tfpose.getOrigin().x();\n            double dy = p.y - tfpose.getOrigin().y();\n            double dist = sqrt(dx * dx + dy * dy);\n\n            double pangle = tf::getYaw(q);\n            double angle = tf::getYaw(tfpose.getRotation());\n            double angular_error = angles::shortest_angular_distance(pangle, angle);\n\n            if (dist >= carrot_distance_ || fabs(angular_error) > 0.1)\n            {\n                // the target pose is enough different to be defined as a target\n                ok = true;\n                ROS_DEBUG(\"current index: %d, carrot goal percentaje: %lf, dist: %lf, maxdist: %lf, angle_error: %lf\", currentPoseIndex_, 100.0 * currentPoseIndex_ / plan_.size(), dist, carrot_distance_, angular_error);\n            }\n            else\n            {\n                currentPoseIndex_++;\n            }\n        }\n\n        ROS_DEBUG_STREAM(\"[ForwardLocalPlanner] selected carrot pose index \" << currentPoseIndex_ << \"/\" << plan_.size());\n\n        if (currentPoseIndex_ >= plan_.size())\n        {\n            // even the latest point is quite similar, then take the last since it is the final goal\n            cmd_vel.linear.x = 0;\n            cmd_vel.angular.z = 0;\n            //ROS_INFO(\"End Local planner\");\n            ok = true;\n            currentPoseIndex_ = plan_.size() - 1;\n            //return true;\n        }\n    }\n\n    //ROS_INFO(\"pose control algorithm\");\n\n    const geometry_msgs::PoseStamped &finalgoalpose = plan_.back();\n    const geometry_msgs::PoseStamped &carrot_goalpose = plan_[currentPoseIndex_];\n    const geometry_msgs::Point &goalposition = carrot_goalpose.pose.position;\n\n    tf::Quaternion carrotGoalQ;\n    tf::quaternionMsgToTF(carrot_goalpose.pose.orientation, carrotGoalQ);\n    //ROS_INFO_STREAM(\"Plan goal quaternion at \"<< goalpose.pose.orientation);\n\n    //goal orientation (global frame)\n    double betta = tf::getYaw(carrot_goalpose.pose.orientation) + betta_offset_;\n\n    double dx = goalposition.x - tfpose.getOrigin().x();\n    double dy = goalposition.y - tfpose.getOrigin().y();\n\n    //distance error to the targetpoint\n    double rho_error = sqrt(dx * dx + dy * dy);\n\n    //current angle\n    tf::Quaternion currentOrientation = tfpose.getRotation();\n    double theta = tf::getYaw(currentOrientation);\n    double alpha = atan2(dy, dx);\n    alpha = alpha + alpha_offset_;\n\n    double alpha_error = angles::shortest_angular_distance(alpha, theta);\n    double betta_error = angles::shortest_angular_distance(betta, theta);\n\n    double vetta; // = k_rho_ * rho_error;\n    double gamma; //= k_alpha_ * alpha_error + k_betta_ * betta_error;\n\n    if (rho_error > xy_goal_tolerance_) // reguular control rule, be careful, rho error is with the carrot not with the final goal (this is something to improve like the backwards planner)\n    {\n        vetta = k_rho_ * rho_error;\n        gamma = k_alpha_ * alpha_error;\n    }\n    else if (fabs(betta_error) >= yaw_goal_tolerance_) // pureSpining\n    {\n        vetta = 0;\n        gamma = k_betta_ * betta_error;\n    }\n    else // goal reached\n    {\n        ROS_DEBUG(\"GOAL REACHED\");\n        vetta = 0;\n        gamma = 0;\n        goalReached_ = true;\n    }\n\n    // linear speed clamp\n    if (vetta > max_linear_x_speed_)\n    {\n        vetta = max_linear_x_speed_;\n    }\n    else if (vetta < -max_linear_x_speed_)\n    {\n        vetta = -max_linear_x_speed_;\n    }\n\n    // angular speed clamp\n    if (gamma > max_angular_z_speed_)\n    {\n        gamma = max_angular_z_speed_;\n    }\n    else if (gamma < -max_angular_z_speed_)\n    {\n        gamma = -max_angular_z_speed_;\n    }\n\n    cmd_vel.linear.x = vetta;\n    cmd_vel.angular.z = gamma;\n\n    //clamp(cmd_vel, max_linear_x_speed_, max_angular_z_speed_);\n\n    //ROS_INFO_STREAM(\"Local planner: \"<< cmd_vel);\n\n    publishGoalMarker(goalposition.x, goalposition.y, betta);\n\n    ROS_DEBUG_STREAM(\"Forward local planner,\" << std::endl\n                                              << \" theta: \" << theta << std::endl\n                                              << \" betta: \" << betta << std::endl\n                                              << \" err_x: \" << dx << std::endl\n                                              << \" err_y:\" << dy << std::endl\n                                              << \" rho_error:\" << rho_error << std::endl\n                                              << \" alpha_error:\" << alpha_error << std::endl\n                                              << \" betta_error:\" << betta_error << std::endl\n                                              << \" vetta:\" << vetta << std::endl\n                                              << \" gamma:\" << gamma << std::endl\n                                              << \" xy_goal_tolerance:\" << xy_goal_tolerance_ << std::endl\n                                              << \" yaw_goal_tolerance:\" << yaw_goal_tolerance_ << std::endl);\n\n    //if(cmd_vel.linear.x==0 && cmd_vel.angular.z == 0 )\n    //{\n    //}\n\n    //integrate trajectory and check collision\n\n    tf::Stamped<tf::Pose> global_pose = optionalRobotPose(costmapRos_);\n\n    //->getRobotPose(global_pose);\n\n    auto *costmap2d = costmapRos_->getCostmap();\n    auto yaw = tf::getYaw(global_pose.getRotation());\n\n    auto &pos = global_pose.getOrigin();\n\n    Eigen::Vector3f currentpose(pos.x(), pos.y(), yaw);\n    Eigen::Vector3f currentvel(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);\n    std::vector<Eigen::Vector3f> trajectory;\n    this->generateTrajectory(currentpose, currentvel, 0.8 /*meters*/, M_PI / 8 /*rads*/, 3.0 /*seconds*/, 0.05 /*seconds*/, trajectory);\n\n    // check plan rejection\n    bool aceptedplan = true;\n\n    uint32_t mx, my;\n\n    int i = 0;\n    // ROS_INFO_STREAM(\"lplanner goal: \" << finalgoalpose.pose.position);\n    for (auto &p : trajectory)\n    {\n        float dx = p[0] - finalgoalpose.pose.position.x;\n        float dy = p[1] - finalgoalpose.pose.position.y;\n\n        float dst = sqrt(dx * dx + dy * dy);\n        if (dst < xy_goal_tolerance_)\n        {\n            //  ROS_INFO(\"trajectory checking skipped, goal reached\");\n            break;\n        }\n\n        costmap2d->worldToMap(p[0], p[1], mx, my);\n        uint64_t cost = costmap2d->getCost(mx, my);\n\n        // ROS_INFO(\"checking cost pt %d [%lf, %lf] cell[%d,%d] = %d\", i, p[0], p[1], mx, my, cost);\n        // ROS_INFO_STREAM(\"cost: \" << cost);\n\n        // static const unsigned char NO_INFORMATION = 255;\n        // static const unsigned char LETHAL_OBSTACLE = 254;\n        // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;\n        // static const unsigned char FREE_SPACE = 0;\n\n        if (costmap2d->getCost(mx, my) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)\n        {\n            aceptedplan = false;\n            // ROS_WARN(\"ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED\");\n            break;\n        }\n        i++;\n    }\n\n    if (aceptedplan)\n    {\n        waiting_ = false;\n        return true;\n    }\n    else\n    {\n        // stop and wait\n        cmd_vel.linear.x = 0;\n        cmd_vel.angular.z = 0;\n\n        if (waiting_ == false)\n        {\n            waiting_ = true;\n            waitingStamp_ = ros::Time::now();\n        }\n        else\n        {\n            auto waitingduration = ros::Time::now() - waitingStamp_;\n\n            if (waitingduration > this->waitingTimeout_)\n            {\n                return false;\n            }\n        }\n\n        return true;\n    }\n}\n\n/**\n******************************************************************************************************************\n* isGoalReached()\n******************************************************************************************************************\n*/\nbool ForwardLocalPlanner::isGoalReached()\n{\n    return goalReached_;\n}\n\n/**\n******************************************************************************************************************\n* setPlan()\n******************************************************************************************************************\n*/\nbool ForwardLocalPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped> &plan)\n{\n    plan_ = plan;\n    goalReached_ = false;\n    return true;\n}\n} // namespace forward_local_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package pure_spinning_local_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Major Merge -> now master is unstable melodic-branch\n* fixing sm_moveit demo for melodic and creating pure spinning local planner\n* Merge branch 'master' into melodic-devel\n* large refactoring in navigation planners and behaviors to improve quality\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Merge branch 'master' into melodic-devel\n* fixing fmottion bug and planners config\n* unpushed code\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, brettpac, pablo.inigo.blasco\n\n* Major Merge -> now master is unstable melodic-branch\n* fixing sm_moveit demo for melodic and creating pure spinning local planner\n* Merge branch 'master' into melodic-devel\n* large refactoring in navigation planners and behaviors to improve quality\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Redoing Client Namespaces\n* Merge branch 'master' into melodic-devel\n* fixing fmottion bug and planners config\n* unpushed code\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(pure_spinning_local_planner)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED\n   roscpp\n   tf costmap_2d\n   geometry_msgs\n   nav_core\n   nav_msgs\n   std_msgs\n   pcl_ros\n   dynamic_reconfigure)\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\ngenerate_dynamic_reconfigure_options(\n  cfg/PureSpinningLocalPlanner.cfg\n)\n\nset_source_files_properties(\n  src/pure_spinning_local_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter\"\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES pure_spinning_local_planner\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/pure_spinning_local_planner.cpp\n)\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/pure_spinning_local_planner_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(FILES\n   pslp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_pure_spinning_local_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/cfg/PureSpinningLocalPlanner.cfg",
    "content": "#!/usr/bin/env python\nPACKAGE = \"pure_spinning_local_planner\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\n\ngen.add(\"k_betta\",   double_t,   1, \"goal angle error gain\", 0.1 )\ngen.add(\"yaw_goal_tolerance\",   double_t,   1, \"radians\", 0.05 )\ngen.add(\"enable_obstacle_checking\",   bool_t,   1, \"bool\", True )\ngen.add(\"max_angular_z_speed\",   double_t,   1, \"maximum angular speed in radians per second\", 1.0 )\n\nexit(gen.generate(PACKAGE, \"pure_spinning_local_planner\", \"PureSpinningLocalPlanner\"))\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/config/pure_spinning_local_planner.yaml",
    "content": "k_betta: 1.0\nyaw_goal_tolerance: 0.02\nmax_angular_z_speed: 2.0 # rad/s\nintermediate_goals_yaw_tolerance: 0.04\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/include/pure_spinning_local_planner/pure_spinning_local_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n#include <dynamic_reconfigure/server.h>\n#include <geometry_msgs/PoseStamped.h>\n#include <nav_core/base_local_planner.h>\n#include <tf/tf.h>\n#include <tf/transform_listener.h>\n#include <tf2_ros/buffer.h>\n#include <Eigen/Eigen>\n#include <pure_spinning_local_planner/PureSpinningLocalPlannerConfig.h>\n\ntypedef double meter;\ntypedef double rad;\ntypedef double rad_s;\n\nnamespace cl_move_base_z\n{\nnamespace pure_spinning_local_planner\n{\nclass PureSpinningLocalPlanner : public nav_core::BaseLocalPlanner\n{\npublic:\n  PureSpinningLocalPlanner();\n\n  virtual ~PureSpinningLocalPlanner();\n\n    /**\n   * @brief  Given the current position, orientation, and velocity of the robot: compute velocity commands to send to\n   * the robot mobile base\n   * @param cmd_vel Will be filled with the velocity command to be passed to the robot base\n   * @return True if a valid velocity command was found, false otherwise\n   */\n  virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override;\n\n  /**\n   * @brief  Check if the goal pose has been achieved by the local planner\n   * @return True if achieved, false otherwise\n   */\n  virtual bool isGoalReached() override;\n\n  /**\n   * @brief  Set the plan that the local planner is following\n   * @param plan The plan to pass to the local planner\n   * @return True if the plan was updated successfully, false otherwise\n   */\n  virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped> &plan) override;\n\n  /**\n   * @brief  Constructs the local planner\n   * @param name The name to give this instance of the local planner\n   * @param tf A pointer to a transform listener\n   * @param costmap_ros The cost map to use for assigning costs to local plans\n   */\n  void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos);\n\n  void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos);\n\n  void initialize();\n\nprivate:\n  void reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level);\n\n  void publishGoalMarker(double x, double y, double phi);\n\n  costmap_2d::Costmap2DROS *costmapRos_;\n\n  std::vector<geometry_msgs::PoseStamped> plan_;\n\n  dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig> paramServer_;\n\n\n  double k_betta_;\n  bool goalReached_;\n  int currentPoseIndex_;\n  rad yaw_goal_tolerance_;\n  rad intermediate_goal_yaw_tolerance_;\n  rad_s max_angular_z_speed_;\n};\n}  // namespace pure_spinning_local_planner\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>pure_spinning_local_planner</name>\n    <version>1.4.16</version>\n  <description>The pure_spinning_local_planner package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/pure_spinning_local_planner</url> -->\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>costmap_2d</depend>\n  <depend>geometry_msgs</depend>\n  <depend>nav_core</depend>\n  <depend>nav_msgs</depend>\n  <depend>std_msgs</depend>\n  <depend>pcl_ros</depend>\n  <depend>roscpp</depend>\n  <depend>tf</depend>\n  <depend>dynamic_reconfigure</depend>\n\n\n  <export>\n    <nav_core plugin=\"${prefix}/pslp_plugin.xml\" />\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/pslp_plugin.xml",
    "content": "<library path=\"libpure_spinning_local_planner\">\n  <class name=\"pure_spinning_local_planner/PureSpinningLocalPlanner\" type=\"cl_move_base_z::pure_spinning_local_planner::PureSpinningLocalPlanner\" base_class_type=\"nav_core::BaseLocalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/pure_spinning_local_planner/src/pure_spinning_local_planner/pure_spinning_local_planner.cpp",
    "content": "\n#include <angles/angles.h>\n#include <pure_spinning_local_planner/pure_spinning_local_planner.h>\n#include <pluginlib/class_list_macros.h>\n\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::pure_spinning_local_planner::PureSpinningLocalPlanner, nav_core::BaseLocalPlanner)\n\nnamespace cl_move_base_z\n{\nnamespace pure_spinning_local_planner\n{\n// MELODIC\n#if ROS_VERSION_MINIMUM(1, 13, 0)\ntf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n{\n  geometry_msgs::PoseStamped paux;\n  costmapRos->getRobotPose(paux);\n  tf::Stamped<tf::Pose> tfpose;\n  tf::poseStampedMsgToTF(paux, tfpose);\n  return tfpose;\n}\n#else\n// INDIGO AND PREVIOUS\ntf::Stamped<tf::Pose> optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)\n{\n  tf::Stamped<tf::Pose> tfpose;\n  costmapRos->getRobotPose(tfpose);\n  return tfpose;\n}\n#endif\n\nPureSpinningLocalPlanner::PureSpinningLocalPlanner()\n  : paramServer_(ros::NodeHandle(\"~PureSpinningLocalPlanner\"))\n{\n  ROS_INFO_STREAM(\"[PureSpinningLocalPlanner] pure spinning planner already created\");\n}\n\nPureSpinningLocalPlanner::~PureSpinningLocalPlanner()\n{\n}\n\nvoid PureSpinningLocalPlanner::initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos)\n{\n  costmapRos_ = costmapRos;\n  this->initialize();\n}\n\nvoid PureSpinningLocalPlanner::initialize(std::string name, tf::TransformListener *tf,\n                                          costmap_2d::Costmap2DROS *costmapRos)\n{\n  costmapRos_ = costmapRos;\n  this->initialize();\n}\n\nvoid PureSpinningLocalPlanner::initialize()\n{\n  ros::NodeHandle nh(\"~/PureSpinningLocalPlanner\");\n  nh.param(\"k_betta\", k_betta_, 10.0);\n  nh.param(\"yaw_goal_tolerance\", yaw_goal_tolerance_, 0.08);\n  nh.param(\"intermediate_goals_yaw_tolerance\", intermediate_goal_yaw_tolerance_, 0.12);\n  nh.param(\"max_angular_z_speed\", max_angular_z_speed_, 1.0);\n\n  dynamic_reconfigure::Server<::pure_spinning_local_planner::PureSpinningLocalPlannerConfig>::CallbackType f;\n  f = boost::bind(&PureSpinningLocalPlanner::reconfigCB, this, _1, _2);\n  paramServer_.setCallback(f);\n}\n\nvoid PureSpinningLocalPlanner::reconfigCB(::pure_spinning_local_planner::PureSpinningLocalPlannerConfig &config, uint32_t level)\n{\n  this->k_betta_ = config.k_betta;\n  this->yaw_goal_tolerance_ = config.yaw_goal_tolerance;\n  this->max_angular_z_speed_ = config.max_angular_z_speed;\n}\nbool PureSpinningLocalPlanner::computeVelocityCommands(geometry_msgs::Twist &cmd_vel)\n{\n  goalReached_ = false;\n  // ROS_DEBUG(\"LOCAL PLANNER LOOP\");\n\n  tf::Stamped<tf::Pose> tfpose = optionalRobotPose(costmapRos_);\n\n  geometry_msgs::PoseStamped currentPose;\n  tf::poseStampedTFToMsg(tfpose, currentPose);\n  // ROS_INFO_STREAM(\"[PureSpinningLocalPlanner] current robot pose \" << currentPose);\n\n  tf::Quaternion q = tfpose.getRotation();\n  auto currentYaw = tf::getYaw(currentPose.pose.orientation);\n  double angular_error;\n  double targetYaw;\n\n  while (currentPoseIndex_ < plan_.size())\n  {\n    auto &goal = plan_[currentPoseIndex_];\n    targetYaw = tf::getYaw(goal.pose.orientation);\n\n    //double angular_error = angles::shortest_angular_distance( currentYaw , targetYaw) ;\n    angular_error = targetYaw - currentYaw ;\n\n    // all the points must be reached using the control rule, but the last one\n    // have an special condition\n    if ( (currentPoseIndex_ < plan_.size() -1 && fabs(angular_error) < this->intermediate_goal_yaw_tolerance_)\n         || (currentPoseIndex_ == plan_.size() -1 && fabs(angular_error) < this->intermediate_goal_yaw_tolerance_)\n    )\n    {\n      currentPoseIndex_++;\n    }\n    else\n    {\n      break;\n    }\n  }\n\n  auto omega = angular_error * k_betta_;\n  cmd_vel.angular.z = std::min(std::max(omega, -fabs(max_angular_z_speed_)), fabs(max_angular_z_speed_));\n\n  //ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] current yaw: \" << currentYaw);\n  //ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] target yaw: \" << targetYaw);\n  ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] angular error: \" << angular_error << \"(\"<<yaw_goal_tolerance_<<\")\");\n  ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] command angular speed: \" << cmd_vel.angular.z);\n  ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] completion \" << currentPoseIndex_ << \"/\"<< plan_.size());\n\n  if (currentPoseIndex_ >= plan_.size() -1 && fabs(angular_error) < yaw_goal_tolerance_)\n  {\n    ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] GOAL REACHED \");\n    goalReached_ = true;\n  }\n\n  return true;\n}\n\nbool PureSpinningLocalPlanner::isGoalReached()\n{\n  return goalReached_;\n}\n\nbool PureSpinningLocalPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped> &plan)\n{\n  ROS_DEBUG_STREAM(\"[PureSpinningLocalPlanner] setting global plan to follow\");\n\n  plan_ = plan;\n  goalReached_ = false;\n  currentPoseIndex_ = 0;\n  return true;\n}\n\nvoid publishGoalMarker(double x, double y, double phi)\n{\n}\n}  // namespace pure_spinning_local_planner\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package backward_global_planner\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(undo_path_global_planner)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED\n  costmap_2d\n  geometry_msgs\n  std_msgs\n  message_generation\n  nav_core\n  nav_msgs\n  roscpp\n  tf\n)\n\nset_source_files_properties(\n  src/undo_path_global_planner.cpp\n  PROPERTIES\n  COMPILE_FLAGS \"-Wno-unused-parameter\"\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES undo_path_global_planner\n  CATKIN_DEPENDS costmap_2d geometry_msgs nav_core nav_msgs roscpp tf\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n ${forward_global_planner_INCLUDE_DIRS}}\n)\n\nadd_library(${PROJECT_NAME}\n  src/undo_path_global_planner.cpp\n)\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\ntarget_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/undo_path_global_planner_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   upgp_plugin.xml\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_undo_path_global_planner.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/include/undo_path_global_planner/undo_path_global_planner.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <nav_core/base_global_planner.h>\n#include <nav_msgs/GetPlan.h>\n#include <nav_msgs/Path.h>\n#include <ros/ros.h>\n\nnamespace cl_move_base_z\n{\nnamespace undo_path_global_planner\n{\nclass UndoPathGlobalPlanner : public nav_core::BaseGlobalPlanner\n{\npublic:\n    UndoPathGlobalPlanner();\n\n    virtual ~UndoPathGlobalPlanner();\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);\n\n    bool makePlan(const geometry_msgs::PoseStamped &start,\n                  const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                  double &cost);\n\n    virtual bool createDefaultUndoPathPlan(const geometry_msgs::PoseStamped &start,\n                                           const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan);\n\n    virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros_) override;\n\nprivate:\n    ros::NodeHandle nh_;\n\n    ros::Subscriber forwardPathSub_;\n\n    ros::Publisher planPub_;\n\n    ros::Publisher markersPub_;\n\n    nav_msgs::Path lastForwardPathMsg_;\n\n    /// stored but almost not used\n    costmap_2d::Costmap2DROS *costmap_ros_;\n\n    void onForwardTrailMsg(const nav_msgs::Path::ConstPtr &trailMessage);\n\n    void publishGoalMarker(const geometry_msgs::Pose &pose, double r, double g, double b);\n\n    ros::ServiceServer cmd_server_;\n\n    double skip_straight_motion_distance_; //meters\n\n    double puresSpinningRadStep_; // rads\n};\n} // namespace backward_global_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>undo_path_global_planner</name>\n    <version>1.4.16</version>\n  <description>The undo_path_global_planner package.</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n\n  <license>BSDv3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>geometry_msgs</depend>\n  <depend>message_generation</depend>\n  <depend>message_runtime</depend>\n  <depend>nav_core</depend>\n  <depend>nav_msgs</depend>\n  <depend>pcl_ros</depend>\n  <depend>roscpp</depend>\n  <depend>tf</depend>\n  <depend>costmap_2d</depend>\n  <depend>dynamic_reconfigure</depend>\n\n  <export>\n      <nav_core plugin=\"${prefix}/upgp_plugin.xml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/src/undo_path_global_planner.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <boost/assign.hpp>\n#include <boost/range/adaptor/reversed.hpp>\n#include <boost/range/algorithm/copy.hpp>\n#include <pluginlib/class_list_macros.h>\n#include <undo_path_global_planner/undo_path_global_planner.h>\n#include <fstream>\n#include <streambuf>\n#include <nav_msgs/Path.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <tf/tf.h>\n#include <tf/transform_datatypes.h>\n#include <angles/angles.h>\n\n//register this planner as a BaseGlobalPlanner plugin\n\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::undo_path_global_planner::UndoPathGlobalPlanner, nav_core::BaseGlobalPlanner);\n\nnamespace cl_move_base_z\n{\n    namespace undo_path_global_planner\n    {\n        /**\n******************************************************************************************************************\n* Constructor()\n******************************************************************************************************************\n*/\n        UndoPathGlobalPlanner::UndoPathGlobalPlanner()\n        {\n            skip_straight_motion_distance_ = 0.2;\n        }\n\n        UndoPathGlobalPlanner::~UndoPathGlobalPlanner()\n        {\n            //clear\n            nav_msgs::Path planMsg;\n            planMsg.header.stamp = ros::Time::now();\n            planPub_.publish(planMsg);\n        }\n\n        /**\n******************************************************************************************************************\n* initialize()\n******************************************************************************************************************\n*/\n        void UndoPathGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)\n        {\n            //ROS_INFO_NAMED(\"Backwards\", \"UndoPathGlobalPlanner initialize\");\n            costmap_ros_ = costmap_ros;\n            //ROS_WARN_NAMED(\"Backwards\", \"initializating global planner, costmap address: %ld\", (long)costmap_ros);\n\n            forwardPathSub_ = nh_.subscribe(\"odom_tracker_path\", 2, &UndoPathGlobalPlanner::onForwardTrailMsg, this);\n\n            ros::NodeHandle nh;\n            planPub_ = nh.advertise<nav_msgs::Path>(\"undo_path_planner/global_plan\", 1);\n            markersPub_ = nh.advertise<visualization_msgs::MarkerArray>(\"undo_path_planner/markers\", 1);\n        }\n\n        /**\n******************************************************************************************************************\n* onForwardTrailMsg()\n******************************************************************************************************************\n*/\n        void UndoPathGlobalPlanner::onForwardTrailMsg(const nav_msgs::Path::ConstPtr &trailMessage)\n        {\n            lastForwardPathMsg_ = *trailMessage;\n            ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] received backward path msg poses [\" << lastForwardPathMsg_.poses.size() << \"]\");\n        }\n\n        /**\n******************************************************************************************************************\n* publishGoalMarker()\n******************************************************************************************************************\n*/\n        void UndoPathGlobalPlanner::publishGoalMarker(const geometry_msgs::Pose &pose, double r, double g, double b)\n        {\n            double phi = tf::getYaw(pose.orientation);\n            visualization_msgs::Marker marker;\n            marker.header.frame_id = this->costmap_ros_->getGlobalFrameID();\n            marker.header.stamp = ros::Time::now();\n            marker.ns = \"my_namespace2\";\n            marker.id = 0;\n            marker.type = visualization_msgs::Marker::ARROW;\n            marker.action = visualization_msgs::Marker::ADD;\n            marker.scale.x = 0.1;\n            marker.scale.y = 0.3;\n            marker.scale.z = 0.1;\n            marker.color.a = 1.0;\n            marker.color.r = r;\n            marker.color.g = g;\n            marker.color.b = b;\n\n            geometry_msgs::Point start, end;\n            start.x = pose.position.x;\n            start.y = pose.position.y;\n\n            end.x = pose.position.x + 0.5 * cos(phi);\n            end.y = pose.position.y + 0.5 * sin(phi);\n\n            marker.points.push_back(start);\n            marker.points.push_back(end);\n\n            visualization_msgs::MarkerArray ma;\n            ma.markers.push_back(marker);\n\n            markersPub_.publish(ma);\n        }\n\n        /**\n******************************************************************************************************************\n* defaultBackwardPath()\n******************************************************************************************************************\n*/\n        bool UndoPathGlobalPlanner::createDefaultUndoPathPlan(const geometry_msgs::PoseStamped &start,\n                                                              const geometry_msgs::PoseStamped &goal,\n                                                              std::vector<geometry_msgs::PoseStamped> &plan)\n        {\n            //ROS_WARN_NAMED(\"Backwards\", \"Iterating in last forward cord path\");\n            int i = lastForwardPathMsg_.poses.size() - 1;\n            double linear_mindist = std::numeric_limits<double>::max();\n            int mindistindex = -1;\n            double startPoseAngle = tf::getYaw(start.pose.orientation);\n            geometry_msgs::Pose startPositionProjected;\n\n            // The goal of this code is finding the most convenient initial path pose.\n            // first, find closest linear point to the current robot position\n            // we start from the final goal, that is, the beginning of the trajectory\n            // (since this was the forward motion from the odom tracker)\n            for (auto &p : lastForwardPathMsg_.poses /*| boost::adaptors::reversed*/)\n            {\n                geometry_msgs::PoseStamped pose = p;\n                pose.header.frame_id = costmap_ros_->getGlobalFrameID();\n                pose.header.stamp = ros::Time::now();\n\n                double dx = pose.pose.position.x - start.pose.position.x;\n                double dy = pose.pose.position.y - start.pose.position.y;\n\n                double dist = sqrt(dx * dx + dy * dy);\n                double angleOrientation = tf::getYaw(pose.pose.orientation);\n                double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));\n                if (dist <= linear_mindist)\n                {\n                    mindistindex = i;\n                    linear_mindist = dist;\n                    startPositionProjected = pose.pose;\n\n                    ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] initial start point search, NEWBEST_LINEAR= \" << i << \". error, linear: \" << linear_mindist << \", angular: \" << angleError);\n                }\n                else\n                {\n                    ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] initial start point search, skipped= \" << i << \". best linear error: \" << linear_mindist << \". current error, linear: \" << dist << \" angular: \" << angleError);\n                }\n\n                i--;\n            }\n\n            double const ERROR_DISTANCE_PURE_SPINNING_FACTOR = 1.5;\n            // Concept of second pass: now we only consider a pure spinning motion in this point. We want to consume some very close angular targets, (accepting a larger linear minerror of 1.5 besterror. That is, more or less in the same point).\n\n            ROS_DEBUG(\"[UndoPathGlobalPlanner] second angular pass\");\n            double angularMinDist = std::numeric_limits<double>::max();\n\n                if(mindistindex >=  lastForwardPathMsg_.poses.size())\n                    mindistindex = lastForwardPathMsg_.poses.size() -1;// workaround, something is making a out of bound exception in poses array access\n            {\n                if(lastForwardPathMsg_.poses.size() == 0)\n                {\n                    ROS_WARN_STREAM(\"[UndoPathGlobalPlanner] Warning possible bug\");\n                }\n\n                ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] second pass loop\");\n                for (int i = mindistindex; i >= 0; i--)\n                {\n                    // warning this index, i refers to some inverse interpretation from the previous loop,\n                    // (last indexes in this path corresponds to the poses closer to our current position)\n                    ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] \" << i << \"/\" << lastForwardPathMsg_.poses.size());\n                    auto index = lastForwardPathMsg_.poses.size() - i -1;\n                    if(index < 0 || index >= lastForwardPathMsg_.poses.size())\n                    {\n                        ROS_WARN_STREAM(\"[UndoPathGlobalPlanner] this should not happen. Check implementation.\");\n                        break;\n                    }\n                    geometry_msgs::PoseStamped pose = lastForwardPathMsg_.poses[lastForwardPathMsg_.poses.size() - i -1];\n\n                    ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] global frame\");\n                    pose.header.frame_id = costmap_ros_->getGlobalFrameID();\n                    pose.header.stamp = ros::Time::now();\n\n                    double dx = pose.pose.position.x - start.pose.position.x;\n                    double dy = pose.pose.position.y - start.pose.position.y;\n\n                    double dist = sqrt(dx * dx + dy * dy);\n                    if (dist <= linear_mindist * ERROR_DISTANCE_PURE_SPINNING_FACTOR)\n                    {\n                        double angleOrientation = tf::getYaw(pose.pose.orientation);\n                        double angleError = fabs(angles::shortest_angular_distance(angleOrientation, startPoseAngle));\n                        if (angleError < angularMinDist)\n                        {\n                            angularMinDist = angleError;\n                            mindistindex = i;\n                            ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] initial start point search (angular update), NEWBEST_ANGULAR= \" << i << \". error, linear: \"<<  dist << \"(\" << linear_mindist << \")\" <<\", angular: \" << angleError << \"(\" << angularMinDist << \")\");\n                        }\n                        else\n                        {\n                            ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] initial start point search (angular update), skipped= \" << i <<\". error, linear: \"<<  dist << \"(\" << linear_mindist << \")\" <<\", angular: \"  << angleError << \"(\" << angularMinDist << \")\");\n                        }\n                    }\n                    else\n                    {\n                        ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] initial start point search (angular update) not in linear range, skipped= \" << i << \" linear error: \" << dist << \"(\" << linear_mindist << \")\");\n                    }\n                }\n            }\n\n            if (mindistindex != -1)\n            {\n                //plan.push_back(start);\n\n                ROS_WARN_STREAM(\"[UndoPathGlobalPlanner] Creating the backwards plan from odom tracker path (\" << lastForwardPathMsg_.poses.size() << \") poses\");\n                ROS_WARN_STREAM(\"[UndoPathGlobalPlanner] closer point to goal i=\" << mindistindex << \" (linear min dist \" << linear_mindist << \")\");\n                // copy the path at the inverse direction\n                for (int i = lastForwardPathMsg_.poses.size() - 1; i >= mindistindex; i--)\n                {\n                    auto &pose = lastForwardPathMsg_.poses[i];\n                    ROS_DEBUG_STREAM(\"[UndoPathGlobalPlanner] adding to plan i = \" << i);\n                    plan.push_back(pose);\n                }\n                ROS_WARN_STREAM(\"[UndoPathGlobalPlanner] refined plan has \" << plan.size() << \"  points\");\n            }\n            else\n            {\n                ROS_ERROR_STREAM(\"[UndoPathGlobalPlanner ] backward global plan size:  \" << plan.size());\n            }\n\n            return true;\n        }\n\n        /**\n******************************************************************************************************************\n* makePlan()\n******************************************************************************************************************\n*/\n        bool UndoPathGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                             const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan)\n        {\n            //ROS_WARN_NAMED(\"Backwards\", \"Backwards global planner: Generating global plan \");\n            //ROS_WARN_NAMED(\"Backwards\", \"Clearing...\");\n\n            plan.clear();\n\n            if(lastForwardPathMsg_.poses.size() == 0)\n            {\n                return false;\n            }\n\n            auto forcedGoal = lastForwardPathMsg_.poses[lastForwardPathMsg_.poses.size() - 1]; // FORCE LAST POSE\n            this->createDefaultUndoPathPlan(start, forcedGoal, plan);\n            //this->createPureSpiningAndStragihtLineBackwardPath(start, goal, plan);\n\n            //ROS_INFO_STREAM(\" start - \" << start);\n            //ROS_INFO_STREAM(\" end - \" << goal.pose.position);\n\n            //ROS_INFO(\"3 - heading to goal orientation\");\n            //double goalOrientation = angles::normalize_angle(tf::getYaw(goal.pose.orientation));\n            //cl_move_base_z::makePureSpinningSubPlan(prevState,goalOrientation,plan);\n\n            //ROS_WARN_STREAM( \"MAKE PLAN INVOKED, plan size:\"<< plan.size());\n            publishGoalMarker(forcedGoal.pose, 1.0, 0, 1.0);\n\n            nav_msgs::Path planMsg;\n            planMsg.poses = plan;\n            planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();\n\n            // check plan rejection\n            bool acceptedGlobalPlan = true;\n\n            // static const unsigned char NO_INFORMATION = 255;\n            // static const unsigned char LETHAL_OBSTACLE = 254;\n            // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;\n            // static const unsigned char FREE_SPACE = 0;\n\n            costmap_2d::Costmap2D *costmap2d = this->costmap_ros_->getCostmap();\n            for (auto &p : plan)\n            {\n                uint32_t mx, my;\n                costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);\n                auto cost = costmap2d->getCost(mx, my);\n\n                if (cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)\n                {\n                    acceptedGlobalPlan = false;\n                    break;\n                }\n            }\n\n            planPub_.publish(planMsg);\n\n            // this was previously set to size() <= 1, but a plan with a single point is also a valid plan (the goal)\n            return true;\n        }\n\n        /**\n******************************************************************************************************************\n* makePlan()\n******************************************************************************************************************\n*/\n        bool UndoPathGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start,\n                                             const geometry_msgs::PoseStamped &goal, std::vector<geometry_msgs::PoseStamped> &plan,\n                                             double &cost)\n        {\n            cost = 0;\n            makePlan(start, goal, plan);\n            return true;\n        }\n\n    } // namespace undo_path_global_planner\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/custom_planners/undo_path_global_planner/upgp_plugin.xml",
    "content": "<library path=\"libundo_path_global_planner\">\n  <class name=\"undo_path_global_planner/UndoPathGlobalPlanner\" type=\"cl_move_base_z::undo_path_global_planner::UndoPathGlobalPlanner\" base_class_type=\"nav_core::BaseGlobalPlanner\">\n    <description>\n    </description>\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package smacc_navigation_plugin\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(move_base_z_client_plugin)\n\nfind_package(catkin REQUIRED smacc pluginlib tf dynamic_reconfigure)\nfind_package(yaml-cpp REQUIRED)\nfind_package(Threads REQUIRED)\n\n# Needed so catkin can package the thread library dependency\nset(THREADS_LIBRARIES \"${CMAKE_THREAD_LIBS_INIT}\")\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n\nadd_action_files(\n   FILES\n   OdomTracker.action\n)\n\n## Generate added messages and services with any dependencies listed here\ngenerate_messages(\n   DEPENDENCIES\n   actionlib_msgs\n )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\ngenerate_dynamic_reconfigure_options(\n  cfg/OdomTracker.cfg\n)\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n   INCLUDE_DIRS include\n   LIBRARIES move_base_z_client_plugin odom_tracker waypoints_navigator planner_switcher move_base_z_client_behaviors costmap_switch pose\n   CATKIN_DEPENDS smacc tf\n   DEPENDS THREADS YAML_CPP\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 17)\n#add_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   src/move_base_z_client_plugin.cpp\n )\n\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n)\n\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n#----------------------------------\n\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n#----------------------------------\n## Declare a C++ library\nadd_library(odom_tracker\n   src/components/odom_tracker/odom_tracker.cpp\n)\n\ntarget_link_libraries(odom_tracker\n   ${catkin_LIBRARIES})\n#----------------------------------\nadd_library(planner_switcher\n   src/components/planner_switcher/planner_switcher.cpp\n)\n\ntarget_link_libraries(planner_switcher\n   ${catkin_LIBRARIES})\n\n#----------------------------------\nadd_library(pose\n   src/components/pose/cp_pose.cpp\n)\n\ntarget_link_libraries(pose\n   ${catkin_LIBRARIES}\n   Threads::Threads\n)\n\n#----------------------------------\nadd_library(costmap_switch\n   src/components/costmap_switch/cp_costmap_switch.cpp\n)\n\ntarget_link_libraries(costmap_switch\n   ${catkin_LIBRARIES})\n\n#----------------------------------\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n ${YAML_CPP_INCLUDE_DIR}\n)\n\n## Declare a C++ library\n add_library(waypoints_navigator\n   src/components/waypoints_navigator/waypoints_event_dispatcher.cpp\n   src/components/waypoints_navigator/waypoints_navigator.cpp\n )\n\ntarget_link_libraries(waypoints_navigator\n   ${catkin_LIBRARIES}\n   ${YAML_CPP_LIBRARIES}\n   planner_switcher\n   move_base_z_client_plugin\n)\n#----------------------------------\nfile(GLOB_RECURSE SRC_FILES \"src/client_behaviors/*.cpp\") # opcionalmente GLOB\n\nadd_library(move_base_z_client_behaviors\n   ${SRC_FILES}\n)\n\ntarget_link_libraries(move_base_z_client_behaviors\n   ${catkin_LIBRARIES}\n   odom_tracker\n   planner_switcher\n   waypoints_navigator\n   Threads::Threads\n)\n\n\n add_dependencies(odom_tracker ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\n install(TARGETS ${PROJECT_NAME} odom_tracker waypoints_navigator planner_switcher costmap_switch move_base_z_client_behaviors pose\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_move_base_z_client_plugin.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/action/OdomTracker.action",
    "content": "uint8 command\n\n# Possible command values\nuint8 RECORD_PATH = 0\nuint8 CLEAR_BACKWARDS = 1\nuint8 IDLE = 2 # do nothing\nuint8 START_BROADCAST_PATH = 3\nuint8 STOP_BROADCAST_PATH = 4\nuint8 PUSH_PATH = 5\nuint8 POP_PATH = 6\n---\n---\nuint8 result\n\n# Possible result values\nuint8 RESULT_SUCCESS = 0\nuint8 RESULT_ERROR = 1\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/cfg/OdomTracker.cfg",
    "content": "#!/usr/bin/env python\nPACKAGE = \"move_base_z_client_plugin\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\n\ngen.add(\"odom_frame\",   str_t,   1, \"\",  \"odom\")\ngen.add(\"record_point_distance_threshold\",   double_t,   1, \"\",  0.005 )\ngen.add(\"record_angular_distance_threshold\",   double_t,   1, \"\", 0.1 )\ngen.add(\"clear_point_distance_threshold\",   double_t,   1, \"\", 0.05 )\ngen.add(\"clear_angular_distance_threshold\",   double_t,   1, \"\", 0.1)\n\nexit(gen.generate(PACKAGE, \"odom_tracker\", \"OdomTracker\"))\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_absolute_rotate.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <tf/transform_listener.h>\n#include <boost/optional.hpp>\n#include \"cb_move_base_client_behavior_base.h\"\n\nnamespace cl_move_base_z\n{\nenum class SpiningPlanner\n{\n  Default,\n  PureSpinning,\n  Forward\n};\n\nclass CbAbsoluteRotate : public CbMoveBaseClientBehaviorBase\n{\npublic:\n  tf::TransformListener listener;\n\n  boost::optional<float> absoluteGoalAngleDegree;\n  boost::optional<float> yawGoalTolerance;\n  boost::optional<float> maxVelTheta;  // if not defined, default parameter server\n  boost::optional<SpiningPlanner> spinningPlanner;\n\n  CbAbsoluteRotate();\n\n  CbAbsoluteRotate(float absoluteGoalAngleDegree, float yawGoalTolerance = -1);\n\n  virtual void onEntry() override;\n  virtual void onExit() override;\n\nprivate:\n  void updateTemporalBehaviorParameters(bool undo);\n  float oldYawTolerance;\n  float oldMaxVelTheta;\n  float oldMinVelTheta;\n};\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_move_base_client_behavior_base.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <visualization_msgs/MarkerArray.h>\n\n#include <tf/transform_listener.h>\n#include <boost/optional.hpp>\nnamespace cl_move_base_z\n{\nclass CbMoveBaseClientBehaviorBase : public smacc::SmaccAsyncClientBehavior\n{\npublic:\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    smacc::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n    this->requiresClient(moveBaseClient_);\n    moveBaseClient_->onSucceeded(&CbMoveBaseClientBehaviorBase::propagateSuccessEvent, this);\n    moveBaseClient_->onAborted(&CbMoveBaseClientBehaviorBase::propagateFailureEvent, this);\n\n    ros::NodeHandle nh;\n    visualizationMarkersPub_ = nh.advertise<visualization_msgs::MarkerArray>(\"move_base_z/visualization_markers\", 1);\n  }\n\nprotected:\n  ClMoveBaseZ* moveBaseClient_;\n  ros::Publisher visualizationMarkersPub_;\n\nprivate:\n  void propagateSuccessEvent(ClMoveBaseZ::ResultConstPtr& r);\n  void propagateFailureEvent(ClMoveBaseZ::ResultConstPtr& r);\n};\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_navigate_backwards.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_base_client_behavior_base.h\"\n#include <tf/transform_listener.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n\nnamespace cl_move_base_z\n{\n    // It sends the mobile base some distance backwards\n    class CbNavigateBackwards : public CbMoveBaseClientBehaviorBase\n    {\n    public:\n        boost::optional<float> backwardDistance;\n\n        // just a stub to show how to use parameterless constructor\n        boost::optional<float> backwardSpeed;\n\n        tf::TransformListener listener;\n\n        cl_move_base_z::odom_tracker::OdomTracker *odomTracker_;\n\n        CbNavigateBackwards(float backwardDistance);\n\n        CbNavigateBackwards();\n\n        virtual void onEntry() override;\n\n        virtual void onExit() override;\n    };\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_navigate_forward.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_base_client_behavior_base.h\"\n#include <tf/transform_listener.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n\nnamespace cl_move_base_z\n{\n    class CbNavigateForward : public CbMoveBaseClientBehaviorBase\n    {\n    public:\n        boost::optional<float> forwardDistance;\n\n        // just a stub to show how to use parameterless constructor\n        boost::optional<float> forwardSpeed;\n\n        // this may be useful in the case you want to do a stright line with some orientation\n        // relative to some global reference (trying to solve the initial orientation error\n        // of the current orientation). If it is not set, the orientation of the straight line is\n        // the orientation of the initial state.\n        boost::optional<geometry_msgs::Quaternion> forceInitialOrientation;\n\n        tf::TransformListener listener;\n\n        odom_tracker::OdomTracker *odomTracker_;\n\n        CbNavigateForward(float forwardDistance);\n\n        CbNavigateForward();\n\n        virtual void onEntry() override;\n\n        virtual void onExit() override;\n    };\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_navigate_global_position.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_base_client_behavior_base.h\"\n#include <boost/optional.hpp>\n#include <geometry_msgs/Point.h>\n\nnamespace cl_move_base_z\n{\n  class CbNavigateGlobalPosition : public CbMoveBaseClientBehaviorBase\n  {\n  public:\n    boost::optional<geometry_msgs::Point> goalPosition;\n    boost::optional<float> goalYaw;\n\n    //boost::optional<float> goalToleranceXY; // not implemented yet\n    //boost::optional<float> yawTolerance; // not implemented yet\n\n    CbNavigateGlobalPosition();\n\n    CbNavigateGlobalPosition(float x, float y, float yaw /*radians*/);\n\n    void setGoal(const geometry_msgs::Pose &pose);\n\n    virtual void onEntry();\n\n    // auxiliary function that defines the motion that is requested to the move_base action server\n    void execute();\n\n    void readStartPoseFromParameterServer(ClMoveBaseZ::Goal &goal);\n\n    // This is the substate destructor. This code will be executed when the\n    // workflow exits from this substate (that is according to statechart the moment when this object is destroyed)\n    virtual void onExit() override;\n  };\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_navigate_next_waypoint.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_base_client_behavior_base.h\"\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\nnamespace cl_move_base_z\n{\n    class CbNavigateNextWaypoint : public CbMoveBaseClientBehaviorBase\n    {\n    public:\n        CbNavigateNextWaypoint();\n\n        virtual ~CbNavigateNextWaypoint();\n\n        virtual void onEntry() override;\n\n        virtual void onExit() override;\n    };\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_rotate.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_base_client_behavior_base.h\"\n#include <tf/transform_listener.h>\n\nnamespace cl_move_base_z\n{\nclass CbRotate : public CbMoveBaseClientBehaviorBase\n{\npublic:\n    tf::TransformListener listener;\n\n    boost::optional<float> rotateDegree;\n\n    CbRotate();\n\n    CbRotate(float rotate_degree);\n\n    virtual void onEntry() override;\n};\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <tf/transform_listener.h>\n#include \"cb_move_base_client_behavior_base.h\"\n\nnamespace cl_move_base_z\n{\nenum UndoPathLocalPlanner\n{\n  BackwardsLocalPlanner, /*default, it is able to move freely backwards, or combined straightsegments with pure spinning\n                            segments*/\n  PureSpinningLocalPlanner    /*only pure spinnings, be careful it may not be able to undo the path if it was not a pure\n                            spinning segment*/\n};\n\nclass CbUndoPathBackwards : public CbMoveBaseClientBehaviorBase\n{\npublic:\n  boost::optional<UndoPathLocalPlanner> forceUndoLocalPlanner;\n\n  virtual void onEntry() override;\n\n  virtual void onExit() override;\n\nprivate:\n  tf::TransformListener listener;\n};\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards2.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n#include <smacc/smacc_updatable.h>\n#include <tf/transform_listener.h>\n#include \"cb_move_base_client_behavior_base.h\"\n\nnamespace cl_move_base_z\n{\ntemplate <typename TSource, typename TObjectTag>\nstruct EvGoalVirtualLinePassed : sc::event<EvGoalVirtualLinePassed<TSource, TObjectTag>>\n{\n};\n\nclass CbUndoPathBackwards2 : public CbMoveBaseClientBehaviorBase, public smacc::ISmaccUpdatable\n{\npublic:\n  CbUndoPathBackwards2();\n  virtual void onEntry() override;\n\n  virtual void onExit() override;\n\n  virtual void update() override;\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    CbMoveBaseClientBehaviorBase::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n\n    postVirtualLinePassed_ = [=] { this->postEvent<EvGoalVirtualLinePassed<TSourceObject, TOrthogonal>>(); };\n  }\n\nprivate:\n  void publishMarkers();\n  float evalPlaneSide(const geometry_msgs::Pose& pose);\n\n  ClMoveBaseZ::Goal goal_;\n  odom_tracker::OdomTracker* odomTracker_;\n\n  tf::TransformListener listener;\n  cl_move_base_z::Pose* robotPose_;\n  std::atomic<bool> goalLinePassed_;\n  float initial_plane_side_;\n  float triggerThreshold_;  // meters absolute\n  std::function<void()> postVirtualLinePassed_;\n};\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/client_behaviors.h",
    "content": "#pragma once\n#include <move_base_z_client_plugin/client_behaviors/cb_rotate.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_absolute_rotate.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards2.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_navigate_global_position.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_navigate_forward.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_navigate_backwards.h>\n#include <move_base_z_client_plugin/client_behaviors/cb_navigate_next_waypoint.h>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/costmap_switch/cp_costmap_switch.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <functional>\n#include <array>\n#include <ros/ros.h>\n\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <smacc/component.h>\n\n#include <dynamic_reconfigure/DoubleParameter.h>\n#include <dynamic_reconfigure/Reconfigure.h>\n#include <dynamic_reconfigure/Config.h>\n\n\nnamespace cl_move_base_z\n{\nclass CostmapProxy;\n\nclass CostmapSwitch : public smacc::ISmaccComponent\n{\npublic:\n    enum class StandardLayers\n    {\n        GLOBAL_OBSTACLES_LAYER = 0,\n        LOCAL_OBSTACLES_LAYER = 1,\n        GLOBAL_INFLATED_LAYER = 2,\n        LOCAL_INFLATED_LAYER = 3\n    };\n\n    static std::array<std::string, 4> layerNames;\n\n    CostmapSwitch();\n\n    virtual void onInitialize() override;\n\n    static std::string getStandardCostmapName(StandardLayers layertype);\n\n    bool exists(std::string layerName);\n\n    void enable(std::string layerName);\n\n    void enable(StandardLayers layerType);\n\n    void disable(std::string layerName);\n\n    void disable(StandardLayers layerType);\n\n    void registerProxyFromDynamicReconfigureServer(std::string costmapName, std::string enablePropertyName = \"enabled\");\n\nprivate:\n    std::map<std::string, std::shared_ptr<CostmapProxy>> costmapProxies;\n    cl_move_base_z::ClMoveBaseZ *moveBaseClient_;\n};\n//-------------------------------------------------------------------------\nclass CostmapProxy\n{\npublic:\n    CostmapProxy(std::string costmap_name, std::string enablePropertyName);\n\n    void setCostmapEnabled(bool value);\n\nprivate:\n    std::string costmapName_;\n    dynamic_reconfigure::Config enableReq;\n    dynamic_reconfigure::Config disableReq;\n\n    void dynreconfCallback(const dynamic_reconfigure::Config::ConstPtr &configuration_update);\n\n    ros::Subscriber dynrecofSub_;\n};\n}\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/odom_tracker/odom_tracker.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/common.h>\n#include <smacc/component.h>\n\n#include <move_base_msgs/MoveBaseAction.h>\n\n#include <ros/ros.h>\n#include <vector>\n#include <nav_msgs/Odometry.h>\n#include <nav_msgs/Path.h>\n#include <tf/transform_datatypes.h>\n#include <realtime_tools/realtime_publisher.h>\n#include <mutex>\n#include <memory>\n#include <geometry_msgs/Point.h>\n#include <std_msgs/Header.h>\n\n#include <dynamic_reconfigure/server.h>\n#include <move_base_z_client_plugin/OdomTrackerConfig.h>\n\nnamespace cl_move_base_z\n{\nnamespace odom_tracker\n{\n\nenum class WorkingMode : uint8_t\n{\n    RECORD_PATH = 0,\n    CLEAR_PATH = 1,\n    IDLE = 2\n};\n\nstruct StackedPathEntry\n{\n    nav_msgs::Path path;\n    std::string pathTagName;\n};\n\n/// This class track the required distance of the cord based on the external localization system\nclass OdomTracker : public smacc::ISmaccComponent\n{\npublic:\n    // by default, the component start in record_path mode and publishing the\n    // current path\n    OdomTracker(std::string odomtopicName = \"/odom\", std::string odomFrame = \"odom\");\n\n    // threadsafe\n    /// odom callback: Updates the path - this must be called periodically for each odometry message.\n    // The odom parameters is the main input of this tracker\n    virtual void processOdometryMessage(const nav_msgs::Odometry &odom);\n\n    // ------ CONTROL COMMANDS ---------------------\n    // threadsafe\n    void setWorkingMode(WorkingMode workingMode);\n\n    // threadsafe\n    void setPublishMessages(bool value);\n\n    // threadsafe\n    void pushPath(std::string newPathTagName=\"\");\n\n    // threadsafe\n    void popPath(int pathCount = 1, bool keepPreviousPath = false);\n\n    // threadsafe\n    void clearPath();\n\n    // threadsafe\n    void setStartPoint(const geometry_msgs::PoseStamped &pose);\n\n    // threadsafe\n    void setStartPoint(const geometry_msgs::Pose &pose);\n\n    // threadsafe\n    nav_msgs::Path getPath();\n\n    void logStateString();\n\n    inline const std::vector<StackedPathEntry> getStackedPaths() const\n    {\n        return this->pathStack_;\n    }\n\nprotected:\n    dynamic_reconfigure::Server<move_base_z_client_plugin::OdomTrackerConfig> paramServer_;\n    dynamic_reconfigure::Server<move_base_z_client_plugin::OdomTrackerConfig>::CallbackType f;\n\n    void reconfigCB(move_base_z_client_plugin::OdomTrackerConfig &config, uint32_t level);\n\n    virtual void rtPublishPaths(ros::Time timestamp);\n\n\n    // this is called when a new odom message is received in record path mode\n    virtual bool updateRecordPath(const nav_msgs::Odometry &odom);\n\n    // this is called when a new odom message is received in clear path mode\n    virtual bool updateClearPath(const nav_msgs::Odometry &odom);\n\n    void updateAggregatedStackPath();\n\n    // -------------- OUTPUTS ---------------------\n    std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Path>> robotBasePathPub_;\n    std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Path>> robotBasePathStackedPub_;\n\n    // --------------- INPUTS ------------------------\n    // optional, this class can be used directly calling the odomProcessing method\n    // without any subscriber\n    ros::Subscriber odomSub_;\n\n    // -------------- PARAMETERS ----------------------\n    /// How much distance there is between two points of the path\n    double recordPointDistanceThreshold_;\n\n    /// Meters\n    double recordAngularDistanceThreshold_;\n\n    /// rads\n    double clearPointDistanceThreshold_;\n\n    /// rads\n    double clearAngularDistanceThreshold_;\n\n    std::string odomFrame_;\n\n    // --------------- STATE ---------------\n    // default true\n    bool publishMessages;\n\n    /// Processed path for the mouth of the reel\n    nav_msgs::Path baseTrajectory_;\n\n    WorkingMode workingMode_;\n\n    std::vector<StackedPathEntry> pathStack_;\n\n    nav_msgs::Path aggregatedStackPathMsg_;\n\n    // subscribes to topic on init if true\n    bool subscribeToOdometryTopic_;\n\n    std::string currentPathTagName_=\"Initial State\";\n\n    std::mutex m_mutex_;\n\n};\n\n/**\n******************************************************************************************************************\n* p2pDistance()\n******************************************************************************************************************\n*/\ninline double p2pDistance(const geometry_msgs::Point &p1, const geometry_msgs::Point &p2)\n{\n    double dx = (p1.x - p2.x);\n    double dy = (p1.y - p2.y);\n    double dz = (p2.z - p2.z);\n    double dist = sqrt(dx * dx + dy * dy + dz * dz);\n    return dist;\n}\n} // namespace odom_tracker\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/planner_switcher/planner_switcher.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/client_bases/smacc_action_client.h>\n#include <smacc/component.h>\n\n#include <dynamic_reconfigure/Config.h>\n#include <dynamic_reconfigure/DoubleParameter.h>\n#include <dynamic_reconfigure/Reconfigure.h>\n#include <ros/ros.h>\n#include <functional>\n\nnamespace cl_move_base_z\n{\nclass PlannerSwitcher : public smacc::ISmaccComponent\n{\npublic:\n  PlannerSwitcher();\n  void setBackwardPlanner();\n  void setUndoPathBackwardsPlannerConfiguration();\n  void setUndoPathPureSpinningPlannerConfiguration();\n\n  void setForwardPlanner();\n  void setPureSpinningPlanner();\n\n  virtual void onInitialize() override;\n\n  // sets ROS defaults local and global planners\n  void setDefaultPlanners();\n\nprivate:\n  std::string desired_global_planner_;\n  std::string desired_local_planner_;\n  ros::Subscriber dynrecofSub_;\n  bool set_planners_mode_flag;\n\n  void updatePlanners(bool subscribecallback = true);\n  void dynreconfCallback(const dynamic_reconfigure::Config::ConstPtr& configuration_update);\n};\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/pose/cp_pose.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/component.h>\n#include <smacc/smacc_updatable.h>\n\n#include <geometry_msgs/Pose.h>\n#include <tf/transform_listener.h>\n#include <tf/transform_datatypes.h>\n#include <mutex>\n\nnamespace cl_move_base_z\n{\nclass Pose : public smacc::ISmaccComponent, public smacc::ISmaccUpdatable\n{\npublic:\n    Pose(std::string poseFrameName = \"base_link\", std::string referenceFrame = \"odom\");\n\n    virtual void update() override;\n\n    void waitTransformUpdate(ros::Rate r = ros::Rate(20));\n\n    inline geometry_msgs::Pose toPoseMsg()\n    {\n        std::lock_guard<std::mutex> guard(m_mutex_);\n        return this->pose_.pose;\n    }\n\n    inline geometry_msgs::PoseStamped toPoseStampedMsg()\n    {\n        std::lock_guard<std::mutex> guard(m_mutex_);\n        return this->pose_;\n    }\n\n    inline const std::string &getReferenceFrame() const\n    {\n        return referenceFrame_;\n    }\n\n    inline const std::string &getFrameId() const\n    {\n        return poseFrameName_;\n    }\n\n    bool isInitialized;\n\nprivate:\n    geometry_msgs::PoseStamped pose_;\n\n    static std::shared_ptr<tf::TransformListener> tfListener_;\n    static std::mutex listenerMutex_;\n\n    std::string poseFrameName_;\n    std::string referenceFrame_;\n\n    std::mutex m_mutex_;\n};\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/waypoints_navigator/waypoints_event_dispatcher.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/smacc.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\nnamespace cl_move_base_z\n{\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint0 : sc::event<EvWaypoint0<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint1 : sc::event<EvWaypoint1<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint2 : sc::event<EvWaypoint2<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint3 : sc::event<EvWaypoint3<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint4 : sc::event<EvWaypoint4<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint5 : sc::event<EvWaypoint5<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint6 : sc::event<EvWaypoint6<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint7 : sc::event<EvWaypoint7<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint8 : sc::event<EvWaypoint8<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint9 : sc::event<EvWaypoint9<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint10 : sc::event<EvWaypoint10<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint11 : sc::event<EvWaypoint11<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint12 : sc::event<EvWaypoint12<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint13 : sc::event<EvWaypoint13<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint14 : sc::event<EvWaypoint14<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint15 : sc::event<EvWaypoint15<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint16 : sc::event<EvWaypoint16<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint17 : sc::event<EvWaypoint17<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint18 : sc::event<EvWaypoint18<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint19 : sc::event<EvWaypoint19<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint20 : sc::event<EvWaypoint20<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint21 : sc::event<EvWaypoint21<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint22 : sc::event<EvWaypoint22<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint23 : sc::event<EvWaypoint23<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint24 : sc::event<EvWaypoint24<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint25 : sc::event<EvWaypoint25<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint26 : sc::event<EvWaypoint26<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint27 : sc::event<EvWaypoint27<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint28 : sc::event<EvWaypoint28<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint29 : sc::event<EvWaypoint29<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint30 : sc::event<EvWaypoint30<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint31 : sc::event<EvWaypoint31<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint32 : sc::event<EvWaypoint32<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint33 : sc::event<EvWaypoint33<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint34 : sc::event<EvWaypoint34<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint35 : sc::event<EvWaypoint35<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint36 : sc::event<EvWaypoint36<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint37 : sc::event<EvWaypoint37<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint38 : sc::event<EvWaypoint38<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint39 : sc::event<EvWaypoint39<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint40 : sc::event<EvWaypoint40<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint41 : sc::event<EvWaypoint41<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint42 : sc::event<EvWaypoint42<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint43 : sc::event<EvWaypoint43<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint44 : sc::event<EvWaypoint44<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint45 : sc::event<EvWaypoint45<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint46 : sc::event<EvWaypoint46<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint47 : sc::event<EvWaypoint47<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint48 : sc::event<EvWaypoint48<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint49 : sc::event<EvWaypoint49<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint50 : sc::event<EvWaypoint50<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint51 : sc::event<EvWaypoint51<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint52 : sc::event<EvWaypoint52<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint53 : sc::event<EvWaypoint53<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint54 : sc::event<EvWaypoint54<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint55 : sc::event<EvWaypoint55<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint56 : sc::event<EvWaypoint56<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint57 : sc::event<EvWaypoint57<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint58 : sc::event<EvWaypoint58<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint59 : sc::event<EvWaypoint59<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint60 : sc::event<EvWaypoint60<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint61 : sc::event<EvWaypoint61<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint62 : sc::event<EvWaypoint62<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint63 : sc::event<EvWaypoint63<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint64 : sc::event<EvWaypoint64<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint65 : sc::event<EvWaypoint65<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint66 : sc::event<EvWaypoint66<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint67 : sc::event<EvWaypoint67<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint68 : sc::event<EvWaypoint68<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint69 : sc::event<EvWaypoint69<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint70 : sc::event<EvWaypoint70<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint71 : sc::event<EvWaypoint71<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint72 : sc::event<EvWaypoint72<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint73 : sc::event<EvWaypoint73<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint74 : sc::event<EvWaypoint74<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint75 : sc::event<EvWaypoint75<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint76 : sc::event<EvWaypoint76<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint77 : sc::event<EvWaypoint77<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint78 : sc::event<EvWaypoint78<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint79 : sc::event<EvWaypoint79<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint80 : sc::event<EvWaypoint80<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint81 : sc::event<EvWaypoint81<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint82 : sc::event<EvWaypoint82<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint83 : sc::event<EvWaypoint83<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint84 : sc::event<EvWaypoint84<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint85 : sc::event<EvWaypoint85<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint86 : sc::event<EvWaypoint86<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint87 : sc::event<EvWaypoint87<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint88 : sc::event<EvWaypoint88<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint89 : sc::event<EvWaypoint89<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint90 : sc::event<EvWaypoint90<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint91 : sc::event<EvWaypoint91<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint92 : sc::event<EvWaypoint92<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint93 : sc::event<EvWaypoint93<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint94 : sc::event<EvWaypoint94<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint95 : sc::event<EvWaypoint95<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint96 : sc::event<EvWaypoint96<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint97 : sc::event<EvWaypoint97<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint98 : sc::event<EvWaypoint98<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint99 : sc::event<EvWaypoint99<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint100 : sc::event<EvWaypoint100<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint101 : sc::event<EvWaypoint101<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint102 : sc::event<EvWaypoint102<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint103 : sc::event<EvWaypoint103<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint104 : sc::event<EvWaypoint104<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint105 : sc::event<EvWaypoint105<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint106 : sc::event<EvWaypoint106<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint107 : sc::event<EvWaypoint107<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint108 : sc::event<EvWaypoint108<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint109 : sc::event<EvWaypoint109<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint110 : sc::event<EvWaypoint110<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint111 : sc::event<EvWaypoint111<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint112 : sc::event<EvWaypoint112<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint113 : sc::event<EvWaypoint113<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint114 : sc::event<EvWaypoint114<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint115 : sc::event<EvWaypoint115<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint116 : sc::event<EvWaypoint116<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint117 : sc::event<EvWaypoint117<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint118 : sc::event<EvWaypoint118<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint119 : sc::event<EvWaypoint119<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint120 : sc::event<EvWaypoint120<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint121 : sc::event<EvWaypoint121<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint122 : sc::event<EvWaypoint122<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint123 : sc::event<EvWaypoint123<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint124 : sc::event<EvWaypoint124<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint125 : sc::event<EvWaypoint125<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint126 : sc::event<EvWaypoint126<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint127 : sc::event<EvWaypoint127<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint128 : sc::event<EvWaypoint128<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint129 : sc::event<EvWaypoint129<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint130 : sc::event<EvWaypoint130<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint131 : sc::event<EvWaypoint131<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint132 : sc::event<EvWaypoint132<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint133 : sc::event<EvWaypoint133<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint134 : sc::event<EvWaypoint134<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint135 : sc::event<EvWaypoint135<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint136 : sc::event<EvWaypoint136<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint137 : sc::event<EvWaypoint137<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint138 : sc::event<EvWaypoint138<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint139 : sc::event<EvWaypoint139<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint140 : sc::event<EvWaypoint140<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint141 : sc::event<EvWaypoint141<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint142 : sc::event<EvWaypoint142<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint143 : sc::event<EvWaypoint143<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint144 : sc::event<EvWaypoint144<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint145 : sc::event<EvWaypoint145<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint146 : sc::event<EvWaypoint146<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint147 : sc::event<EvWaypoint147<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint148 : sc::event<EvWaypoint148<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint149 : sc::event<EvWaypoint149<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint150 : sc::event<EvWaypoint150<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint151 : sc::event<EvWaypoint151<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint152 : sc::event<EvWaypoint152<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint153 : sc::event<EvWaypoint153<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint154 : sc::event<EvWaypoint154<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint155 : sc::event<EvWaypoint155<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint156 : sc::event<EvWaypoint156<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint157 : sc::event<EvWaypoint157<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint158 : sc::event<EvWaypoint158<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint159 : sc::event<EvWaypoint159<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint160 : sc::event<EvWaypoint160<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint161 : sc::event<EvWaypoint161<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint162 : sc::event<EvWaypoint162<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint163 : sc::event<EvWaypoint163<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint164 : sc::event<EvWaypoint164<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint165 : sc::event<EvWaypoint165<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint166 : sc::event<EvWaypoint166<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint167 : sc::event<EvWaypoint167<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint168 : sc::event<EvWaypoint168<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint169 : sc::event<EvWaypoint169<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint170 : sc::event<EvWaypoint170<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint171 : sc::event<EvWaypoint171<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint172 : sc::event<EvWaypoint172<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint173 : sc::event<EvWaypoint173<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint174 : sc::event<EvWaypoint174<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint175 : sc::event<EvWaypoint175<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint176 : sc::event<EvWaypoint176<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint177 : sc::event<EvWaypoint177<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint178 : sc::event<EvWaypoint178<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint179 : sc::event<EvWaypoint179<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint180 : sc::event<EvWaypoint180<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint181 : sc::event<EvWaypoint181<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint182 : sc::event<EvWaypoint182<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint183 : sc::event<EvWaypoint183<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint184 : sc::event<EvWaypoint184<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint185 : sc::event<EvWaypoint185<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint186 : sc::event<EvWaypoint186<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint187 : sc::event<EvWaypoint187<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint188 : sc::event<EvWaypoint188<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint189 : sc::event<EvWaypoint189<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint190 : sc::event<EvWaypoint190<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint191 : sc::event<EvWaypoint191<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint192 : sc::event<EvWaypoint192<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint193 : sc::event<EvWaypoint193<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint194 : sc::event<EvWaypoint194<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint195 : sc::event<EvWaypoint195<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint196 : sc::event<EvWaypoint196<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint197 : sc::event<EvWaypoint197<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint198 : sc::event<EvWaypoint198<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint199 : sc::event<EvWaypoint199<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint200 : sc::event<EvWaypoint200<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint201 : sc::event<EvWaypoint201<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint202 : sc::event<EvWaypoint202<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint203 : sc::event<EvWaypoint203<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint204 : sc::event<EvWaypoint204<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint205 : sc::event<EvWaypoint205<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint206 : sc::event<EvWaypoint206<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint207 : sc::event<EvWaypoint207<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint208 : sc::event<EvWaypoint208<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint209 : sc::event<EvWaypoint209<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint210 : sc::event<EvWaypoint210<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint211 : sc::event<EvWaypoint211<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint212 : sc::event<EvWaypoint212<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint213 : sc::event<EvWaypoint213<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint214 : sc::event<EvWaypoint214<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint215 : sc::event<EvWaypoint215<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint216 : sc::event<EvWaypoint216<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint217 : sc::event<EvWaypoint217<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint218 : sc::event<EvWaypoint218<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint219 : sc::event<EvWaypoint219<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint220 : sc::event<EvWaypoint220<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint221 : sc::event<EvWaypoint221<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint222 : sc::event<EvWaypoint222<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint223 : sc::event<EvWaypoint223<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint224 : sc::event<EvWaypoint224<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint225 : sc::event<EvWaypoint225<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint226 : sc::event<EvWaypoint226<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint227 : sc::event<EvWaypoint227<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint228 : sc::event<EvWaypoint228<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint229 : sc::event<EvWaypoint229<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint230 : sc::event<EvWaypoint230<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint231 : sc::event<EvWaypoint231<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint232 : sc::event<EvWaypoint232<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint233 : sc::event<EvWaypoint233<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint234 : sc::event<EvWaypoint234<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint235 : sc::event<EvWaypoint235<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint236 : sc::event<EvWaypoint236<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint237 : sc::event<EvWaypoint237<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint238 : sc::event<EvWaypoint238<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint239 : sc::event<EvWaypoint239<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint240 : sc::event<EvWaypoint240<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint241 : sc::event<EvWaypoint241<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint242 : sc::event<EvWaypoint242<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint243 : sc::event<EvWaypoint243<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint244 : sc::event<EvWaypoint244<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint245 : sc::event<EvWaypoint245<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint246 : sc::event<EvWaypoint246<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint247 : sc::event<EvWaypoint247<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint248 : sc::event<EvWaypoint248<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint249 : sc::event<EvWaypoint249<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint250 : sc::event<EvWaypoint250<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint251 : sc::event<EvWaypoint251<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint252 : sc::event<EvWaypoint252<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint253 : sc::event<EvWaypoint253<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint254 : sc::event<EvWaypoint254<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint255 : sc::event<EvWaypoint255<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvWaypoint256 : sc::event<EvWaypoint256<TSource, TOrthogonal>>\n{\n    int waypointIndex;\n};\n\nclass ClMoveBaseZ;\n\n#define WAYPOINTS_EVENTCOUNT 257\n\nclass WaypointEventDispatcher\n{\n    std::function<void()> postWaypointFn[WAYPOINTS_EVENTCOUNT];\n\npublic:\n    template <typename TDerived, typename TOrthogonal>\n    void initialize(ClMoveBaseZ *client);\n\n    void postWaypointEvent(int index);\n};\n\ntemplate <typename TEv>\nvoid configurePostEvWaypoint(std::function<void()> *fntarget, ClMoveBaseZ *client, int index)\n{\n    fntarget[index] = [=]() {\n        client->template postEvent<TEv>();\n    };\n}\n\ntemplate <typename TDerived, typename TOrthogonal>\nvoid WaypointEventDispatcher::initialize(ClMoveBaseZ *client)\n{\n    configurePostEvWaypoint<EvWaypoint0<TDerived, TOrthogonal>>(postWaypointFn, client, 0);\n    configurePostEvWaypoint<EvWaypoint1<TDerived, TOrthogonal>>(postWaypointFn, client, 1);\n    configurePostEvWaypoint<EvWaypoint2<TDerived, TOrthogonal>>(postWaypointFn, client, 2);\n    configurePostEvWaypoint<EvWaypoint3<TDerived, TOrthogonal>>(postWaypointFn, client, 3);\n    configurePostEvWaypoint<EvWaypoint4<TDerived, TOrthogonal>>(postWaypointFn, client, 4);\n    configurePostEvWaypoint<EvWaypoint5<TDerived, TOrthogonal>>(postWaypointFn, client, 5);\n    configurePostEvWaypoint<EvWaypoint6<TDerived, TOrthogonal>>(postWaypointFn, client, 6);\n    configurePostEvWaypoint<EvWaypoint7<TDerived, TOrthogonal>>(postWaypointFn, client, 7);\n    configurePostEvWaypoint<EvWaypoint8<TDerived, TOrthogonal>>(postWaypointFn, client, 8);\n    configurePostEvWaypoint<EvWaypoint9<TDerived, TOrthogonal>>(postWaypointFn, client, 9);\n    configurePostEvWaypoint<EvWaypoint10<TDerived, TOrthogonal>>(postWaypointFn, client, 10);\n    configurePostEvWaypoint<EvWaypoint11<TDerived, TOrthogonal>>(postWaypointFn, client, 11);\n    configurePostEvWaypoint<EvWaypoint12<TDerived, TOrthogonal>>(postWaypointFn, client, 12);\n    configurePostEvWaypoint<EvWaypoint13<TDerived, TOrthogonal>>(postWaypointFn, client, 13);\n    configurePostEvWaypoint<EvWaypoint14<TDerived, TOrthogonal>>(postWaypointFn, client, 14);\n    configurePostEvWaypoint<EvWaypoint15<TDerived, TOrthogonal>>(postWaypointFn, client, 15);\n    configurePostEvWaypoint<EvWaypoint16<TDerived, TOrthogonal>>(postWaypointFn, client, 16);\n    configurePostEvWaypoint<EvWaypoint17<TDerived, TOrthogonal>>(postWaypointFn, client, 17);\n    configurePostEvWaypoint<EvWaypoint18<TDerived, TOrthogonal>>(postWaypointFn, client, 18);\n    configurePostEvWaypoint<EvWaypoint19<TDerived, TOrthogonal>>(postWaypointFn, client, 19);\n    configurePostEvWaypoint<EvWaypoint20<TDerived, TOrthogonal>>(postWaypointFn, client, 20);\n    configurePostEvWaypoint<EvWaypoint21<TDerived, TOrthogonal>>(postWaypointFn, client, 21);\n    configurePostEvWaypoint<EvWaypoint22<TDerived, TOrthogonal>>(postWaypointFn, client, 22);\n    configurePostEvWaypoint<EvWaypoint23<TDerived, TOrthogonal>>(postWaypointFn, client, 23);\n    configurePostEvWaypoint<EvWaypoint24<TDerived, TOrthogonal>>(postWaypointFn, client, 24);\n    configurePostEvWaypoint<EvWaypoint25<TDerived, TOrthogonal>>(postWaypointFn, client, 25);\n    configurePostEvWaypoint<EvWaypoint26<TDerived, TOrthogonal>>(postWaypointFn, client, 26);\n    configurePostEvWaypoint<EvWaypoint27<TDerived, TOrthogonal>>(postWaypointFn, client, 27);\n    configurePostEvWaypoint<EvWaypoint28<TDerived, TOrthogonal>>(postWaypointFn, client, 28);\n    configurePostEvWaypoint<EvWaypoint29<TDerived, TOrthogonal>>(postWaypointFn, client, 29);\n    configurePostEvWaypoint<EvWaypoint30<TDerived, TOrthogonal>>(postWaypointFn, client, 30);\n    configurePostEvWaypoint<EvWaypoint31<TDerived, TOrthogonal>>(postWaypointFn, client, 31);\n    configurePostEvWaypoint<EvWaypoint32<TDerived, TOrthogonal>>(postWaypointFn, client, 32);\n    configurePostEvWaypoint<EvWaypoint33<TDerived, TOrthogonal>>(postWaypointFn, client, 33);\n    configurePostEvWaypoint<EvWaypoint34<TDerived, TOrthogonal>>(postWaypointFn, client, 34);\n    configurePostEvWaypoint<EvWaypoint35<TDerived, TOrthogonal>>(postWaypointFn, client, 35);\n    configurePostEvWaypoint<EvWaypoint36<TDerived, TOrthogonal>>(postWaypointFn, client, 36);\n    configurePostEvWaypoint<EvWaypoint37<TDerived, TOrthogonal>>(postWaypointFn, client, 37);\n    configurePostEvWaypoint<EvWaypoint38<TDerived, TOrthogonal>>(postWaypointFn, client, 38);\n    configurePostEvWaypoint<EvWaypoint39<TDerived, TOrthogonal>>(postWaypointFn, client, 39);\n    configurePostEvWaypoint<EvWaypoint40<TDerived, TOrthogonal>>(postWaypointFn, client, 40);\n    configurePostEvWaypoint<EvWaypoint41<TDerived, TOrthogonal>>(postWaypointFn, client, 41);\n    configurePostEvWaypoint<EvWaypoint42<TDerived, TOrthogonal>>(postWaypointFn, client, 42);\n    configurePostEvWaypoint<EvWaypoint43<TDerived, TOrthogonal>>(postWaypointFn, client, 43);\n    configurePostEvWaypoint<EvWaypoint44<TDerived, TOrthogonal>>(postWaypointFn, client, 44);\n    configurePostEvWaypoint<EvWaypoint45<TDerived, TOrthogonal>>(postWaypointFn, client, 45);\n    configurePostEvWaypoint<EvWaypoint46<TDerived, TOrthogonal>>(postWaypointFn, client, 46);\n    configurePostEvWaypoint<EvWaypoint47<TDerived, TOrthogonal>>(postWaypointFn, client, 47);\n    configurePostEvWaypoint<EvWaypoint48<TDerived, TOrthogonal>>(postWaypointFn, client, 48);\n    configurePostEvWaypoint<EvWaypoint49<TDerived, TOrthogonal>>(postWaypointFn, client, 49);\n    configurePostEvWaypoint<EvWaypoint50<TDerived, TOrthogonal>>(postWaypointFn, client, 50);\n    configurePostEvWaypoint<EvWaypoint51<TDerived, TOrthogonal>>(postWaypointFn, client, 51);\n    configurePostEvWaypoint<EvWaypoint52<TDerived, TOrthogonal>>(postWaypointFn, client, 52);\n    configurePostEvWaypoint<EvWaypoint53<TDerived, TOrthogonal>>(postWaypointFn, client, 53);\n    configurePostEvWaypoint<EvWaypoint54<TDerived, TOrthogonal>>(postWaypointFn, client, 54);\n    configurePostEvWaypoint<EvWaypoint55<TDerived, TOrthogonal>>(postWaypointFn, client, 55);\n    configurePostEvWaypoint<EvWaypoint56<TDerived, TOrthogonal>>(postWaypointFn, client, 56);\n    configurePostEvWaypoint<EvWaypoint57<TDerived, TOrthogonal>>(postWaypointFn, client, 57);\n    configurePostEvWaypoint<EvWaypoint58<TDerived, TOrthogonal>>(postWaypointFn, client, 58);\n    configurePostEvWaypoint<EvWaypoint59<TDerived, TOrthogonal>>(postWaypointFn, client, 59);\n    configurePostEvWaypoint<EvWaypoint60<TDerived, TOrthogonal>>(postWaypointFn, client, 60);\n    configurePostEvWaypoint<EvWaypoint61<TDerived, TOrthogonal>>(postWaypointFn, client, 61);\n    configurePostEvWaypoint<EvWaypoint62<TDerived, TOrthogonal>>(postWaypointFn, client, 62);\n    configurePostEvWaypoint<EvWaypoint63<TDerived, TOrthogonal>>(postWaypointFn, client, 63);\n    configurePostEvWaypoint<EvWaypoint64<TDerived, TOrthogonal>>(postWaypointFn, client, 64);\n    configurePostEvWaypoint<EvWaypoint65<TDerived, TOrthogonal>>(postWaypointFn, client, 65);\n    configurePostEvWaypoint<EvWaypoint66<TDerived, TOrthogonal>>(postWaypointFn, client, 66);\n    configurePostEvWaypoint<EvWaypoint67<TDerived, TOrthogonal>>(postWaypointFn, client, 67);\n    configurePostEvWaypoint<EvWaypoint68<TDerived, TOrthogonal>>(postWaypointFn, client, 68);\n    configurePostEvWaypoint<EvWaypoint69<TDerived, TOrthogonal>>(postWaypointFn, client, 69);\n    configurePostEvWaypoint<EvWaypoint70<TDerived, TOrthogonal>>(postWaypointFn, client, 70);\n    configurePostEvWaypoint<EvWaypoint71<TDerived, TOrthogonal>>(postWaypointFn, client, 71);\n    configurePostEvWaypoint<EvWaypoint72<TDerived, TOrthogonal>>(postWaypointFn, client, 72);\n    configurePostEvWaypoint<EvWaypoint73<TDerived, TOrthogonal>>(postWaypointFn, client, 73);\n    configurePostEvWaypoint<EvWaypoint74<TDerived, TOrthogonal>>(postWaypointFn, client, 74);\n    configurePostEvWaypoint<EvWaypoint75<TDerived, TOrthogonal>>(postWaypointFn, client, 75);\n    configurePostEvWaypoint<EvWaypoint76<TDerived, TOrthogonal>>(postWaypointFn, client, 76);\n    configurePostEvWaypoint<EvWaypoint77<TDerived, TOrthogonal>>(postWaypointFn, client, 77);\n    configurePostEvWaypoint<EvWaypoint78<TDerived, TOrthogonal>>(postWaypointFn, client, 78);\n    configurePostEvWaypoint<EvWaypoint79<TDerived, TOrthogonal>>(postWaypointFn, client, 79);\n    configurePostEvWaypoint<EvWaypoint80<TDerived, TOrthogonal>>(postWaypointFn, client, 80);\n    configurePostEvWaypoint<EvWaypoint81<TDerived, TOrthogonal>>(postWaypointFn, client, 81);\n    configurePostEvWaypoint<EvWaypoint82<TDerived, TOrthogonal>>(postWaypointFn, client, 82);\n    configurePostEvWaypoint<EvWaypoint83<TDerived, TOrthogonal>>(postWaypointFn, client, 83);\n    configurePostEvWaypoint<EvWaypoint84<TDerived, TOrthogonal>>(postWaypointFn, client, 84);\n    configurePostEvWaypoint<EvWaypoint85<TDerived, TOrthogonal>>(postWaypointFn, client, 85);\n    configurePostEvWaypoint<EvWaypoint86<TDerived, TOrthogonal>>(postWaypointFn, client, 86);\n    configurePostEvWaypoint<EvWaypoint87<TDerived, TOrthogonal>>(postWaypointFn, client, 87);\n    configurePostEvWaypoint<EvWaypoint88<TDerived, TOrthogonal>>(postWaypointFn, client, 88);\n    configurePostEvWaypoint<EvWaypoint89<TDerived, TOrthogonal>>(postWaypointFn, client, 89);\n    configurePostEvWaypoint<EvWaypoint90<TDerived, TOrthogonal>>(postWaypointFn, client, 90);\n    configurePostEvWaypoint<EvWaypoint91<TDerived, TOrthogonal>>(postWaypointFn, client, 91);\n    configurePostEvWaypoint<EvWaypoint92<TDerived, TOrthogonal>>(postWaypointFn, client, 92);\n    configurePostEvWaypoint<EvWaypoint93<TDerived, TOrthogonal>>(postWaypointFn, client, 93);\n    configurePostEvWaypoint<EvWaypoint94<TDerived, TOrthogonal>>(postWaypointFn, client, 94);\n    configurePostEvWaypoint<EvWaypoint95<TDerived, TOrthogonal>>(postWaypointFn, client, 95);\n    configurePostEvWaypoint<EvWaypoint96<TDerived, TOrthogonal>>(postWaypointFn, client, 96);\n    configurePostEvWaypoint<EvWaypoint97<TDerived, TOrthogonal>>(postWaypointFn, client, 97);\n    configurePostEvWaypoint<EvWaypoint98<TDerived, TOrthogonal>>(postWaypointFn, client, 98);\n    configurePostEvWaypoint<EvWaypoint99<TDerived, TOrthogonal>>(postWaypointFn, client, 99);\n    configurePostEvWaypoint<EvWaypoint100<TDerived, TOrthogonal>>(postWaypointFn, client, 100);\n    configurePostEvWaypoint<EvWaypoint101<TDerived, TOrthogonal>>(postWaypointFn, client, 101);\n    configurePostEvWaypoint<EvWaypoint102<TDerived, TOrthogonal>>(postWaypointFn, client, 102);\n    configurePostEvWaypoint<EvWaypoint103<TDerived, TOrthogonal>>(postWaypointFn, client, 103);\n    configurePostEvWaypoint<EvWaypoint104<TDerived, TOrthogonal>>(postWaypointFn, client, 104);\n    configurePostEvWaypoint<EvWaypoint105<TDerived, TOrthogonal>>(postWaypointFn, client, 105);\n    configurePostEvWaypoint<EvWaypoint106<TDerived, TOrthogonal>>(postWaypointFn, client, 106);\n    configurePostEvWaypoint<EvWaypoint107<TDerived, TOrthogonal>>(postWaypointFn, client, 107);\n    configurePostEvWaypoint<EvWaypoint108<TDerived, TOrthogonal>>(postWaypointFn, client, 108);\n    configurePostEvWaypoint<EvWaypoint109<TDerived, TOrthogonal>>(postWaypointFn, client, 109);\n    configurePostEvWaypoint<EvWaypoint110<TDerived, TOrthogonal>>(postWaypointFn, client, 110);\n    configurePostEvWaypoint<EvWaypoint111<TDerived, TOrthogonal>>(postWaypointFn, client, 111);\n    configurePostEvWaypoint<EvWaypoint112<TDerived, TOrthogonal>>(postWaypointFn, client, 112);\n    configurePostEvWaypoint<EvWaypoint113<TDerived, TOrthogonal>>(postWaypointFn, client, 113);\n    configurePostEvWaypoint<EvWaypoint114<TDerived, TOrthogonal>>(postWaypointFn, client, 114);\n    configurePostEvWaypoint<EvWaypoint115<TDerived, TOrthogonal>>(postWaypointFn, client, 115);\n    configurePostEvWaypoint<EvWaypoint116<TDerived, TOrthogonal>>(postWaypointFn, client, 116);\n    configurePostEvWaypoint<EvWaypoint117<TDerived, TOrthogonal>>(postWaypointFn, client, 117);\n    configurePostEvWaypoint<EvWaypoint118<TDerived, TOrthogonal>>(postWaypointFn, client, 118);\n    configurePostEvWaypoint<EvWaypoint119<TDerived, TOrthogonal>>(postWaypointFn, client, 119);\n    configurePostEvWaypoint<EvWaypoint120<TDerived, TOrthogonal>>(postWaypointFn, client, 120);\n    configurePostEvWaypoint<EvWaypoint121<TDerived, TOrthogonal>>(postWaypointFn, client, 121);\n    configurePostEvWaypoint<EvWaypoint122<TDerived, TOrthogonal>>(postWaypointFn, client, 122);\n    configurePostEvWaypoint<EvWaypoint123<TDerived, TOrthogonal>>(postWaypointFn, client, 123);\n    configurePostEvWaypoint<EvWaypoint124<TDerived, TOrthogonal>>(postWaypointFn, client, 124);\n    configurePostEvWaypoint<EvWaypoint125<TDerived, TOrthogonal>>(postWaypointFn, client, 125);\n    configurePostEvWaypoint<EvWaypoint126<TDerived, TOrthogonal>>(postWaypointFn, client, 126);\n    configurePostEvWaypoint<EvWaypoint127<TDerived, TOrthogonal>>(postWaypointFn, client, 127);\n    configurePostEvWaypoint<EvWaypoint128<TDerived, TOrthogonal>>(postWaypointFn, client, 128);\n    configurePostEvWaypoint<EvWaypoint129<TDerived, TOrthogonal>>(postWaypointFn, client, 129);\n    configurePostEvWaypoint<EvWaypoint130<TDerived, TOrthogonal>>(postWaypointFn, client, 130);\n    configurePostEvWaypoint<EvWaypoint131<TDerived, TOrthogonal>>(postWaypointFn, client, 131);\n    configurePostEvWaypoint<EvWaypoint132<TDerived, TOrthogonal>>(postWaypointFn, client, 132);\n    configurePostEvWaypoint<EvWaypoint133<TDerived, TOrthogonal>>(postWaypointFn, client, 133);\n    configurePostEvWaypoint<EvWaypoint134<TDerived, TOrthogonal>>(postWaypointFn, client, 134);\n    configurePostEvWaypoint<EvWaypoint135<TDerived, TOrthogonal>>(postWaypointFn, client, 135);\n    configurePostEvWaypoint<EvWaypoint136<TDerived, TOrthogonal>>(postWaypointFn, client, 136);\n    configurePostEvWaypoint<EvWaypoint137<TDerived, TOrthogonal>>(postWaypointFn, client, 137);\n    configurePostEvWaypoint<EvWaypoint138<TDerived, TOrthogonal>>(postWaypointFn, client, 138);\n    configurePostEvWaypoint<EvWaypoint139<TDerived, TOrthogonal>>(postWaypointFn, client, 139);\n    configurePostEvWaypoint<EvWaypoint140<TDerived, TOrthogonal>>(postWaypointFn, client, 140);\n    configurePostEvWaypoint<EvWaypoint141<TDerived, TOrthogonal>>(postWaypointFn, client, 141);\n    configurePostEvWaypoint<EvWaypoint142<TDerived, TOrthogonal>>(postWaypointFn, client, 142);\n    configurePostEvWaypoint<EvWaypoint143<TDerived, TOrthogonal>>(postWaypointFn, client, 143);\n    configurePostEvWaypoint<EvWaypoint144<TDerived, TOrthogonal>>(postWaypointFn, client, 144);\n    configurePostEvWaypoint<EvWaypoint145<TDerived, TOrthogonal>>(postWaypointFn, client, 145);\n    configurePostEvWaypoint<EvWaypoint146<TDerived, TOrthogonal>>(postWaypointFn, client, 146);\n    configurePostEvWaypoint<EvWaypoint147<TDerived, TOrthogonal>>(postWaypointFn, client, 147);\n    configurePostEvWaypoint<EvWaypoint148<TDerived, TOrthogonal>>(postWaypointFn, client, 148);\n    configurePostEvWaypoint<EvWaypoint149<TDerived, TOrthogonal>>(postWaypointFn, client, 149);\n    configurePostEvWaypoint<EvWaypoint150<TDerived, TOrthogonal>>(postWaypointFn, client, 150);\n    configurePostEvWaypoint<EvWaypoint151<TDerived, TOrthogonal>>(postWaypointFn, client, 151);\n    configurePostEvWaypoint<EvWaypoint152<TDerived, TOrthogonal>>(postWaypointFn, client, 152);\n    configurePostEvWaypoint<EvWaypoint153<TDerived, TOrthogonal>>(postWaypointFn, client, 153);\n    configurePostEvWaypoint<EvWaypoint154<TDerived, TOrthogonal>>(postWaypointFn, client, 154);\n    configurePostEvWaypoint<EvWaypoint155<TDerived, TOrthogonal>>(postWaypointFn, client, 155);\n    configurePostEvWaypoint<EvWaypoint156<TDerived, TOrthogonal>>(postWaypointFn, client, 156);\n    configurePostEvWaypoint<EvWaypoint157<TDerived, TOrthogonal>>(postWaypointFn, client, 157);\n    configurePostEvWaypoint<EvWaypoint158<TDerived, TOrthogonal>>(postWaypointFn, client, 158);\n    configurePostEvWaypoint<EvWaypoint159<TDerived, TOrthogonal>>(postWaypointFn, client, 159);\n    configurePostEvWaypoint<EvWaypoint160<TDerived, TOrthogonal>>(postWaypointFn, client, 160);\n    configurePostEvWaypoint<EvWaypoint161<TDerived, TOrthogonal>>(postWaypointFn, client, 161);\n    configurePostEvWaypoint<EvWaypoint162<TDerived, TOrthogonal>>(postWaypointFn, client, 162);\n    configurePostEvWaypoint<EvWaypoint163<TDerived, TOrthogonal>>(postWaypointFn, client, 163);\n    configurePostEvWaypoint<EvWaypoint164<TDerived, TOrthogonal>>(postWaypointFn, client, 164);\n    configurePostEvWaypoint<EvWaypoint165<TDerived, TOrthogonal>>(postWaypointFn, client, 165);\n    configurePostEvWaypoint<EvWaypoint166<TDerived, TOrthogonal>>(postWaypointFn, client, 166);\n    configurePostEvWaypoint<EvWaypoint167<TDerived, TOrthogonal>>(postWaypointFn, client, 167);\n    configurePostEvWaypoint<EvWaypoint168<TDerived, TOrthogonal>>(postWaypointFn, client, 168);\n    configurePostEvWaypoint<EvWaypoint169<TDerived, TOrthogonal>>(postWaypointFn, client, 169);\n    configurePostEvWaypoint<EvWaypoint170<TDerived, TOrthogonal>>(postWaypointFn, client, 170);\n    configurePostEvWaypoint<EvWaypoint171<TDerived, TOrthogonal>>(postWaypointFn, client, 171);\n    configurePostEvWaypoint<EvWaypoint172<TDerived, TOrthogonal>>(postWaypointFn, client, 172);\n    configurePostEvWaypoint<EvWaypoint173<TDerived, TOrthogonal>>(postWaypointFn, client, 173);\n    configurePostEvWaypoint<EvWaypoint174<TDerived, TOrthogonal>>(postWaypointFn, client, 174);\n    configurePostEvWaypoint<EvWaypoint175<TDerived, TOrthogonal>>(postWaypointFn, client, 175);\n    configurePostEvWaypoint<EvWaypoint176<TDerived, TOrthogonal>>(postWaypointFn, client, 176);\n    configurePostEvWaypoint<EvWaypoint177<TDerived, TOrthogonal>>(postWaypointFn, client, 177);\n    configurePostEvWaypoint<EvWaypoint178<TDerived, TOrthogonal>>(postWaypointFn, client, 178);\n    configurePostEvWaypoint<EvWaypoint179<TDerived, TOrthogonal>>(postWaypointFn, client, 179);\n    configurePostEvWaypoint<EvWaypoint180<TDerived, TOrthogonal>>(postWaypointFn, client, 180);\n    configurePostEvWaypoint<EvWaypoint181<TDerived, TOrthogonal>>(postWaypointFn, client, 181);\n    configurePostEvWaypoint<EvWaypoint182<TDerived, TOrthogonal>>(postWaypointFn, client, 182);\n    configurePostEvWaypoint<EvWaypoint183<TDerived, TOrthogonal>>(postWaypointFn, client, 183);\n    configurePostEvWaypoint<EvWaypoint184<TDerived, TOrthogonal>>(postWaypointFn, client, 184);\n    configurePostEvWaypoint<EvWaypoint185<TDerived, TOrthogonal>>(postWaypointFn, client, 185);\n    configurePostEvWaypoint<EvWaypoint186<TDerived, TOrthogonal>>(postWaypointFn, client, 186);\n    configurePostEvWaypoint<EvWaypoint187<TDerived, TOrthogonal>>(postWaypointFn, client, 187);\n    configurePostEvWaypoint<EvWaypoint188<TDerived, TOrthogonal>>(postWaypointFn, client, 188);\n    configurePostEvWaypoint<EvWaypoint189<TDerived, TOrthogonal>>(postWaypointFn, client, 189);\n    configurePostEvWaypoint<EvWaypoint190<TDerived, TOrthogonal>>(postWaypointFn, client, 190);\n    configurePostEvWaypoint<EvWaypoint191<TDerived, TOrthogonal>>(postWaypointFn, client, 191);\n    configurePostEvWaypoint<EvWaypoint192<TDerived, TOrthogonal>>(postWaypointFn, client, 192);\n    configurePostEvWaypoint<EvWaypoint193<TDerived, TOrthogonal>>(postWaypointFn, client, 193);\n    configurePostEvWaypoint<EvWaypoint194<TDerived, TOrthogonal>>(postWaypointFn, client, 194);\n    configurePostEvWaypoint<EvWaypoint195<TDerived, TOrthogonal>>(postWaypointFn, client, 195);\n    configurePostEvWaypoint<EvWaypoint196<TDerived, TOrthogonal>>(postWaypointFn, client, 196);\n    configurePostEvWaypoint<EvWaypoint197<TDerived, TOrthogonal>>(postWaypointFn, client, 197);\n    configurePostEvWaypoint<EvWaypoint198<TDerived, TOrthogonal>>(postWaypointFn, client, 198);\n    configurePostEvWaypoint<EvWaypoint199<TDerived, TOrthogonal>>(postWaypointFn, client, 199);\n    configurePostEvWaypoint<EvWaypoint200<TDerived, TOrthogonal>>(postWaypointFn, client, 200);\n    configurePostEvWaypoint<EvWaypoint201<TDerived, TOrthogonal>>(postWaypointFn, client, 201);\n    configurePostEvWaypoint<EvWaypoint202<TDerived, TOrthogonal>>(postWaypointFn, client, 202);\n    configurePostEvWaypoint<EvWaypoint203<TDerived, TOrthogonal>>(postWaypointFn, client, 203);\n    configurePostEvWaypoint<EvWaypoint204<TDerived, TOrthogonal>>(postWaypointFn, client, 204);\n    configurePostEvWaypoint<EvWaypoint205<TDerived, TOrthogonal>>(postWaypointFn, client, 205);\n    configurePostEvWaypoint<EvWaypoint206<TDerived, TOrthogonal>>(postWaypointFn, client, 206);\n    configurePostEvWaypoint<EvWaypoint207<TDerived, TOrthogonal>>(postWaypointFn, client, 207);\n    configurePostEvWaypoint<EvWaypoint208<TDerived, TOrthogonal>>(postWaypointFn, client, 208);\n    configurePostEvWaypoint<EvWaypoint209<TDerived, TOrthogonal>>(postWaypointFn, client, 209);\n    configurePostEvWaypoint<EvWaypoint210<TDerived, TOrthogonal>>(postWaypointFn, client, 210);\n    configurePostEvWaypoint<EvWaypoint211<TDerived, TOrthogonal>>(postWaypointFn, client, 211);\n    configurePostEvWaypoint<EvWaypoint212<TDerived, TOrthogonal>>(postWaypointFn, client, 212);\n    configurePostEvWaypoint<EvWaypoint213<TDerived, TOrthogonal>>(postWaypointFn, client, 213);\n    configurePostEvWaypoint<EvWaypoint214<TDerived, TOrthogonal>>(postWaypointFn, client, 214);\n    configurePostEvWaypoint<EvWaypoint215<TDerived, TOrthogonal>>(postWaypointFn, client, 215);\n    configurePostEvWaypoint<EvWaypoint216<TDerived, TOrthogonal>>(postWaypointFn, client, 216);\n    configurePostEvWaypoint<EvWaypoint217<TDerived, TOrthogonal>>(postWaypointFn, client, 217);\n    configurePostEvWaypoint<EvWaypoint218<TDerived, TOrthogonal>>(postWaypointFn, client, 218);\n    configurePostEvWaypoint<EvWaypoint219<TDerived, TOrthogonal>>(postWaypointFn, client, 219);\n    configurePostEvWaypoint<EvWaypoint220<TDerived, TOrthogonal>>(postWaypointFn, client, 220);\n    configurePostEvWaypoint<EvWaypoint221<TDerived, TOrthogonal>>(postWaypointFn, client, 221);\n    configurePostEvWaypoint<EvWaypoint222<TDerived, TOrthogonal>>(postWaypointFn, client, 222);\n    configurePostEvWaypoint<EvWaypoint223<TDerived, TOrthogonal>>(postWaypointFn, client, 223);\n    configurePostEvWaypoint<EvWaypoint224<TDerived, TOrthogonal>>(postWaypointFn, client, 224);\n    configurePostEvWaypoint<EvWaypoint225<TDerived, TOrthogonal>>(postWaypointFn, client, 225);\n    configurePostEvWaypoint<EvWaypoint226<TDerived, TOrthogonal>>(postWaypointFn, client, 226);\n    configurePostEvWaypoint<EvWaypoint227<TDerived, TOrthogonal>>(postWaypointFn, client, 227);\n    configurePostEvWaypoint<EvWaypoint228<TDerived, TOrthogonal>>(postWaypointFn, client, 228);\n    configurePostEvWaypoint<EvWaypoint229<TDerived, TOrthogonal>>(postWaypointFn, client, 229);\n    configurePostEvWaypoint<EvWaypoint230<TDerived, TOrthogonal>>(postWaypointFn, client, 230);\n    configurePostEvWaypoint<EvWaypoint231<TDerived, TOrthogonal>>(postWaypointFn, client, 231);\n    configurePostEvWaypoint<EvWaypoint232<TDerived, TOrthogonal>>(postWaypointFn, client, 232);\n    configurePostEvWaypoint<EvWaypoint233<TDerived, TOrthogonal>>(postWaypointFn, client, 233);\n    configurePostEvWaypoint<EvWaypoint234<TDerived, TOrthogonal>>(postWaypointFn, client, 234);\n    configurePostEvWaypoint<EvWaypoint235<TDerived, TOrthogonal>>(postWaypointFn, client, 235);\n    configurePostEvWaypoint<EvWaypoint236<TDerived, TOrthogonal>>(postWaypointFn, client, 236);\n    configurePostEvWaypoint<EvWaypoint237<TDerived, TOrthogonal>>(postWaypointFn, client, 237);\n    configurePostEvWaypoint<EvWaypoint238<TDerived, TOrthogonal>>(postWaypointFn, client, 238);\n    configurePostEvWaypoint<EvWaypoint239<TDerived, TOrthogonal>>(postWaypointFn, client, 239);\n    configurePostEvWaypoint<EvWaypoint240<TDerived, TOrthogonal>>(postWaypointFn, client, 240);\n    configurePostEvWaypoint<EvWaypoint241<TDerived, TOrthogonal>>(postWaypointFn, client, 241);\n    configurePostEvWaypoint<EvWaypoint242<TDerived, TOrthogonal>>(postWaypointFn, client, 242);\n    configurePostEvWaypoint<EvWaypoint243<TDerived, TOrthogonal>>(postWaypointFn, client, 243);\n    configurePostEvWaypoint<EvWaypoint244<TDerived, TOrthogonal>>(postWaypointFn, client, 244);\n    configurePostEvWaypoint<EvWaypoint245<TDerived, TOrthogonal>>(postWaypointFn, client, 245);\n    configurePostEvWaypoint<EvWaypoint246<TDerived, TOrthogonal>>(postWaypointFn, client, 246);\n    configurePostEvWaypoint<EvWaypoint247<TDerived, TOrthogonal>>(postWaypointFn, client, 247);\n    configurePostEvWaypoint<EvWaypoint248<TDerived, TOrthogonal>>(postWaypointFn, client, 248);\n    configurePostEvWaypoint<EvWaypoint249<TDerived, TOrthogonal>>(postWaypointFn, client, 249);\n    configurePostEvWaypoint<EvWaypoint250<TDerived, TOrthogonal>>(postWaypointFn, client, 250);\n    configurePostEvWaypoint<EvWaypoint251<TDerived, TOrthogonal>>(postWaypointFn, client, 251);\n    configurePostEvWaypoint<EvWaypoint252<TDerived, TOrthogonal>>(postWaypointFn, client, 252);\n    configurePostEvWaypoint<EvWaypoint253<TDerived, TOrthogonal>>(postWaypointFn, client, 253);\n    configurePostEvWaypoint<EvWaypoint254<TDerived, TOrthogonal>>(postWaypointFn, client, 254);\n    configurePostEvWaypoint<EvWaypoint255<TDerived, TOrthogonal>>(postWaypointFn, client, 255);\n    configurePostEvWaypoint<EvWaypoint256<TDerived, TOrthogonal>>(postWaypointFn, client, 256);\n}\n\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h",
    "content": "\n/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/smacc.h>\n#include <geometry_msgs/Pose.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_event_dispatcher.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\nnamespace cl_move_base_z\n{\nclass ClMoveBaseZ;\n\nstruct Pose2D\n{\n  Pose2D(double x, double y, double yaw)\n  {\n    this->x_ = x;\n    this->y_ = y;\n    this->yaw_ = yaw;\n  }\n\n  double x_;\n  double y_;\n  double yaw_;\n};\n\nclass WaypointNavigator : public smacc::ISmaccComponent\n{\npublic:\n  WaypointEventDispatcher waypointsEventDispatcher;\n\n  ClMoveBaseZ *client_;\n\n  WaypointNavigator();\n\n  virtual void onInitialize() override;\n\n  void insertWaypoint(int index, geometry_msgs::Pose &newpose);\n\n  void removeWaypoint(int index);\n\n  void loadWayPointsFromFile(std::string filepath);\n\n  void setWaypoints(const std::vector<geometry_msgs::Pose> &waypoints);\n\n  void setWaypoints(const std::vector<Pose2D> &waypoints);\n\n  void sendNextGoal();\n\n  const std::vector<geometry_msgs::Pose> &getWaypoints() const;\n\n  long getCurrentWaypointIndex() const;\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);\n  }\n\n  int currentWaypoint_;\n\nprivate:\n  void onGoalReached(ClMoveBaseZ::ResultConstPtr &res);\n\n  std::vector<geometry_msgs::Pose> waypoints_;\n\n  boost::signals2::connection succeddedConnection_;\n};\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/include/move_base_z_client_plugin/move_base_z_client_plugin.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/smacc.h>\n#include <smacc/client_bases/smacc_action_client_base.h>\n\n#include <move_base_msgs/MoveBaseAction.h>\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n\nnamespace cl_move_base_z\n{\nclass WaypointNavigator;\n\nclass ClMoveBaseZ : public smacc::client_bases::SmaccActionClientBase<move_base_msgs::MoveBaseAction>\n{\n    typedef SmaccActionClientBase<move_base_msgs::MoveBaseAction> Base;\n\npublic:\n    typedef SmaccActionClientBase<move_base_msgs::MoveBaseAction>::ResultConstPtr ResultConstPtr;\n\n    ClMoveBaseZ(std::string moveBaseName=\"/move_base\");\n\n    virtual ~ClMoveBaseZ();\n\n    virtual void initialize() override;\n\n    virtual std::string getName() const override;\n};\n\n} // namespace smacc\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>move_base_z_client_plugin</name>\n\n    <version>1.4.16</version>\n  <description>The move_base_z_client_plugin package implements SMACC Action Client Plugin for the ROS Navigation State - move_base node.  Developed by Reel Robotics.</description>\n\n  <author email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</author>\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n  <license>MIT</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>pluginlib</depend>\n  <depend>smacc</depend>\n  <depend>tf</depend>\n  <depend>dynamic_reconfigure</depend>\n  <!-- <depend>yaml-cpp</depend> -->\n\n  <export>\n      <smacc plugin=\"${prefix}/smacc_plugin.xml\" />\n      <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_absolute_rotate.cpp",
    "content": "\n#include <move_base_z_client_plugin/client_behaviors/cb_absolute_rotate.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace cl_move_base_z\n{\nCbAbsoluteRotate::CbAbsoluteRotate()\n{\n}\n\nCbAbsoluteRotate::CbAbsoluteRotate(float absoluteGoalAngleDegree, float yaw_goal_tolerance)\n{\n  this->absoluteGoalAngleDegree = absoluteGoalAngleDegree;\n\n  if (yaw_goal_tolerance >= 0)\n  {\n    this->yawGoalTolerance = yaw_goal_tolerance;\n  }\n}\n\nvoid CbAbsoluteRotate::updateTemporalBehaviorParameters(bool undo)\n{\n  dynamic_reconfigure::ReconfigureRequest srv_req;\n  dynamic_reconfigure::ReconfigureResponse srv_resp;\n  dynamic_reconfigure::Config conf;\n\n  ros::NodeHandle nh;\n  std::string nodename = \"/move_base\";\n  std::string localPlannerName;\n  dynamic_reconfigure::DoubleParameter yaw_goal_tolerance;\n  yaw_goal_tolerance.name = \"yaw_goal_tolerance\";\n\n  dynamic_reconfigure::DoubleParameter max_vel_theta;\n  dynamic_reconfigure::DoubleParameter min_vel_theta;\n  bool isRosBasePlanner = !spinningPlanner || *spinningPlanner == SpiningPlanner::Default;\n  bool isPureSpinningPlanner = spinningPlanner && *spinningPlanner == SpiningPlanner::PureSpinning;\n\n  if (isPureSpinningPlanner)\n  {\n    localPlannerName = \"PureSpinningLocalPlanner\";\n    max_vel_theta.name = \"max_angular_z_speed\";\n    min_vel_theta.name = \"min_vel_theta\";\n  }\n  else if (isRosBasePlanner)\n  {\n    localPlannerName = \"TrajectoryPlannerROS\";\n    max_vel_theta.name = \"max_vel_theta\";\n    min_vel_theta.name = \"min_vel_theta\";\n  }\n\n  if (!undo)\n  {\n    if (yawGoalTolerance)\n    {\n      // save old yaw tolerance\n      nh.getParam(nodename + \"/\" + localPlannerName + \"/yaw_goal_tolerance\", oldYawTolerance);\n      yaw_goal_tolerance.value = *yawGoalTolerance;\n      conf.doubles.push_back(yaw_goal_tolerance);\n      ROS_INFO(\"[CbAbsoluteRotate] updating yaw tolerance local planner to: %lf, from previous value: %lf \",\n               *yawGoalTolerance, this->oldYawTolerance);\n    }\n\n    if (maxVelTheta)\n    {\n      if (isRosBasePlanner)\n      {\n        // save old yaw tolerance\n        // nh.getParam(nodename + \"/\"  + localPlannerName+\"/min_vel_theta\", oldMinVelTheta);\n        nh.getParam(nodename + \"/\" + localPlannerName + \"/max_vel_theta\", oldMaxVelTheta);\n      }\n      max_vel_theta.value = *maxVelTheta;\n      min_vel_theta.value = -*maxVelTheta;\n      conf.doubles.push_back(max_vel_theta);\n      conf.doubles.push_back(min_vel_theta);\n      ROS_INFO(\"[CbAbsoluteRotate] updating max vel theta local planner to: %lf, from previous value: %lf \",\n               *maxVelTheta, this->oldMaxVelTheta);\n      ROS_INFO(\"[CbAbsoluteRotate] updating min vel theta local planner to: %lf, from previous value: %lf \",\n               -*maxVelTheta, this->oldMinVelTheta);\n    }\n  }\n  else\n  {\n    if (yawGoalTolerance)\n    {\n      yaw_goal_tolerance.value = oldYawTolerance;\n      conf.doubles.push_back(yaw_goal_tolerance);\n      ROS_INFO(\"[CbAbsoluteRotate] restoring yaw tolerance local planner from: %lf, to previous value: %lf \",\n               *yawGoalTolerance, this->oldYawTolerance);\n    }\n\n    if (maxVelTheta)\n    {\n      if (isRosBasePlanner)\n      {\n        max_vel_theta.value = oldMaxVelTheta;\n        min_vel_theta.value = oldMinVelTheta;\n      }\n\n      conf.doubles.push_back(max_vel_theta);\n      conf.doubles.push_back(min_vel_theta);\n      ROS_INFO(\"[CbAbsoluteRotate] restoring max vel theta local planner from: %lf, to previous value: %lf \",\n               *maxVelTheta, this->oldMaxVelTheta);\n      ROS_INFO(\"[CbAbsoluteRotate] restoring min vel theta local planner from: %lf, to previous value: %lf \",\n               -(*maxVelTheta), this->oldMinVelTheta);\n    }\n  }\n\n  srv_req.config = conf;\n  bool res;\n  do\n  {\n    std::string servername = nodename + \"/\" + localPlannerName + \"/set_parameters\";\n    res = ros::service::call(servername, srv_req, srv_resp);\n    ROS_INFO_STREAM(\"[CbAbsoluteRotate] dynamic configure call [\" << servername << \"]: \" << res);\n    ros::spinOnce();\n    if (!res)\n    {\n      ros::Duration(0.1).sleep();\n      ROS_INFO(\"[CbAbsoluteRotate] Failed, retrtying call\");\n    }\n  } while (!res);\n}\n\nvoid CbAbsoluteRotate::onExit()\n{\n  if (spinningPlanner && *spinningPlanner == SpiningPlanner::PureSpinning)\n  {\n  }\n  else\n  {\n  }\n\n  this->updateTemporalBehaviorParameters(true);\n}\n\nvoid CbAbsoluteRotate::onEntry()\n{\n  double goal_angle;\n  ROS_INFO_STREAM(\"[CbAbsoluteRotate] Absolute yaw Angle:\" << this->absoluteGoalAngleDegree);\n\n  if (!this->absoluteGoalAngleDegree)\n  {\n    this->getCurrentState()->param(\"goal_angle\", goal_angle, 45.0);\n  }\n  else\n  {\n    goal_angle = *this->absoluteGoalAngleDegree;\n  }\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  // this should work better with a coroutine and await\n  // this->plannerSwitcher_->setForwardPlanner();\n\n  if (spinningPlanner && *spinningPlanner == SpiningPlanner::PureSpinning)\n    plannerSwitcher->setPureSpinningPlanner();\n  else\n    plannerSwitcher->setDefaultPlanners();\n\n  updateTemporalBehaviorParameters(false);\n\n  auto p = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n  auto referenceFrame = p->getReferenceFrame();\n  auto currentPoseMsg = p->toPoseMsg();\n\n  ClMoveBaseZ::Goal goal;\n  goal.target_pose.header.frame_id = referenceFrame;\n  goal.target_pose.header.stamp = ros::Time::now();\n\n  auto currentAngle = tf::getYaw(currentPoseMsg.orientation);\n  auto targetAngle = goal_angle * M_PI / 180.0;\n  goal.target_pose.pose.position = currentPoseMsg.position;\n  goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(targetAngle);\n\n  auto odomTracker_ = moveBaseClient_->getComponent<odom_tracker::OdomTracker>();\n  if (odomTracker_ != nullptr)\n  {\n    odomTracker_->pushPath(\"PureSpinningToAbsoluteGoalOrientation\");\n    odomTracker_->setStartPoint(p->toPoseStampedMsg());\n    odomTracker_->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);\n  }\n\n  ROS_INFO_STREAM(\"[CbAbsoluteRotate] current pose: \" << currentPoseMsg);\n  ROS_INFO_STREAM(\"[CbAbsoluteRotate] goal pose: \" << goal.target_pose.pose);\n  moveBaseClient_->sendGoal(goal);\n}\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_move_base_client_behavior_base.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_base_z_client_plugin/client_behaviors/cb_move_base_client_behavior_base.h>\n\nnamespace cl_move_base_z\n{\nvoid CbMoveBaseClientBehaviorBase::propagateSuccessEvent(ClMoveBaseZ::ResultConstPtr& r)\n{\n  this->postSuccessEvent();\n}\nvoid CbMoveBaseClientBehaviorBase::propagateFailureEvent(ClMoveBaseZ::ResultConstPtr& r)\n{\n  this->postFailureEvent();\n}\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_navigate_backward.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_navigate_backwards.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n#include <tf/tf.h>\n#include <thread>\n\nnamespace cl_move_base_z\n{\nusing namespace ::cl_move_base_z::odom_tracker;\n\nCbNavigateBackwards::CbNavigateBackwards(float backwardDistance)\n{\n  if (backwardDistance < 0)\n  {\n    ROS_ERROR(\"cb backward: distance must be greater or equal than 0\");\n    this->backwardDistance = 0;\n  }\n  this->backwardDistance = backwardDistance;\n}\n\nCbNavigateBackwards::CbNavigateBackwards()\n{\n}\n\nvoid CbNavigateBackwards::onEntry()\n{\n  // straight motion distance\n  double dist;\n\n  if (!backwardDistance)\n  {\n    this->getCurrentState()->param(\"straight_motion_distance\", dist, 3.5);\n  }\n  else\n  {\n    dist = *backwardDistance;\n  }\n\n  ROS_INFO_STREAM(\"[CbNavigateBackwards] Straight backwards motion distance: \" << dist);\n\n  auto p = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n  auto referenceFrame = p->getReferenceFrame();\n  auto currentPoseMsg = p->toPoseMsg();\n\n  tf::Transform currentPose;\n  tf::poseMsgToTF(currentPoseMsg, currentPose);\n  tf::Transform forwardDeltaTransform;\n  forwardDeltaTransform.setIdentity();\n  forwardDeltaTransform.setOrigin(tf::Vector3(-dist, 0, 0));\n  tf::Transform targetPose = currentPose * forwardDeltaTransform;\n  ClMoveBaseZ::Goal goal;\n  goal.target_pose.header.frame_id = referenceFrame;\n  goal.target_pose.header.stamp = ros::Time::now();\n  tf::poseTFToMsg(targetPose, goal.target_pose.pose);\n  ROS_INFO_STREAM(\"[CbNavigateBackwards] TARGET POSE BACKWARDS: \" << goal.target_pose);\n\n  odomTracker_ = moveBaseClient_->getComponent<OdomTracker>();\n  if (odomTracker_ != nullptr)\n  {\n    this->odomTracker_->clearPath();\n    this->odomTracker_->setStartPoint(currentPoseMsg);\n    this->odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);\n  }\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  plannerSwitcher->setBackwardPlanner();\n  // this wait might be needed to let the backward planner receive the last forward message from the odom tracker\n  ros::Duration(0.5).sleep();\n\n  moveBaseClient_->sendGoal(goal);\n}\n\nvoid CbNavigateBackwards::onExit()\n{\n  if (odomTracker_)\n  {\n    this->odomTracker_->setWorkingMode(WorkingMode::IDLE);\n  }\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_navigate_forward.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_navigate_forward.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace cl_move_base_z\n{\nusing namespace ::cl_move_base_z::odom_tracker;\n\nCbNavigateForward::CbNavigateForward(float forwardDistance)\n{\n  this->forwardDistance = forwardDistance;\n}\n\nCbNavigateForward::CbNavigateForward()\n{\n}\n\nvoid CbNavigateForward::onEntry()\n{\n  // straight motion distance\n  double dist;\n\n  if (!forwardDistance)\n  {\n    this->getCurrentState()->param(\"straight_motion_distance\", dist, 3.5);\n  }\n  else\n  {\n    dist = *forwardDistance;\n  }\n\n  ROS_INFO_STREAM(\"[CbNavigateForward] Straight motion distance: \" << dist);\n\n  auto p = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n  auto referenceFrame = p->getReferenceFrame();\n  auto currentPoseMsg = p->toPoseMsg();\n\n  if (this->forceInitialOrientation)\n  {\n    currentPoseMsg.orientation = *forceInitialOrientation;\n    ROS_WARN_STREAM(\"[CbNavigateForward] Forcing initial straight motion orientation: \" << currentPoseMsg.orientation);\n  }\n\n  tf::Transform currentPose;\n  tf::poseMsgToTF(currentPoseMsg, currentPose);\n\n  tf::Transform forwardDeltaTransform;\n  forwardDeltaTransform.setIdentity();\n  forwardDeltaTransform.setOrigin(tf::Vector3(dist, 0, 0));\n\n  tf::Transform targetPose = currentPose * forwardDeltaTransform;\n\n  ClMoveBaseZ::Goal goal;\n  goal.target_pose.header.frame_id = referenceFrame;\n  goal.target_pose.header.stamp = ros::Time::now();\n  tf::poseTFToMsg(targetPose, goal.target_pose.pose);\n\n  ROS_INFO_STREAM(\"TARGET POSE FORWARD: \" << goal.target_pose.pose);\n\n  geometry_msgs::PoseStamped currentStampedPoseMsg;\n  currentStampedPoseMsg.header.frame_id = referenceFrame;\n  currentStampedPoseMsg.header.stamp = ros::Time::now();\n  tf::poseTFToMsg(currentPose, currentStampedPoseMsg.pose);\n\n  odomTracker_ = moveBaseClient_->getComponent<OdomTracker>();\n  odomTracker_->pushPath(\"StraightNavigationForwards\");\n\n  odomTracker_->setStartPoint(currentStampedPoseMsg);\n  odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  plannerSwitcher->setForwardPlanner();\n\n  moveBaseClient_->sendGoal(goal);\n}\n\nvoid CbNavigateForward::onExit()\n{\n  this->odomTracker_->setWorkingMode(WorkingMode::IDLE);\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_navigate_global_position.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_navigate_global_position.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace cl_move_base_z\n{\nusing namespace ::cl_move_base_z::odom_tracker;\n\nCbNavigateGlobalPosition::CbNavigateGlobalPosition()\n{\n}\n\nCbNavigateGlobalPosition::CbNavigateGlobalPosition(float x, float y, float yaw)\n{\n  auto p = geometry_msgs::Point();\n  p.x = x;\n  p.y = y;\n  goalPosition = p;\n  goalYaw = yaw;\n}\n\nvoid CbNavigateGlobalPosition::setGoal(const geometry_msgs::Pose &pose)\n{\n  goalPosition = pose.position;\n  goalYaw = tf::getYaw(pose.orientation);\n}\n\nvoid CbNavigateGlobalPosition::onEntry()\n{\n  ROS_INFO(\"[CbNavigateGlobalPosition] Entering Navigate Global position\");\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  plannerSwitcher->setDefaultPlanners();\n\n  auto pose = moveBaseClient_->getComponent<cl_move_base_z::Pose>()->toPoseMsg();\n  auto *odomTracker = moveBaseClient_->getComponent<OdomTracker>();\n\n  odomTracker->pushPath(\"FreeNavigationToGoalPose\");\n  odomTracker->setStartPoint(pose);\n  odomTracker->setWorkingMode(WorkingMode::RECORD_PATH);\n\n  execute();\n}\n\n// auxiliary function that defines the motion that is requested to the move_base action server\nvoid CbNavigateGlobalPosition::execute()\n{\n  auto p = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n  auto referenceFrame = p->getReferenceFrame();\n  auto currentPoseMsg = p->toPoseMsg();\n\n  ROS_INFO(\"Sending Goal to MoveBase\");\n  ClMoveBaseZ::Goal goal;\n  goal.target_pose.header.frame_id = referenceFrame;\n  goal.target_pose.header.stamp = ros::Time::now();\n  readStartPoseFromParameterServer(goal);\n\n  // store the start pose on the state machine storage so that it can\n  // be referenced from other states (for example return to radial start)\n  this->getStateMachine()->setGlobalSMData(\"radial_start_pose\", goal.target_pose);\n\n  moveBaseClient_->sendGoal(goal);\n}\n\nvoid CbNavigateGlobalPosition::readStartPoseFromParameterServer(ClMoveBaseZ::Goal &goal)\n{\n  if (!goalPosition)\n  {\n    this->getCurrentState()->getParam(\"start_position_x\", goal.target_pose.pose.position.x);\n    this->getCurrentState()->getParam(\"start_position_y\", goal.target_pose.pose.position.y);\n    double yaw;\n    this->getCurrentState()->getParam(\"start_position_yaw\", yaw);\n\n    goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);\n  }\n  else\n  {\n    goal.target_pose.pose.position = *goalPosition;\n    goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(*goalYaw);\n  }\n\n  ROS_INFO_STREAM(\"start position read from parameter server: \" << goal.target_pose.pose.position);\n}\n\n// This is the substate destructor. This code will be executed when the\n// workflow exits from this substate (that is according to statechart the moment when this object is destroyed)\nvoid CbNavigateGlobalPosition::onExit()\n{\n  ROS_INFO(\"Exiting move goal Action Client\");\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_navigate_next_waypoint.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_navigate_next_waypoint.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n\nnamespace cl_move_base_z\n{\nCbNavigateNextWaypoint::CbNavigateNextWaypoint()\n{\n}\n\nCbNavigateNextWaypoint::~CbNavigateNextWaypoint()\n{\n}\n\nvoid CbNavigateNextWaypoint::onEntry()\n{\n  auto waypointsNavigator = moveBaseClient_->getComponent<WaypointNavigator>();\n  waypointsNavigator->sendNextGoal();\n  ROS_INFO(\"[CbNavigateNextWaypoint] current iteration waypoints x: %ld\",\n           waypointsNavigator->getCurrentWaypointIndex());\n}\n\nvoid CbNavigateNextWaypoint::onExit()\n{\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_rotate.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_rotate.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace cl_move_base_z\n{\nCbRotate::CbRotate()\n{\n}\n\nCbRotate::CbRotate(float rotate_degree)\n{\n  rotateDegree = rotate_degree;\n}\n\nvoid CbRotate::onEntry()\n{\n  double angle_increment_degree;\n\n  if (!rotateDegree)\n  {\n    this->getCurrentState()->param(\"angle_increment_degree\", angle_increment_degree, 45.0);\n  }\n  else\n  {\n    angle_increment_degree = *rotateDegree;\n  }\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  // this should work better with a coroutine and await\n  // this->plannerSwitcher_->setForwardPlanner();\n  plannerSwitcher->setDefaultPlanners();\n\n  auto p = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n  auto referenceFrame = p->getReferenceFrame();\n  auto currentPoseMsg = p->toPoseMsg();\n\n  tf::Transform currentPose;\n  tf::poseMsgToTF(currentPoseMsg, currentPose);\n\n  auto odomTracker = moveBaseClient_->getComponent<odom_tracker::OdomTracker>();\n  ClMoveBaseZ::Goal goal;\n  goal.target_pose.header.frame_id = referenceFrame;\n  goal.target_pose.header.stamp = ros::Time::now();\n\n  auto currentAngle = tf::getYaw(currentPoseMsg.orientation);\n  auto targetAngle = currentAngle + angle_increment_degree * M_PI / 180.0;\n  goal.target_pose.pose.position = currentPoseMsg.position;\n  goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(targetAngle);\n\n  geometry_msgs::PoseStamped stampedCurrentPoseMsg;\n  stampedCurrentPoseMsg.header.frame_id = referenceFrame;\n  stampedCurrentPoseMsg.header.stamp = ros::Time::now();\n  stampedCurrentPoseMsg.pose = currentPoseMsg;\n\n  this->requiresClient(moveBaseClient_);\n  odomTracker->pushPath(\"RelativeRotation\");\n\n  odomTracker->setStartPoint(stampedCurrentPoseMsg);\n  odomTracker->setWorkingMode(odom_tracker::WorkingMode::RECORD_PATH);\n\n  ROS_INFO_STREAM(\"current pose: \" << currentPoseMsg);\n  ROS_INFO_STREAM(\"goal pose: \" << goal.target_pose.pose);\n  moveBaseClient_->sendGoal(goal);\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_undo_path_backwards.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n\nnamespace cl_move_base_z\n{\nusing namespace ::cl_move_base_z::odom_tracker;\n\nvoid CbUndoPathBackwards::onEntry()\n{\n  auto *odomTracker = moveBaseClient_->getComponent<OdomTracker>();\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n\n  nav_msgs::Path forwardpath = odomTracker->getPath();\n  // ROS_INFO_STREAM(\"[UndoPathBackward] Current path backwards: \" << forwardpath);\n\n  odomTracker->setWorkingMode(WorkingMode::CLEAR_PATH);\n\n  ClMoveBaseZ::Goal goal;\n  // this line is used to flush/reset backward planner in the case it were already there\n  // plannerSwitcher->setDefaultPlanners();\n  if (forwardpath.poses.size() > 0)\n  {\n    goal.target_pose = forwardpath.poses.front();\n\n    if(forceUndoLocalPlanner)\n    {\n      if(forceUndoLocalPlanner == UndoPathLocalPlanner::PureSpinningLocalPlanner)\n      {\n        ROS_INFO(\"[CbUndoPathBackwards] forced to use Pure Spinning local planner\");\n        plannerSwitcher->setUndoPathPureSpinningPlannerConfiguration();\n      }\n      else\n      {\n        plannerSwitcher->setUndoPathBackwardsPlannerConfiguration();\n        ROS_INFO(\"[CbUndoPathBackwards] forced to use BackwardsLocalPlanner (default)\");\n      }\n    }\n    else\n    {\n      ROS_INFO(\"[CbUndoPathBackwards] using default local planner: BackwardsLocalPlanner\");\n      plannerSwitcher->setUndoPathBackwardsPlannerConfiguration();\n    }\n\n    moveBaseClient_->sendGoal(goal);\n  }\n}\n\nvoid CbUndoPathBackwards::onExit()\n{\n  auto *odomTracker = moveBaseClient_->getComponent<OdomTracker>();\n  odomTracker->popPath();\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/client_behaviors/cb_undo_path_backwards2.cpp",
    "content": "#include <move_base_z_client_plugin/client_behaviors/cb_undo_path_backwards2.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n\nnamespace cl_move_base_z\n{\ntemplate <typename T>\nint sgn(T val)\n{\n  return (T(0) < val) - (val < T(0));\n}\n\nusing namespace ::cl_move_base_z::odom_tracker;\n\nCbUndoPathBackwards2::CbUndoPathBackwards2() : goalLinePassed_(false)\n{\n  triggerThreshold_ = 0.01;  // 10 mm\n}\n\nvoid CbUndoPathBackwards2::onEntry()\n{\n  odomTracker_ = moveBaseClient_->getComponent<OdomTracker>();\n\n  auto plannerSwitcher = moveBaseClient_->getComponent<PlannerSwitcher>();\n  robotPose_ = moveBaseClient_->getComponent<cl_move_base_z::Pose>();\n\n  nav_msgs::Path forwardpath = odomTracker_->getPath();\n  // ROS_INFO_STREAM(\"[UndoPathBackward] Current path backwards: \" << forwardpath);\n\n  odomTracker_->setWorkingMode(WorkingMode::CLEAR_PATH);\n\n  // this line is used to flush/reset backward planner in the case it were already there\n  // plannerSwitcher->setDefaultPlanners();\n  if (forwardpath.poses.size() > 0)\n  {\n    goal_.target_pose = forwardpath.poses.front();\n    initial_plane_side_ = evalPlaneSide(robotPose_->toPoseMsg());\n    plannerSwitcher->setUndoPathBackwardsPlannerConfiguration();\n    moveBaseClient_->sendGoal(goal_);\n  }\n}\n\n// bool points_on_same_side_of_line(const Vector2d &p1, const Vector2d &p2, const Vector2d &p_line, const Vector2d &normal)\n// {\n//   return normal.dot(p1 - p_line)*normal.dot(p2 - p_line) > 0.0f;\n// }\n\nfloat CbUndoPathBackwards2::evalPlaneSide(const geometry_msgs::Pose& pose)\n{\n  // check the line was passed\n  // y = mx x + y0\n  // y = (sin(alpha)/cos(alpha)) (x -x0) + y0\n  // cos(alpha)(y - y0) - sin(alpha) (x -x0)= 0 // if greater one side if lower , the other\n  auto y = pose.position.y;\n  auto x = pose.position.x;\n  auto alpha = tf::getYaw(goal_.target_pose.pose.orientation);\n  auto y0 = goal_.target_pose.pose.position.y;\n  auto x0 = goal_.target_pose.pose.position.x;\n\n  auto evalimplicit = cos(alpha) * (y - y0) - sin (alpha) * (x - x0);\n  return evalimplicit;\n}\n\nvoid CbUndoPathBackwards2::update()\n{\n  auto pose = robotPose_->toPoseMsg();\n\n  float evalimplicit = evalPlaneSide(pose);\n  if (sgn(evalimplicit) != sgn(initial_plane_side_))\n  {\n    ROS_WARN_STREAM(\"[CbUndoPathBackwards2] goal_ line passed: \"\n                                      << evalimplicit << \"/\" << this->initial_plane_side_);\n\n    if (fabs(evalimplicit) > triggerThreshold_ /*meters*/)\n    {\n       ROS_WARN_STREAM(\"[CbUndoPathBackwards2] virtual goal line passed, stopping behavior and success: \"\n                                      << evalimplicit << \"/\" << this->initial_plane_side_);\n      moveBaseClient_->cancelGoal();\n      // this->postSuccessEvent();\n      this->postVirtualLinePassed_();\n    }\n  }\n  else\n  {\n    ROS_INFO_STREAM_THROTTLE(1.0, \"[CbUndoPathBackwards2] goal_ line not passed yet: \" << evalimplicit << \"/\"\n                                                                                       << this->initial_plane_side_);\n  }\n}\n\nvoid CbUndoPathBackwards2::publishMarkers()\n{\n  double phi = tf::getYaw(goal_.target_pose.pose.orientation);\n  visualization_msgs::Marker marker;\n  marker.header.frame_id = robotPose_->getReferenceFrame();\n\n  marker.header.stamp = ros::Time::now();\n  marker.ns = \"my_namespace2\";\n  marker.id = 0;\n  marker.type = visualization_msgs::Marker::SPHERE;\n  marker.action = visualization_msgs::Marker::ADD;\n  marker.scale.x = 3;\n  marker.scale.y = 3;\n  marker.scale.z = 3;\n  marker.color.a = 1.0;\n  marker.color.r = 1.0;\n  marker.color.g = 0.0;\n  marker.color.b = 0.0;\n\n  marker.pose = goal_.target_pose.pose;\n\n  // geometry_msgs::Point start, end;\n  // start.x = pose.position.x;\n  // start.y = pose.position.y;\n\n  // end.x = pose.position.x + 0.5 * cos(phi);\n  // end.y = pose.position.y + 0.5 * sin(phi);\n\n  // marker.points.push_back(start);\n  // marker.points.push_back(end);\n\n  visualization_msgs::MarkerArray ma;\n  ma.markers.push_back(marker);\n\n  this->visualizationMarkersPub_.publish(ma);\n}\n\nvoid CbUndoPathBackwards2::onExit()\n{\n  auto* odomTracker = moveBaseClient_->getComponent<OdomTracker>();\n  odomTracker->popPath();\n}\n\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/costmap_switch/cp_costmap_switch.cpp",
    "content": "#include <move_base_z_client_plugin/components/costmap_switch/cp_costmap_switch.h>\n\nnamespace cl_move_base_z\n{\n\nstd::array<std::string, 4>\n    CostmapSwitch::layerNames =\n        {\n            \"global_costmap/obstacles_layer\",\n            \"local_costmap/obstacles_layer\"\n            \"global_costmap/inflater_layer\",\n            \"local_costmap/inflater_layer\"};\n\nvoid CostmapSwitch::registerProxyFromDynamicReconfigureServer(std::string costmapName, std::string enablePropertyName)\n{\n    ROS_INFO(\"[CostmapSwitch] registering costmap type: %s\", costmapName.c_str());\n    auto proxy = std::make_shared<CostmapProxy>(this->moveBaseClient_->name_ + \"/\" + costmapName, enablePropertyName);\n    costmapProxies[costmapName] = proxy;\n}\n\nCostmapSwitch::CostmapSwitch()\n{\n}\n\nvoid CostmapSwitch::onInitialize()\n{\n    this->moveBaseClient_ = dynamic_cast<cl_move_base_z::ClMoveBaseZ *>(owner_);\n\n    if (this->moveBaseClient_ == nullptr)\n    {\n        ROS_ERROR(\"the owner of the CostmapSwitch must be a ClMoveBaseZ\");\n    }\n\n    registerProxyFromDynamicReconfigureServer(getStandardCostmapName(StandardLayers::GLOBAL_OBSTACLES_LAYER));\n    registerProxyFromDynamicReconfigureServer(getStandardCostmapName(StandardLayers::LOCAL_OBSTACLES_LAYER));\n    registerProxyFromDynamicReconfigureServer(getStandardCostmapName(StandardLayers::GLOBAL_INFLATED_LAYER));\n    registerProxyFromDynamicReconfigureServer(getStandardCostmapName(StandardLayers::LOCAL_INFLATED_LAYER));\n}\n\nstd::string CostmapSwitch::getStandardCostmapName(StandardLayers layertype)\n{\n    return CostmapSwitch::layerNames[(int)layertype];\n}\n\nbool CostmapSwitch::exists(std::string layerName)\n{\n    if (!this->costmapProxies.count(layerName))\n    {\n        return false;\n    }\n\n    return true;\n}\n\nvoid CostmapSwitch::enable(std::string layerName)\n{\n    ROS_INFO(\"[CostmapSwitch] enabling %s\", layerName.c_str());\n\n    if (!exists(layerName))\n    {\n        ROS_ERROR(\"[CostmapSwitch] costmap %s does not exist\", layerName.c_str());\n        return;\n    }\n    else\n    {\n        ROS_INFO(\"[CostmapSwitch] costmap %s found. Calling dynamic reconfigure server.\", layerName.c_str());\n        costmapProxies[layerName]->setCostmapEnabled(true);\n    }\n}\n\nvoid CostmapSwitch::enable(StandardLayers layerType)\n{\n    this->enable(getStandardCostmapName(layerType));\n}\n\nvoid CostmapSwitch::disable(std::string layerName)\n{\n    ROS_INFO(\"[CostmapSwitch] disabling %s\", layerName.c_str());\n\n    if (!exists(layerName))\n    {\n        ROS_ERROR(\"[CostmapSwitch] costmap %s does not exist\", layerName.c_str());\n        return;\n    }\n    else\n    {\n        ROS_INFO(\"[CostmapSwitch] costmap %s found. Calling dynamic reconfigure server.\", layerName.c_str());\n        costmapProxies[layerName]->setCostmapEnabled(false);\n    }\n}\n\nvoid CostmapSwitch::disable(StandardLayers layerType)\n{\n    this->disable(getStandardCostmapName(layerType));\n}\n\n//-------------------------------------------------------------------------\n\nCostmapProxy::CostmapProxy(std::string costmap_name, std::string enablePropertyName)\n{\n    this->costmapName_ = costmap_name + \"/set_parameters\";\n    dynamic_reconfigure::BoolParameter enableField;\n    enableField.name = \"enabled\";\n    enableField.value = true;\n\n    enableReq.bools.push_back(enableField);\n\n    enableField.value = false;\n    disableReq.bools.push_back(enableField);\n}\n\nvoid CostmapProxy::setCostmapEnabled(bool value)\n{\n    dynamic_reconfigure::ReconfigureRequest srv_req;\n    dynamic_reconfigure::ReconfigureResponse srv_resp;\n\n    if (value)\n        srv_req.config = enableReq;\n    else\n        srv_req.config = disableReq;\n\n    if (ros::service::exists(costmapName_, true))\n    {\n        ROS_INFO(\"sending dynamic reconfigure request: %s\", costmapName_.c_str());\n        ros::service::call(costmapName_, srv_req, srv_resp);\n    }\n    else\n    {\n        ROS_WARN(\"could not call dynamic reconfigure server. It does not exist: %s\", costmapName_.c_str());\n    }\n}\n\nvoid CostmapProxy::dynreconfCallback(const dynamic_reconfigure::Config::ConstPtr &configuration_update)\n{\n    // auto gp = std::find_if(configuration_update->strs.begin(), configuration_update->strs.begin(),\n    //                        [&](const dynamic_reconfigure::StrParameter &p) { return p.name == \"base_global_planner\" && p.value == desired_global_planner_; });\n}\n}\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/odom_tracker/odom_tracker.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <angles/angles.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <boost/range/adaptor/reversed.hpp>\n\nnamespace cl_move_base_z\n{\nnamespace odom_tracker\n{\nOdomTracker::OdomTracker(std::string odomTopicName, std::string odomFrame)\n  : paramServer_(ros::NodeHandle(\"~/odom_tracker\"))\n{\n  workingMode_ = WorkingMode::RECORD_PATH;\n  publishMessages = true;\n  subscribeToOdometryTopic_ = true;\n  this->odomFrame_ = odomFrame;\n\n  ros::NodeHandle nh(\"~/odom_tracker\");\n\n  ROS_WARN(\"Initializing Odometry Tracker\");\n\n  if (!nh.getParam(\"odom_frame\", this->odomFrame_))\n  {\n    ROS_INFO_STREAM(\"[OdomTracker] odomFrame:\" << this->odomFrame_);\n  }\n  ROS_INFO_STREAM(\"[OdomTracker] odomFrame overwritten by ros parameter:\" << this->odomFrame_);\n\n  if (!nh.getParam(\"record_point_distance_threshold\", recordPointDistanceThreshold_))\n  {\n    recordPointDistanceThreshold_ = 0.005;  // 5 mm\n  }\n  ROS_INFO_STREAM(\"[OdomTracker] record_point_distance_threshold :\" << recordPointDistanceThreshold_);\n\n  if (!nh.getParam(\"record_angular_distance_threshold\", recordAngularDistanceThreshold_))\n  {\n    recordAngularDistanceThreshold_ = 0.1;  // radians\n  }\n  ROS_INFO_STREAM(\"[OdomTracker] record_angular_distance_threshold :\" << recordAngularDistanceThreshold_);\n\n  if (!nh.getParam(\"clear_point_distance_threshold\", clearPointDistanceThreshold_))\n  {\n    clearPointDistanceThreshold_ = 0.05;  // 5 cm\n  }\n  ROS_INFO_STREAM(\"[OdomTracker] clear_point_distance_threshold :\" << clearPointDistanceThreshold_);\n\n  if (!nh.getParam(\"clear_angular_distance_threshold\", clearAngularDistanceThreshold_))\n  {\n    clearAngularDistanceThreshold_ = 0.1;  // radians\n  }\n  ROS_INFO_STREAM(\"[OdomTracker] clear_angular_distance_threshold :\" << clearAngularDistanceThreshold_);\n\n  if (this->subscribeToOdometryTopic_)\n  {\n    odomSub_ = nh.subscribe(odomTopicName, 1, &OdomTracker::processOdometryMessage, this);\n  }\n\n  robotBasePathPub_ = std::make_shared<realtime_tools::RealtimePublisher<nav_msgs::Path>>(nh, \"odom_tracker_path\", 1);\n  robotBasePathStackedPub_ =\n      std::make_shared<realtime_tools::RealtimePublisher<nav_msgs::Path>>(nh, \"odom_tracker_stacked_path\", 1);\n\n  f = boost::bind(&OdomTracker::reconfigCB, this, _1, _2);\n  paramServer_.setCallback(f);\n}\n\n/**\n ******************************************************************************************************************\n * setWorkingMode()\n ******************************************************************************************************************\n */\nvoid OdomTracker::setWorkingMode(WorkingMode workingMode)\n{\n  // ROS_INFO(\"odom_tracker m_mutex acquire\");\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  ROS_INFO(\"[OdomTracker] setting working mode to: %d\", (uint8_t)workingMode);\n  workingMode_ = workingMode;\n  // ROS_INFO(\"odom_tracker m_mutex release\");\n}\n\n/**\n ******************************************************************************************************************\n * setPublishMessages()\n ******************************************************************************************************************\n */\nvoid OdomTracker::setPublishMessages(bool value)\n{\n  // ROS_INFO(\"odom_tracker m_mutex acquire\");\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  publishMessages = value;\n  // ROS_INFO(\"odom_tracker m_mutex release\");\n  this->updateAggregatedStackPath();\n}\n\nvoid OdomTracker::pushPath(std::string newPathTagName)\n{\n  ROS_INFO(\"odom_tracker m_mutex acquire\");\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  ROS_INFO(\"PUSH_PATH PATH EXITING\");\n  this->logStateString();\n\n  pathStack_.push_back({baseTrajectory_, this->currentPathTagName_});\n  baseTrajectory_.poses.clear();\n\n  if(newPathTagName ==\"\")\n  {\n    this->currentPathTagName_=\"(unspecified path name)\";\n  }\n  else\n  {\n    this->currentPathTagName_ = newPathTagName;\n  }\n\n  ROS_INFO(\"PUSH_PATH PATH EXITING\");\n  this->logStateString();\n  ROS_INFO(\"odom_tracker m_mutex release\");\n  this->updateAggregatedStackPath();\n}\n\nvoid OdomTracker::popPath(int popCount, bool keepPreviousPath)\n{\n  ROS_INFO(\"odom_tracker m_mutex acquire\");\n  std::lock_guard<std::mutex> lock(m_mutex_);\n\n  ROS_INFO(\"POP PATH ENTRY\");\n  this->logStateString();\n\n  if (!keepPreviousPath)\n  {\n    baseTrajectory_.poses.clear();\n  }\n\n  while (popCount > 0 && !pathStack_.empty())\n  {\n    auto &stacked = pathStack_.back().path.poses;\n    baseTrajectory_.poses.insert(baseTrajectory_.poses.begin(), stacked.begin(), stacked.end());\n    pathStack_.pop_back();\n    popCount--;\n\n    ROS_INFO(\"POP PATH Iteration \");\n    this->logStateString();\n  }\n\n  ROS_INFO(\"POP PATH EXITING\");\n  this->logStateString();\n  ROS_INFO(\"odom_tracker m_mutex release\");\n  this->updateAggregatedStackPath();\n}\n\nvoid OdomTracker::logStateString()\n{\n  ROS_INFO(\"--- odom tracker state ---\");\n  ROS_INFO(\" - stacked paths count: %ld\", pathStack_.size());\n  ROS_INFO_STREAM(\" - [STACK-HEAD active path '\" << currentPathTagName_ <<\"' size: \"<< baseTrajectory_.poses.size()<<\"]\");\n  int i = 0;\n  for (auto &p : pathStack_ | boost::adaptors::reversed)\n  {\n    ROS_INFO_STREAM(\" - p \" << i << \"[\" <<  p.path.header.stamp <<  \"][\" << p.pathTagName << \"], size: \" << p.path.poses.size());\n    i++;\n  }\n  ROS_INFO(\"---\");\n}\n\nvoid OdomTracker::clearPath()\n{\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  baseTrajectory_.poses.clear();\n\n  rtPublishPaths(ros::Time::now());\n  this->logStateString();\n  this->updateAggregatedStackPath();\n}\n\nvoid OdomTracker::setStartPoint(const geometry_msgs::PoseStamped &pose)\n{\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  ROS_INFO_STREAM(\"[OdomTracker] set current path starting point: \" << pose);\n  if (baseTrajectory_.poses.size() > 0)\n  {\n    baseTrajectory_.poses[0] = pose;\n  }\n  else\n  {\n    baseTrajectory_.poses.push_back(pose);\n  }\n  this->updateAggregatedStackPath();\n}\n\nvoid OdomTracker::setStartPoint(const geometry_msgs::Pose &pose)\n{\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  ROS_INFO_STREAM(\"[OdomTracker] set current path starting point: \" << pose);\n  geometry_msgs::PoseStamped posestamped;\n  posestamped.header.frame_id = this->odomFrame_;\n  posestamped.header.stamp = ros::Time::now();\n  posestamped.pose = pose;\n\n  if (baseTrajectory_.poses.size() > 0)\n  {\n    baseTrajectory_.poses[0] = posestamped;\n  }\n  else\n  {\n    baseTrajectory_.poses.push_back(posestamped);\n  }\n  this->updateAggregatedStackPath();\n}\n\nnav_msgs::Path OdomTracker::getPath()\n{\n  std::lock_guard<std::mutex> lock(m_mutex_);\n  return this->baseTrajectory_;\n}\n\n/**\n ******************************************************************************************************************\n * rtPublishPaths()\n ******************************************************************************************************************\n */\nvoid OdomTracker::rtPublishPaths(ros::Time timestamp)\n{\n  if (robotBasePathPub_->trylock())\n  {\n    nav_msgs::Path &msg = robotBasePathPub_->msg_;\n    ///  Copy trajectory\n\n    msg = baseTrajectory_;\n\n    msg.header.stamp = timestamp;\n    robotBasePathPub_->unlockAndPublish();\n  }\n\n  if (robotBasePathStackedPub_->trylock())\n  {\n    nav_msgs::Path &msg = robotBasePathStackedPub_->msg_;\n    ///  Copy trajectory\n\n    msg = aggregatedStackPathMsg_;\n    msg.header.stamp = timestamp;\n    robotBasePathStackedPub_->unlockAndPublish();\n  }\n}\n\nvoid OdomTracker::updateAggregatedStackPath()\n{\n  aggregatedStackPathMsg_.poses.clear();\n  for (auto &p : pathStack_)\n  {\n    aggregatedStackPathMsg_.poses.insert(aggregatedStackPathMsg_.poses.end(), p.path.poses.begin(), p.path.poses.end());\n  }\n\n  aggregatedStackPathMsg_.header.frame_id = this->odomFrame_;\n}\n\n/**\n ******************************************************************************************************************\n * updateBackward()\n ******************************************************************************************************************\n */\nbool OdomTracker::updateClearPath(const nav_msgs::Odometry &odom)\n{\n  // we initially accept any message if the queue is empty\n  /// Track robot base pose\n  geometry_msgs::PoseStamped base_pose;\n\n  base_pose.pose = odom.pose.pose;\n  base_pose.header = odom.header;\n  baseTrajectory_.header = odom.header;\n\n  bool acceptBackward = false;\n  bool clearingError = false;\n  bool finished = false;\n\n  while (!finished)\n  {\n    if (baseTrajectory_.poses.size() <= 1)  // we at least keep always the first point of the forward path when clearing\n                                            // (this is important for backwards planner replanning and not losing the\n                                            // last goal)\n    {\n      acceptBackward = false;\n      finished = true;\n    }\n    else\n    {\n      auto &carrotPose = baseTrajectory_.poses.back().pose;\n      const geometry_msgs::Point &carrotPoint = carrotPose.position;\n      double carrotAngle = tf::getYaw(carrotPose.orientation);\n\n      auto &currePose = base_pose.pose;\n      const geometry_msgs::Point &currePoint = currePose.position;\n      double currentAngle = tf::getYaw(currePose.orientation);\n\n      double lastpointdist = p2pDistance(carrotPoint, currePoint);\n      double goalAngleOffset = fabs(angles::shortest_angular_distance(carrotAngle, currentAngle));\n\n      acceptBackward = !baseTrajectory_.poses.empty() && lastpointdist < clearPointDistanceThreshold_ &&\n                       goalAngleOffset < clearAngularDistanceThreshold_;\n\n      clearingError = lastpointdist > 2 * clearPointDistanceThreshold_;\n      ROS_DEBUG_STREAM(\"[OdomTracker] clearing (accepted: \" << acceptBackward << \") linerr: \" << lastpointdist\n                                                            << \", anglerr: \" << goalAngleOffset);\n    }\n\n    // ROS_INFO(\"Backwards, last distance: %lf < %lf accept: %d\", dist, minPointDistanceBackwardThresh_,\n    // acceptBackward);\n    if (acceptBackward && baseTrajectory_.poses.size() > 1) /*we always leave at least one item, specially interesting\n                                                               for the backward local planner reach the backwards goal\n                                                               with precision enough*/\n    {\n      baseTrajectory_.poses.pop_back();\n    }\n    else if (clearingError)\n    {\n      finished = true;\n      ROS_WARN(\"[OdomTracker] Incorrect odom clearing motion.\");\n    }\n    else\n    {\n      finished = true;\n      /// Not removing point because it is enough far from the last cord point\n    }\n  }\n\n  return acceptBackward;\n}\n/**\n ******************************************************************************************************************\n * updateRecordPath()\n ******************************************************************************************************************\n */\nbool OdomTracker::updateRecordPath(const nav_msgs::Odometry &odom)\n{\n  /// Track robot base pose\n  geometry_msgs::PoseStamped base_pose;\n\n  base_pose.pose = odom.pose.pose;\n  base_pose.header = odom.header;\n  baseTrajectory_.header = odom.header;\n\n  bool enqueueOdomMessage = false;\n\n  double dist = -1;\n  if (baseTrajectory_.poses.empty())\n  {\n    enqueueOdomMessage = true;\n  }\n  else\n  {\n    const auto &prevPose = baseTrajectory_.poses.back().pose;\n    const geometry_msgs::Point &prevPoint = prevPose.position;\n    double prevAngle = tf::getYaw(prevPose.orientation);\n\n    const geometry_msgs::Point &currePoint = base_pose.pose.position;\n    double currentAngle = tf::getYaw(base_pose.pose.orientation);\n\n    dist = p2pDistance(prevPoint, currePoint);\n    double goalAngleOffset = fabs(angles::shortest_angular_distance(prevAngle, currentAngle));\n\n    // ROS_WARN(\"dist %lf vs min %lf\", dist, recordPointDistanceThreshold_);\n\n    if (dist > recordPointDistanceThreshold_ || goalAngleOffset > recordAngularDistanceThreshold_)\n    {\n      enqueueOdomMessage = true;\n    }\n    else\n    {\n      // ROS_WARN(\"skip odom, dist: %lf\", dist);\n      enqueueOdomMessage = false;\n    }\n  }\n\n  if (enqueueOdomMessage)\n  {\n    baseTrajectory_.poses.push_back(base_pose);\n  }\n\n  return enqueueOdomMessage;\n}\n\n/**\n ******************************************************************************************************************\n * reconfigCB()\n ******************************************************************************************************************\n */\nvoid OdomTracker::reconfigCB(::move_base_z_client_plugin::OdomTrackerConfig &config, uint32_t level)\n{\n  ROS_INFO(\"[OdomTracker] reconfigure Request\");\n  this->odomFrame_ = config.odom_frame;\n\n  this->recordPointDistanceThreshold_ = config.record_point_distance_threshold;\n  this->recordAngularDistanceThreshold_ = config.record_angular_distance_threshold;\n  this->clearPointDistanceThreshold_ = config.clear_point_distance_threshold;\n  this->clearAngularDistanceThreshold_ = config.clear_angular_distance_threshold;\n}\n\n/**\n ******************************************************************************************************************\n * processOdometryMessage()\n ******************************************************************************************************************\n */\nvoid OdomTracker::processOdometryMessage(const nav_msgs::Odometry &odom)\n{\n  // ROS_INFO(\"odom_tracker m_mutex acquire\");\n  std::lock_guard<std::mutex> lock(m_mutex_);\n\n  if (workingMode_ == WorkingMode::RECORD_PATH)\n  {\n    updateRecordPath(odom);\n  }\n  else if (workingMode_ == WorkingMode::CLEAR_PATH)\n  {\n    updateClearPath(odom);\n  }\n\n  // ROS_WARN(\"odomTracker odometry callback\");\n  if (publishMessages)\n  {\n    rtPublishPaths(odom.header.stamp);\n  }\n\n  // ROS_INFO(\"odom_tracker m_mutex release\");\n}\n}  // namespace odom_tracker\n}  // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/odom_tracker/odom_tracker_node.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_base_z_client_plugin/components/move_base_z_plugin/components/odom_tracker/odom_tracker.h>\n#include <odom_tracker/OdomTrackerAction.h>\n#include <actionlib/server/simple_action_server.h>\n#include <memory>\n\ntypedef actionlib::SimpleActionServer<odom_tracker::OdomTrackerAction> Server;\n\nusing namespace odom_tracker;\nusing namespace cl_move_base_z::odom_tracker;\n\nclass OdomTrackerActionServer\n{\npublic:\n  std::shared_ptr<Server> as_;\n  OdomTracker odomTracker;\n\n  OdomTrackerActionServer()\n      : odomTracker(\"move_base\")\n  {\n  }\n\n  /**\n******************************************************************************************************************\n* execute()\n******************************************************************************************************************\n*/\n  void execute(const OdomTrackerGoalConstPtr &goal) // Note: \"Action\" is not appended to DoDishes here\n  {\n    try\n    {\n      switch (goal->command)\n      {\n      case OdomTrackerGoal::RECORD_PATH:\n        odomTracker.setWorkingMode(WorkingMode::RECORD_PATH);\n        break;\n\n      case OdomTrackerGoal::CLEAR_PATH:\n        odomTracker.setWorkingMode(WorkingMode::CLEAR_PATH);\n        break;\n\n      case OdomTrackerGoal::IDLE:\n        odomTracker.setWorkingMode(WorkingMode::IDLE);\n        break;\n\n      case OdomTrackerGoal::START_BROADCAST_PATH:\n        odomTracker.setPublishMessages(true);\n        break;\n\n      case OdomTrackerGoal::STOP_BROADCAST_PATH:\n        odomTracker.setPublishMessages(false);\n        break;\n\n      case OdomTrackerGoal::PUSH_PATH:\n        odomTracker.pushPath();\n        break;\n\n      case OdomTrackerGoal::POP_PATH:\n        odomTracker.popPath();\n        break;\n\n      default:\n\n        ROS_ERROR(\"Odom Tracker Node - Action Server execute error: incorrect command - %d\", goal->command);\n        as_->setAborted();\n      }\n\n      // never reach succeeded because were are interested in keeping the feedback alive\n      as_->setSucceeded();\n    }\n    catch (std::exception &ex)\n    {\n      ROS_ERROR(\"Odom Tracker Node - Action Server execute error: %s\", ex.what());\n      as_->setAborted();\n    }\n  }\n\n  /**\n******************************************************************************************************************\n* run()\n******************************************************************************************************************\n*/\n  void run()\n  {\n    ros::NodeHandle n;\n    ROS_INFO(\"Creating odom tracker action server\");\n\n    as_ = std::make_shared<Server>(n, \"odom_tracker\", boost::bind(&OdomTrackerActionServer::execute, this, _1), false);\n    ROS_INFO(\"Starting OdomTracker Action Server\");\n\n    as_->start();\n\n    ros::spin();\n  }\n};\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"odom_tracker_node\");\n  OdomTrackerActionServer as;\n\n  as.run();\n}\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/planner_switcher/planner_switcher.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\nnamespace cl_move_base_z\n{\n\nPlannerSwitcher::PlannerSwitcher()\n{\n}\n\nvoid PlannerSwitcher::onInitialize()\n{\n  auto client_ = dynamic_cast<ClMoveBaseZ *>(owner_);\n  ros::NodeHandle nh(client_->name_);\n  dynrecofSub_ = nh.subscribe<dynamic_reconfigure::Config>(\"/move_base/parameter_updates\", 1, boost::bind(&PlannerSwitcher::dynreconfCallback, this, _1));\n}\n\nvoid PlannerSwitcher::setUndoPathBackwardsPlannerConfiguration()\n{\n  ROS_INFO(\"[PlannerSwitcher] Planner Switcher: Trying to set BackwardPlanner\");\n  desired_global_planner_ = \"undo_path_global_planner/UndoPathGlobalPlanner\";\n  desired_local_planner_ = \"backward_local_planner/BackwardLocalPlanner\";\n  updatePlanners();\n}\n\nvoid PlannerSwitcher::setUndoPathPureSpinningPlannerConfiguration()\n{\n  ROS_INFO(\"[PlannerSwitcher] Planner Switcher: Trying to set BackwardPlanner\");\n  desired_global_planner_ = \"undo_path_global_planner/UndoPathGlobalPlanner\";\n  desired_local_planner_ = \"pure_spinning_local_planner/PureSpinningLocalPlanner\";\n  updatePlanners();\n}\n\nvoid PlannerSwitcher::setBackwardPlanner()\n{\n  ROS_INFO(\"[PlannerSwitcher] Planner Switcher: Trying to set BackwardPlanner\");\n  desired_global_planner_ = \"backward_global_planner/BackwardGlobalPlanner\";\n  desired_local_planner_ = \"backward_local_planner/BackwardLocalPlanner\";\n  updatePlanners();\n}\n\nvoid PlannerSwitcher::setForwardPlanner()\n{\n  ROS_INFO(\"[PlannerSwitcher] Planner Switcher: Trying to set ForwardPlanner\");\n  desired_global_planner_ = \"forward_global_planner/ForwardGlobalPlanner\";\n  desired_local_planner_ = \"forward_local_planner/ForwardLocalPlanner\";\n  updatePlanners();\n}\n\n\nvoid PlannerSwitcher::setPureSpinningPlanner()\n{\n  ROS_INFO(\"[PlannerSwitcher] Planner Switcher: Trying to set PureSpinningPlanner\");\n  desired_global_planner_ = \"forward_global_planner/ForwardGlobalPlanner\";\n  desired_local_planner_ = \"pure_spinning_local_planner/PureSpinningLocalPlanner\";\n  updatePlanners();\n}\n\nvoid PlannerSwitcher::setDefaultPlanners()\n{\n  desired_global_planner_ = \"navfn/NavfnROS\";\n  desired_local_planner_ = \"base_local_planner/TrajectoryPlannerROS\";\n  updatePlanners();\n}\n\nvoid PlannerSwitcher::updatePlanners(bool subscribecallback)\n{\n  ROS_INFO_STREAM(\"[PlannerSwitcher] Setting global planner: \" << desired_global_planner_);\n  ROS_INFO_STREAM(\"[PlannerSwitcher] Setting local planner: \" << desired_local_planner_);\n\n  dynamic_reconfigure::ReconfigureRequest srv_req;\n  dynamic_reconfigure::ReconfigureResponse srv_resp;\n  dynamic_reconfigure::StrParameter local_planner, global_planner;\n  dynamic_reconfigure::Config conf;\n\n  local_planner.name = \"base_local_planner\";\n  local_planner.value = desired_local_planner_;\n  conf.strs.push_back(local_planner);\n\n  global_planner.name = \"base_global_planner\";\n  global_planner.value = desired_global_planner_;\n  conf.strs.push_back(global_planner);\n\n  srv_req.config = conf;\n  ROS_INFO(\"setting values of the dynamic reconfigure server\");\n  bool error;\n  do\n  {\n    bool res = ros::service::call(\"/move_base/set_parameters\", srv_req, srv_resp);\n    ros::spinOnce();\n    ros::Duration(0.5).sleep();\n\n    error = false;\n    auto baselocalPlannerIt = std::find_if(srv_resp.config.strs.begin(), srv_resp.config.strs.end(), [](auto sp){return sp.name == \"base_local_planner\";});\n    auto baseglobalPlannerIt = std::find_if(srv_resp.config.strs.begin(), srv_resp.config.strs.end(), [](auto sp){return sp.name == \"base_global_planner\";});\n\n    auto updatedLocalPlanner = baselocalPlannerIt->value;\n    auto updatedGlobalPlanner = baseglobalPlannerIt->value;\n    ROS_INFO_STREAM(\"[PlannerSwitcher] Selected base local planner: \" << updatedLocalPlanner);\n    ROS_INFO_STREAM(\"[PlannerSwitcher] Selected base global planner: \" << updatedGlobalPlanner);\n\n    if(updatedGlobalPlanner != desired_global_planner_ || updatedLocalPlanner!= desired_local_planner_)\n    {\n      ROS_WARN(\"[PlannerSwitcher] Planners not correctly configured. Waiting 1 second and retrying...\");\n      ROS_INFO_STREAM(\"[PlannerSwitcher] Response: \" << srv_resp);\n      error = true;\n    }\n\n  }while(error);\n\n}\n\nvoid PlannerSwitcher::dynreconfCallback(const dynamic_reconfigure::Config::ConstPtr &configuration_update)\n{\n  auto gp = std::find_if(configuration_update->strs.begin(), configuration_update->strs.begin(),\n                         [&](const dynamic_reconfigure::StrParameter &p) {\n                           return p.name == \"base_global_planner\" && p.value == desired_global_planner_;\n                         });\n\n  auto lp = std::find_if(configuration_update->strs.begin(), configuration_update->strs.begin(),\n                         [&](const dynamic_reconfigure::StrParameter &p) {\n                           return p.name == \"base_local_planner\" && p.value == desired_local_planner_;\n                         });\n\n  if (gp == configuration_update->strs.end() || lp == configuration_update->strs.end())\n  {\n    ROS_INFO(\"[PlannerSwitcher] After planner update it is noticed an incorrect move_base planner configuration. Resending request.\");\n    set_planners_mode_flag = false;\n    updatePlanners(false);\n  }\n  else\n  {\n    ROS_INFO(\"[PlannerSwitcher] Planners correctly configured according to parameter update callback\");\n    set_planners_mode_flag = true;\n  }\n}\n}; // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/pose/cp_pose.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\n\nnamespace cl_move_base_z\n{\n    std::shared_ptr<tf::TransformListener> Pose::tfListener_ = nullptr;\n    std::mutex Pose::listenerMutex_;\n\n    Pose::Pose(std::string targetFrame, std::string referenceFrame)\n        : poseFrameName_(targetFrame),\n          referenceFrame_(referenceFrame),\n          isInitialized(false),\n          m_mutex_()\n    {\n        this->pose_.header.frame_id = referenceFrame_;\n        ROS_INFO(\"[Pose] Creating Pose tracker component to track %s in the reference frame %s\", targetFrame.c_str(), referenceFrame.c_str());\n\n        {\n            //singleton\n            std::lock_guard<std::mutex> guard(listenerMutex_);\n            if (tfListener_ == nullptr)\n                tfListener_ = std::make_shared<tf::TransformListener>();\n        }\n    }\n\n    void Pose::waitTransformUpdate(ros::Rate r)\n    {\n        bool found = false;\n        while (ros::ok() && !found)\n        {\n            tf::StampedTransform transform;\n            try\n            {\n                {\n                    std::lock_guard<std::mutex> lock(listenerMutex_);\n                    tfListener_->lookupTransform(referenceFrame_, poseFrameName_,\n                                                      ros::Time(0), transform);\n                }\n\n                {\n                    std::lock_guard<std::mutex> guard(m_mutex_);\n                    tf::poseTFToMsg(transform, this->pose_.pose);\n                    this->pose_.header.stamp = transform.stamp_;\n                    found = true;\n                    this->isInitialized = true;\n                }\n            }\n            catch (tf::TransformException ex)\n            {\n                ROS_ERROR_STREAM_THROTTLE(1, \"[Component pose] (\" << poseFrameName_ << \"/[\" << referenceFrame_ << \"] ) is failing on pose update : \" << ex.what());\n            }\n\n            r.sleep();\n            ros::spinOnce();\n        }\n    }\n\n    void Pose::update()\n    {\n        tf::StampedTransform transform;\n        try\n        {\n            {\n                std::lock_guard<std::mutex> lock(listenerMutex_);\n                tfListener_->lookupTransform(referenceFrame_, poseFrameName_,\n                                                  ros::Time(0), transform);\n            }\n\n            {\n                std::lock_guard<std::mutex> guard(m_mutex_);\n                tf::poseTFToMsg(transform, this->pose_.pose);\n                this->pose_.header.stamp = transform.stamp_;\n                this->isInitialized = true;\n            }\n        }\n        catch (tf::TransformException ex)\n        {\n            ROS_ERROR_STREAM_THROTTLE(1, \"[Component pose] (\" << poseFrameName_ << \"/[\" << referenceFrame_ << \"] ) is failing on pose update : \" << ex.what());\n        }\n    }\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/waypoints_navigator/waypoints_event_dispatcher.cpp",
    "content": "#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_event_dispatcher.h>\n\nnamespace cl_move_base_z\n{\nvoid WaypointEventDispatcher::postWaypointEvent(int index)\n{\n    auto& fn = postWaypointFn[index % WAYPOINTS_EVENTCOUNT];\n    if(fn!=nullptr)\n        fn();\n}\n} // namespace smacc\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/components/waypoints_navigator/waypoints_navigator.cpp",
    "content": "#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n#include <move_base_z_client_plugin/components/planner_switcher/planner_switcher.h>\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\n#include <fstream>\n#include <ros/ros.h>\n#include <yaml-cpp/yaml.h>\n#include <tf/transform_datatypes.h>\n\nnamespace cl_move_base_z\n{\nWaypointNavigator::WaypointNavigator()\n    : currentWaypoint_(0),\n      waypoints_(0)\n{\n}\n\nvoid WaypointNavigator::onInitialize()\n{\n  client_ = dynamic_cast<ClMoveBaseZ *>(owner_);\n}\n\nvoid WaypointNavigator::onGoalReached(ClMoveBaseZ::ResultConstPtr &res)\n{\n  waypointsEventDispatcher.postWaypointEvent(currentWaypoint_);\n  currentWaypoint_++;\n  this->succeddedConnection_.disconnect();\n}\n\nvoid WaypointNavigator::sendNextGoal()\n{\n  if (currentWaypoint_ >= 0 && currentWaypoint_ < waypoints_.size())\n  {\n    auto &next = waypoints_[currentWaypoint_];\n\n    auto odomTracker = client_->getComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n    auto p = client_->getComponent<cl_move_base_z::Pose>();\n    auto pose = p->toPoseMsg();\n\n    ClMoveBaseZ::Goal goal;\n    goal.target_pose.header.frame_id = p->getReferenceFrame();\n    goal.target_pose.header.stamp = ros::Time::now();\n    goal.target_pose.pose = next;\n\n    auto plannerSwitcher = client_->getComponent<PlannerSwitcher>();\n    plannerSwitcher->setDefaultPlanners();\n\n    ros::spinOnce();\n    ros::Duration(5).sleep();\n\n    if (odomTracker != nullptr)\n    {\n      odomTracker->pushPath(\"FreeNavigationToGoalWaypointPose\");\n      odomTracker->setStartPoint(pose);\n      odomTracker->setWorkingMode(cl_move_base_z::odom_tracker::WorkingMode::RECORD_PATH);\n    }\n\n    this->succeddedConnection_ = client_->onSucceeded(&WaypointNavigator::onGoalReached, this);\n    client_->sendGoal(goal);\n  }\n  else\n  {\n    ROS_WARN(\"[WaypointsNavigator] All waypoints were consumed. There is no more waypoints available.\");\n  }\n}\n\nvoid WaypointNavigator::insertWaypoint(int index, geometry_msgs::Pose &newpose)\n{\n  if (index >= 0 && index <= waypoints_.size())\n  {\n    waypoints_.insert(waypoints_.begin(), index, newpose);\n  }\n}\n\nvoid WaypointNavigator::setWaypoints(const std::vector<geometry_msgs::Pose> &waypoints)\n{\n  this->waypoints_ = waypoints;\n}\n\nvoid WaypointNavigator::setWaypoints(const std::vector<Pose2D> &waypoints)\n{\n  this->waypoints_.clear();\n  for (auto &p : waypoints)\n  {\n    geometry_msgs::Pose pose;\n    pose.position.x = p.x_;\n    pose.position.y = p.y_;\n    pose.position.z = 0.0;\n    pose.orientation = tf::createQuaternionMsgFromYaw(p.yaw_);\n\n    this->waypoints_.push_back(pose);\n  }\n}\n\nvoid WaypointNavigator::removeWaypoint(int index)\n{\n  if (index >= 0 && index < waypoints_.size())\n  {\n    waypoints_.erase(waypoints_.begin() + index);\n  }\n}\n\nconst std::vector<geometry_msgs::Pose> &WaypointNavigator::getWaypoints() const\n{\n  return waypoints_;\n}\n\nlong WaypointNavigator::getCurrentWaypointIndex() const\n{\n  return currentWaypoint_;\n}\n\n#define HAVE_NEW_YAMLCPP\nvoid WaypointNavigator::loadWayPointsFromFile(std::string filepath)\n{\n  this->waypoints_.clear();\n  std::ifstream ifs(filepath.c_str(), std::ifstream::in);\n  if (ifs.good() == false)\n  {\n    throw std::string(\"Waypoints file not found\");\n  }\n\n  try\n  {\n\n#ifdef HAVE_NEW_YAMLCPP\n    YAML::Node node = YAML::Load(ifs);\n#else\n    YAML::Parser parser(ifs);\n    parser.GetNextDocument(node);\n#endif\n\n#ifdef HAVE_NEW_YAMLCPP\n    const YAML::Node &wp_node_tmp = node[\"waypoints\"];\n    const YAML::Node *wp_node = wp_node_tmp ? &wp_node_tmp : NULL;\n#else\n    const YAML::Node *wp_node = node.FindValue(\"waypoints\");\n#endif\n\n    if (wp_node != NULL)\n    {\n      for (uint64_t i = 0; i < wp_node->size(); ++i)\n      {\n        // Parse waypoint entries on YAML\n        geometry_msgs::Pose wp;\n\n        try\n        {\n          // (*wp_node)[i][\"name\"] >> wp.name;\n          // (*wp_node)[i][\"frame_id\"] >> wp.header.frame_id;\n          wp.position.x = (*wp_node)[i][\"position\"][\"x\"].as<double>();\n          wp.position.y = (*wp_node)[i][\"position\"][\"y\"].as<double>();\n          wp.position.z = (*wp_node)[i][\"position\"][\"z\"].as<double>();\n          wp.orientation.x = (*wp_node)[i][\"orientation\"][\"x\"].as<double>();\n          wp.orientation.y = (*wp_node)[i][\"orientation\"][\"y\"].as<double>();\n          wp.orientation.z = (*wp_node)[i][\"orientation\"][\"z\"].as<double>();\n          wp.orientation.w = (*wp_node)[i][\"orientation\"][\"w\"].as<double>();\n\n          this->waypoints_.push_back(wp);\n        }\n        catch (...)\n        {\n          ROS_ERROR(\"parsing waypoint file, syntax error in point %ld\", i);\n        }\n      }\n      ROS_INFO_STREAM(\"Parsed \" << this->waypoints_.size() << \" waypoints.\");\n    }\n    else\n    {\n      ROS_WARN_STREAM(\"Couldn't find any waypoints in the provided yaml file.\");\n    }\n  }\n  catch (const YAML::ParserException &ex)\n  {\n    ROS_ERROR_STREAM(\"Error loading the Waypoints YAML file. Incorrect syntax: \" << ex.what());\n  }\n}\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_base_z_client/move_base_z_client_plugin/src/move_base_z_client_plugin.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <pluginlib/class_list_macros.h>\n\nnamespace cl_move_base_z\n{\n\nClMoveBaseZ::ClMoveBaseZ(std::string moveBaseName)\n : Base(moveBaseName)\n{\n    //ROS_INFO(\"Smacc Move Base Action Client\");\n}\n\nstd::string ClMoveBaseZ::getName() const\n{\n    return \"MOVE BASE ACTION CLIENT\";\n}\n\nvoid ClMoveBaseZ::initialize()\n{\n    SmaccActionClientBase<move_base_msgs::MoveBaseAction>::initialize();\n}\n\nClMoveBaseZ::~ClMoveBaseZ()\n{\n}\n} // namespace smacc\n\nPLUGINLIB_EXPORT_CLASS(cl_move_base_z::ClMoveBaseZ, smacc::ISmaccClient)\n"
  },
  {
    "path": "smacc_client_library/move_eye/move_eye_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package move_eye_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* move_eye package\n* Contributors: Pabo Iñigo Blasco\n\n* move_eye package\n* Contributors: Pabo Iñigo Blasco\n\n* move_eye package\n* Contributors: Pabo Iñigo Blasco\n\n* move_eye package\n* Contributors: Pabo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/move_eye/move_eye_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(move_eye_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES move_eye_client\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n# include\n# ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/move_eye_client.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/move_eye_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# catkin_install_python(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_move_eye_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_eye/move_eye_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>move_eye_client</name>\n    <version>1.4.16</version>\n  <description>The move_eye_client package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag -->\n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>BSDv3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/move_eye_client</url> -->\n\n\n  <!-- Author tags are optional, multiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintainers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->\n  <!--   <depend>roscpp</depend> -->\n  <!--   Note that this is equivalent to the following: -->\n  <!--   <build_depend>roscpp</build_depend> -->\n  <!--   <exec_depend>roscpp</exec_depend> -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use build_export_depend for packages you need in order to build against this package: -->\n  <!--   <build_export_depend>message_generation</build_export_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use exec_depend for packages you need at runtime: -->\n  <!--   <exec_depend>message_runtime</exec_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <!-- Use doc_depend for packages you need only for building documentation: -->\n  <!--   <doc_depend>doxygen</doc_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_eye/move_eye_client/src/cl_move_eye.cpp",
    "content": ""
  },
  {
    "path": "smacc_client_library/move_group_interface_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package move_group_interface_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* progress on cubes collisions\n* adding threads to moveit client behaviors\n* some improvements in move_group_interface_client and examples\n* improving sm_moveit\n* improving move it clients known-states and also adding the joint_state_viewer.launch\n* progressing in sm moveit client behavior known states\n* adding some code related with move z client\n* adding set named target moveit_z_clent funcionality\n* Major Merge -> now master is unstable melodic-branch\n* minor improvements in moveit cartesian behaviors\n* progressing in melodic\n* Merge branch 'feature/moving_melodic' into melodic-devel\n* Merge branch 'master' into melodic-devel\n* some changes for melodic\n* some improvements in move_group_interface_client and other fixes\n* fixing smacc_viewer in melodic\n* testing the move joint behaviors\n* refactoring names and fixing broken build\n* progressing in moveit behaviors\n* improving sm_moveit demo\n* fixing functioning in moveit example\n* trying to improve the example\n* fixing broken build\n* refactoring sm_moveit example, and creating library sm_moveit_z\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, pablo.inigo.blasco, pibgeus\n\n* progress on cubes collisions\n* adding threads to moveit client behaviors\n* some improvements in move_group_interface_client and examples\n* improving sm_moveit\n* improving move it clients known-states and also adding the joint_state_viewer.launch\n* progressing in sm moveit client behavior known states\n* adding some code related with move z client\n* adding set named target moveit_z_clent funcionality\n* Major Merge -> now master is unstable melodic-branch\n* minor improvements in moveit cartesian behaviors\n* progressing in melodic\n* Merge branch 'feature/moving_melodic' into melodic-devel\n* Merge branch 'master' into melodic-devel\n* some changes for melodic\n* some improvements in move_group_interface_client and other fixes\n* fixing smacc_viewer in melodic\n* testing the move joint behaviors\n* refactoring names and fixing broken build\n* progressing in moveit behaviors\n* improving sm_moveit demo\n* fixing functioning in moveit example\n* trying to improve the example\n* fixing broken build\n* refactoring sm_moveit example, and creating library sm_moveit_z\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, pablo.inigo.blasco, pibgeus\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(move_group_interface_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc moveit_ros_planning_interface tf)\n#find_package(yaml-cpp REQUIRED)\nset(YAML_CPP_LIBRARIES yaml-cpp)\nfind_package( Threads )\n\n## System dependencies are found with CMake's conventions\nfind_package(Eigen3 REQUIRED)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS} ${YAML_CPP_INCLUDE_DIR}\n  LIBRARIES move_group_interface_client ${YAML_CPP_LIBRARIES}\n  CATKIN_DEPENDS smacc moveit_ros_planning_interface\n  DEPENDS EIGEN3 YAML_CPP\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 17)\nadd_compile_options(-std=c++17) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${EIGEN3_INCLUDE_DIRS}\n ${catkin_INCLUDE_DIRS}\n)\n\n# sources\nfile(GLOB_RECURSE SRC_FILES \"src/*.cpp\") # opcionalmente GLOB\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   ${SRC_FILES}\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/move_group_interface_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n   ${YAML_CPP_LIBRARIES}\n   stdc++fs\n   ${CMAKE_THREAD_LIBS_INIT}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_move_group_interface_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/cl_movegroup.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n//#include <smacc/smacc_client.h>\n//#include <smacc/smacc_signal.h>\n#include <smacc/smacc.h>\n\n#include <moveit/move_group_interface/move_group_interface.h>\n#include <moveit/planning_scene_interface/planning_scene_interface.h>\n#include <geometry_msgs/Vector3.h>\n#include <geometry_msgs/Transform.h>\n\nnamespace cl_move_group_interface\n{\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvMoveGroupMotionExecutionSucceded : sc::event<EvMoveGroupMotionExecutionSucceded<TSource, TOrthogonal>>\n{\n};\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvMoveGroupMotionExecutionFailed : sc::event<EvMoveGroupMotionExecutionFailed<TSource, TOrthogonal>>\n{\n};\n\n/*\nmoveit_msgs/MoveItErrorCodes\n----------------------------\nint32 SUCCESS=1\nint32 FAILURE=99999\nint32 PLANNING_FAILED=-1\nint32 INVALID_MOTION_PLAN=-2\nint32 MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE=-3\nint32 CONTROL_FAILED=-4\nint32 UNABLE_TO_AQUIRE_SENSOR_DATA=-5\nint32 TIMED_OUT=-6\nint32 PREEMPTED=-7\nint32 START_STATE_IN_COLLISION=-10\nint32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-11\nint32 GOAL_IN_COLLISION=-12\nint32 GOAL_VIOLATES_PATH_CONSTRAINTS=-13\nint32 GOAL_CONSTRAINTS_VIOLATED=-14\nint32 INVALID_GROUP_NAME=-15\nint32 INVALID_GOAL_CONSTRAINTS=-16\nint32 INVALID_ROBOT_STATE=-17\nint32 INVALID_LINK_NAME=-18\nint32 INVALID_OBJECT_NAME=-19\nint32 FRAME_TRANSFORM_FAILURE=-21\nint32 COLLISION_CHECKING_UNAVAILABLE=-22\nint32 ROBOT_STATE_STALE=-23\nint32 SENSOR_INFO_STALE=-24\nint32 NO_IK_SOLUTION=-31\nint32 val\n*/\n\nclass ClMoveGroup : public smacc::ISmaccClient\n{\nprivate:\n  std::function<void()> postEventMotionExecutionSucceded_;\n  std::function<void()> postEventMotionExecutionFailed_;\n\n  smacc::SmaccSignal<void()> onSucceded_;\n  smacc::SmaccSignal<void()> onFailed_;\n\npublic:\n  // this structure contains the default move_group configuration for any arm motion through move_group\n  // the client behavior will override these default values in a copy of this object so that their changes\n  // are not persinstent. In the other hand, if you change this client configuration, the parameters will be persistent.\n  moveit::planning_interface::MoveGroupInterface moveGroupClientInterface;\n\n  moveit::planning_interface::PlanningSceneInterface planningSceneInterface;\n\n  ClMoveGroup(std::string groupName);\n\n  virtual ~ClMoveGroup();\n\n  void postEventMotionExecutionSucceded();\n  void postEventMotionExecutionFailed();\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    postEventMotionExecutionSucceded_ = [=]() {\n      this->onSucceded_();\n      this->postEvent<EvMoveGroupMotionExecutionSucceded<TSourceObject, TOrthogonal>>();\n    };\n\n    postEventMotionExecutionFailed_ = [=]() {\n      this->onFailed_();\n      this->postEvent<EvMoveGroupMotionExecutionFailed<TSourceObject, TOrthogonal>>();\n    };\n  }\n\n  template <typename TCallback, typename T>\n  boost::signals2::connection onMotionExecutionSuccedded(TCallback callback, T *object)\n  {\n    return this->getStateMachine()->createSignalConnection(onSucceded_, callback, object);\n  }\n\n  template <typename TCallback, typename T>\n  boost::signals2::connection onMotionExecutionFailed(TCallback callback, T *object)\n  {\n    return this->getStateMachine()->createSignalConnection(onFailed_, callback, object);\n  }\n};\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_attach_object.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc.h>\n#include <move_group_interface_client/cl_movegroup.h>\n\nnamespace cl_move_group_interface\n{\n    class CbAttachObject : public smacc::SmaccClientBehavior\n    {\n    public:\n        CbAttachObject(std::string targetObjectName);\n\n        CbAttachObject();\n\n        virtual void onEntry() override;\n\n        virtual void onExit() override;\n\n        std::string targetObjectName_;\n\n    private:\n    };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_circular_pivot_motion.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_end_effector_trajectory.h\"\n#include \"tf/transform_datatypes.h\"\n#include <tf/transform_listener.h>\n\nnamespace cl_move_group_interface\n{\n    class CbCircularPivotMotion : public CbMoveEndEffectorTrajectory\n    {\n    public:\n        boost::optional<double> angularSpeed_rad_s_;\n        boost::optional<double> linearSpeed_m_s_;\n\n        // if not specified it would be used the current robot pose\n        boost::optional<geometry_msgs::Pose> relativeInitialPose_;\n\n        CbCircularPivotMotion(std::string tipLink = \"\");\n\n        CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, double deltaRadians, std::string tipLink = \"\");\n\n        CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, const geometry_msgs::Pose &relativeInitialPose, double deltaRadians, std::string tipLink = \"\");\n\n        virtual void generateTrajectory() override;\n\n        virtual void createMarkers() override;\n\n    protected:\n        geometry_msgs::PoseStamped planePivotPose_;\n\n        double deltaRadians_;\n\n    private:\n        void computeCurrentEndEffectorPoseRelativeToPivot();\n    };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_detach_object.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc.h>\n#include <move_group_interface_client/components/cp_grasping_objects.h>\n#include <move_group_interface_client/cl_movegroup.h>\n\nnamespace cl_move_group_interface\n{\n    class CbDetachObject : public smacc::SmaccClientBehavior\n    {\n    public:\n        virtual void onEntry() override;\n\n        virtual void onExit() override;\n    };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_end_effector_rotate.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include \"cb_circular_pivot_motion.h\"\n\nnamespace cl_move_group_interface\n{\n    class CbEndEffectorRotate : public CbCircularPivotMotion\n    {\n    public:\n        CbEndEffectorRotate(double deltaRadians, std::string tipLink = \"\");\n        virtual ~CbEndEffectorRotate();\n\n        virtual void onEntry() override;\n    };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_execute_last_trajectory.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n    class CbExecuteLastTrajectory : public CbMoveEndEffectorTrajectory\n    {\n    public:\n        CbExecuteLastTrajectory();\n\n        virtual ~CbExecuteLastTrajectory();\n\n        virtual void onEntry() override;\n    };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_cartesian_relative.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <move_group_interface_client/cl_movegroup.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n\nnamespace cl_move_group_interface\n{\nclass CbMoveCartesianRelative : public smacc::SmaccAsyncClientBehavior\n{\npublic:\n  geometry_msgs::Vector3 offset_;\n\n  boost::optional<double> scalingFactor_;\n\n  boost::optional<std::string> group_;\n\n  CbMoveCartesianRelative();\n\n  CbMoveCartesianRelative(geometry_msgs::Vector3 offset);\n\n  virtual void onEntry() override;\n\n  virtual void onExit() override;\n\n  void moveRelativeCartesian(moveit::planning_interface::MoveGroupInterface *movegroupClient,\n                             geometry_msgs::Vector3 &offset);\n\n  public:\n    ClMoveGroup *moveGroupSmaccClient_;\n};\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_cartesian_relative2.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <move_group_interface_client/cl_movegroup.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <tf/transform_datatypes.h>\n\nnamespace cl_move_group_interface\n{\n    class CbMoveCartesianRelative2 : public CbMoveEndEffectorTrajectory\n    {\n    public:\n        geometry_msgs::Vector3 offset_;\n\n        boost::optional<double> linearSpeed_m_s_;\n\n        CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink)\n            : CbMoveEndEffectorTrajectory(tipLink)\n        {\n            globalFrame_ = referenceFrame;\n        }\n\n        CbMoveCartesianRelative2(std::string referenceFrame, std::string tipLink, geometry_msgs::Vector3 offset)\n            : CbMoveEndEffectorTrajectory(tipLink)\n        {\n            globalFrame_ = referenceFrame;\n            offset_ = offset;\n        }\n\n        virtual void generateTrajectory() override\n        {\n            // at least 1 sample per centimeter (average)\n            const double METERS_PER_SAMPLE = 0.001;\n\n            float dist_meters = 0;\n            tf::Vector3 voffset;\n            tf::vector3MsgToTF(offset_, voffset);\n\n            float totallineardist = voffset.length();\n\n            int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;\n            int steps = totallineardist / METERS_PER_SAMPLE;\n\n            float interpolation_factor_step = 1.0 / totalSamplesCount;\n\n            double secondsPerSample;\n\n            if (!linearSpeed_m_s_)\n            {\n                linearSpeed_m_s_ = 0.1;\n            }\n\n            secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);\n\n            tf::StampedTransform currentEndEffectorTransform;\n\n            this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);\n\n            tf::Transform finalEndEffectorTransform = currentEndEffectorTransform;\n            finalEndEffectorTransform.setOrigin(finalEndEffectorTransform.getOrigin() + voffset);\n\n            float linc = totallineardist / steps; // METERS_PER_SAMPLE with sign\n            float interpolation_factor = 0;\n\n            ros::Time startTime = ros::Time::now();\n\n            for (float i = 0; i < steps; i++)\n            {\n                interpolation_factor += interpolation_factor_step;\n                dist_meters += linc;\n\n                tf::Vector3 vi = currentEndEffectorTransform.getOrigin().lerp(finalEndEffectorTransform.getOrigin(), interpolation_factor);\n\n                tf::Transform pose;\n                pose.setOrigin(vi);\n                pose.setRotation(currentEndEffectorTransform.getRotation());\n\n                geometry_msgs::PoseStamped pointerPose;\n                tf::poseTFToMsg(pose, pointerPose.pose);\n                pointerPose.header.frame_id = globalFrame_;\n                pointerPose.header.stamp = startTime + ros::Duration(i * secondsPerSample);\n\n                this->endEffectorTrajectory_.push_back(pointerPose);\n            }\n\n            ROS_INFO_STREAM(\"[CbMoveEndEffectorRelative2] Target End efector Pose: \" << this->endEffectorTrajectory_.back());\n\n        }\n\n    private:\n        std::string globalFrame_;\n    };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_end_effector.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <move_group_interface_client/cl_movegroup.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <future>\nnamespace cl_move_group_interface\n{\nclass CbMoveEndEffector : public smacc::SmaccAsyncClientBehavior\n{\npublic:\n  geometry_msgs::PoseStamped targetPose;\n  std::string tip_link_;\n  boost::optional<std::string> group_;\n\n  CbMoveEndEffector();\n  CbMoveEndEffector(geometry_msgs::PoseStamped target_pose, std::string tip_link = \"\");\n\n  virtual void onEntry() override;\n\nprotected:\n  bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface,\n                          geometry_msgs::PoseStamped &targetObjectPose);\n\n  ClMoveGroup *movegroupClient_;\n};\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_end_effector_relative.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <move_group_interface_client/cl_movegroup.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n\nnamespace cl_move_group_interface\n{\nclass CbMoveEndEffectorRelative : public smacc::SmaccAsyncClientBehavior\n{\npublic:\n  geometry_msgs::Transform transform_;\n\n  boost::optional<std::string> group_;\n\n  CbMoveEndEffectorRelative();\n\n  CbMoveEndEffectorRelative(geometry_msgs::Transform transform);\n\n  virtual void onEntry() override;\n\n  virtual void onExit() override;\n\nprotected:\n  void moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupinterface,\n                    geometry_msgs::Transform &transformOffset);\n\n  ClMoveGroup *movegroupClient_;\n};\n\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <move_group_interface_client/cl_movegroup.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <tf/transform_datatypes.h>\n\nnamespace cl_move_group_interface\n{\n  template <typename AsyncCB, typename Orthogonal>\n  struct EvJointDiscontinuity : sc::event<EvJointDiscontinuity<AsyncCB, Orthogonal>>\n  {\n    moveit_msgs::RobotTrajectory trajectory;\n  };\n\n  template <typename AsyncCB, typename Orthogonal>\n  struct EvIncorrectInitialPosition : sc::event<EvIncorrectInitialPosition<AsyncCB, Orthogonal>>\n  {\n    moveit_msgs::RobotTrajectory trajectory;\n  };\n\n  enum class ComputeJointTrajectoryErrorCode\n  {\n    SUCCESS,\n    INCORRECT_INITIAL_STATE,\n    JOINT_TRAJECTORY_DISCONTINUITY\n  };\n\n  class CbMoveEndEffectorTrajectory : public smacc::SmaccAsyncClientBehavior,\n                                      public smacc::ISmaccUpdatable\n  {\n  public:\n    // std::string tip_link_;\n    boost::optional<std::string> group_;\n\n    boost::optional<std::string> tipLink_;\n\n    boost::optional<bool> allowInitialTrajectoryStateJointDiscontinuity_;\n\n    CbMoveEndEffectorTrajectory(std::string tipLink = \"\");\n\n    CbMoveEndEffectorTrajectory(const std::vector<geometry_msgs::PoseStamped> &endEffectorTrajectory, std::string tipLink = \"\");\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n      smacc::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n\n      postJointDiscontinuityEvent = [this](auto traj) {\n        auto ev = new EvJointDiscontinuity<TSourceObject, TOrthogonal>();\n        ev->trajectory = traj;\n        this->postEvent(ev);\n      };\n\n      postIncorrectInitialStateEvent = [this](auto traj)\n      {\n        auto ev = new EvIncorrectInitialPosition<TSourceObject, TOrthogonal>();\n        ev->trajectory = traj;\n        this->postEvent(ev);\n      };\n\n      postMotionExecutionFailureEvents = [this]\n      {\n          ROS_INFO_STREAM(\"[\" << this->getName() << \"] motion execution failed\");\n          movegroupClient_->postEventMotionExecutionFailed();\n          this->postEvent<EvMoveGroupMotionExecutionFailed<TSourceObject,TOrthogonal>>();\n      };\n    }\n\n    virtual void onEntry() override;\n\n    virtual void onExit() override;\n\n    virtual void update() override;\n\n  protected:\n    ComputeJointTrajectoryErrorCode computeJointSpaceTrajectory(moveit_msgs::RobotTrajectory &computedJointTrajectory);\n\n    void executeJointSpaceTrajectory(const moveit_msgs::RobotTrajectory &computedJointTrajectory);\n\n    virtual void generateTrajectory();\n\n    virtual void createMarkers();\n\n    std::vector<geometry_msgs::PoseStamped> endEffectorTrajectory_;\n\n    ClMoveGroup *movegroupClient_ = nullptr;\n\n    visualization_msgs::MarkerArray beahiorMarkers_;\n\n    void getCurrentEndEffectorPose(std::string globalFrame, tf::StampedTransform& currentEndEffectorTransform);\n\n  private:\n    void initializeROS();\n\n    ros::Publisher markersPub_;\n\n    std::atomic<bool> markersInitialized_;\n\n    ros::ServiceClient iksrv_;\n\n    std::mutex m_mutex_;\n\n    std::function<void(moveit_msgs::RobotTrajectory &)> postJointDiscontinuityEvent;\n    std::function<void(moveit_msgs::RobotTrajectory &)> postIncorrectInitialStateEvent;\n\n    std::function<void()> postMotionExecutionFailureEvents;\n\n    bool autocleanmarkers = false;\n  };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_joints.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <move_group_interface_client/cl_movegroup.h>\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <map>\n#include <string>\n\nnamespace cl_move_group_interface\n{\nclass CbMoveJoints : public smacc::SmaccAsyncClientBehavior\n{\npublic:\n  boost::optional<double> scalingFactor_;\n  std::map<std::string, double> jointValueTarget_;\n  boost::optional<std::string> group_;\n\n  CbMoveJoints();\n  CbMoveJoints(const std::map<std::string, double> &jointValueTarget);\n  virtual void onEntry() override;\n  virtual void onExit() override;\n\nprotected:\n  void moveJoints(moveit::planning_interface::MoveGroupInterface &moveGroupInterface);\n  ClMoveGroup *movegroupClient_;\n  };\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_joints_relative.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_known_state.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include \"cb_move_joints.h\"\n#include <map>\n#include <string>\n\nnamespace cl_move_group_interface\n{\nclass CbMoveKnownState : public CbMoveJoints\n{\npublic:\n  CbMoveKnownState(std::string pkg, std::string config_path);\n  virtual ~CbMoveKnownState();\n\n  private:\n  static std::map<std::string, double> loadJointStatesFromFile(std::string pkg, std::string filepath);\n};\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_last_trajectory_initial_state.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include \"cb_move_joints.h\"\n\nnamespace cl_move_group_interface\n{\n    class CbMoveLastTrajectoryInitialState : public CbMoveJoints\n    {\n    public:\n        CbMoveLastTrajectoryInitialState();\n\n        CbMoveLastTrajectoryInitialState(int backIndex);\n\n        virtual ~CbMoveLastTrajectoryInitialState();\n\n        virtual void onEntry() override;\n\n    private:\n        int backIndex_ = -1;\n    };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_move_named_target.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#pragma once\n\n#include <smacc/smacc_asynchronous_client_behavior.h>\n#include <move_group_interface_client/cl_movegroup.h>\n#include <map>\n#include <string>\n\nnamespace cl_move_group_interface\n{\n  //named targets are configured in the urdf file\nclass CbMoveNamedTarget : public smacc::SmaccAsyncClientBehavior\n{\nprotected:\n  ClMoveGroup *movegroupClient_;\n  std::string namedTarget_;\n\npublic:\n  CbMoveNamedTarget(std::string namedtarget);\n\n  virtual void onEntry() override;\n\n  virtual void onExit() override;\n\n  std::map<std::string, double> getNamedTargetValues();\n};\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_pouring_motion.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include \"cb_move_end_effector_trajectory.h\"\n#include \"tf/transform_datatypes.h\"\n#include <tf/transform_listener.h>\n\nnamespace cl_move_group_interface\n{\n    class CbCircularPouringMotion : public CbMoveEndEffectorTrajectory\n    {\n    public:\n        boost::optional<double> angularSpeed_rad_s_;\n\n        boost::optional<double> linearSpeed_m_s_;\n\n        CbCircularPouringMotion(const geometry_msgs::Point &pivotPoint, double deltaHeight, std::string tipLink , std::string globalFrame);\n\n        virtual void generateTrajectory() override;\n\n        virtual void createMarkers() override;\n\n        geometry_msgs::Vector3 directionVector_;\n\n        // relative position of the \"lid\" of the bottle in the end effector reference frame.\n        // that point is the one that must do the linear motion\n        geometry_msgs::Pose pointerRelativePose_;\n    protected:\n        geometry_msgs::Point relativePivotPoint_;\n\n        // distance in meters from the initial pose to the bottom/top direction in z axe\n        double deltaHeight_;\n\n        std::vector<geometry_msgs::PoseStamped> pointerTrajectory_;\n\n    private:\n        void computeCurrentEndEffectorPoseRelativeToPivot();\n\n        std::string globalFrame_;\n    };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors/cb_undo_last_trajectory.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n    class CbUndoLastTrajectory : public CbMoveEndEffectorTrajectory\n    {\n    public:\n        CbUndoLastTrajectory();\n\n        CbUndoLastTrajectory(int backIndex);\n\n        virtual ~CbUndoLastTrajectory();\n\n        virtual void onEntry() override;\n    private:\n        int backIndex_ = -1;\n\n        moveit_msgs::RobotTrajectory trajectory;\n        moveit_msgs::RobotTrajectory reversed;\n    };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/client_behaviors.h",
    "content": "#pragma once\n\n// BASIC MANIPULATION BEHAVIORS\n#include \"client_behaviors/cb_move_end_effector.h\"\n#include \"client_behaviors/cb_move_end_effector_relative.h\"\n#include \"client_behaviors/cb_move_cartesian_relative.h\"\n#include \"client_behaviors/cb_move_joints.h\"\n#include \"client_behaviors/cb_move_known_state.h\"\n#include \"client_behaviors/cb_move_named_target.h\"\n\n// ADVANCED MANIPULATION BEHAVIORS\n#include \"client_behaviors/cb_move_end_effector_trajectory.h\"\n#include \"client_behaviors/cb_circular_pivot_motion.h\"\n#include \"client_behaviors/cb_end_effector_rotate.h\"\n#include \"client_behaviors/cb_pouring_motion.h\"\n#include \"client_behaviors/cb_move_cartesian_relative2.h\"\n\n// HISTORY BASED BEHAVIRORS\n#include \"client_behaviors/cb_move_last_trajectory_initial_state.h\"\n#include \"client_behaviors/cb_execute_last_trajectory.h\"\n#include \"client_behaviors/cb_undo_last_trajectory.h\"\n\n// GRASPING BEHAVIORS\n#include \"client_behaviors/cb_attach_object.h\"\n#include \"client_behaviors/cb_detach_object.h\"\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/components/cp_grasping_objects.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <smacc/component.h>\n#include <moveit_msgs/CollisionObject.h>\n#include <map>\n\nnamespace cl_move_group_interface\n{\n   class GraspingComponent : public smacc::ISmaccComponent\n   {\n   private:\n      std::map<std::string, moveit_msgs::CollisionObject> graspingObjects;\n\n   public:\n      std::vector<std::string> fingerTipNames;\n\n      boost::optional<std::string> currentAttachedObjectName;\n\n      bool getGraspingObject(std::string name, moveit_msgs::CollisionObject &object);\n\n      void createGraspableBox(std::string frameid, float x, float y, float z, float xl, float yl, float zl);\n   };\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/components/cp_tf_listener.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/component.h>\n#include <smacc/smacc_updatable.h>\n\n#include <geometry_msgs/Pose.h>\n#include <tf/transform_listener.h>\n#include <tf/transform_datatypes.h>\n#include <mutex>\n#include <thread>\n\nnamespace cl_move_base_z\n{\n    struct TfPoseTrack\n    {\n        std::mutex mutex_;\n        geometry_msgs::PoseStamped pose_;\n        std::string targetPoseFrame_;\n        std::string referenceBaseFrame_;\n        bool once = true;\n        bool isInitialized = false;\n    };\n\n    class CpTFListener : public smacc::ISmaccComponent, public smacc::ISmaccUpdatable\n    {\n    public:\n        CpTFListener();\n\n        virtual void update() override\n        {\n            for(auto& poseTrack: poseTracks_)\n            {\n                tf::StampedTransform transform;\n                try\n                {\n                    {\n                        std::lock_guard<std::mutex> lock(listenerMutex_);\n                        tfListener_->lookupTransform(poseTrack->referenceBaseFrame_,poseTrack->targetPoseFrame_,\n                                                    ros::Time(0), transform);\n                    }\n\n                    {\n                        std::lock_guard<std::mutex> guard(m_mutex_);\n                        tf::poseTFToMsg(transform, poseTrack->pose_.pose);\n                        poseTrack->pose_.header.stamp = transform.stamp_;\n                        poseTrack->pose_.header.frame_id = poseTrack->referenceBaseFrame_;\n                        poseTrack->isInitialized = true;\n                    }\n                }\n                catch (tf::TransformException ex)\n                {\n                    ROS_ERROR_STREAM_THROTTLE(1, \"[Component pose] (\" << poseFrameName_ << \"/[\" << referenceFrame_ << \"] ) is failing on pose update : \" << ex.what());\n                }\n            }\n        }\n\n        void getLastTransform(std::string &targetPoseFrameName, std::string &referenceBaseFrame, geometry_msgs::Pose &out)\n        {\n        }\n\n        std::future<geometry_msgs::Pose> waitForNextTransform(std::string &targetName, std::string &referenceBaseFrame)\n        {\n            tracks_\n        }\n\n    private:\n        static std::shared_ptr<tf::TransformListener> tfListener_;\n        static std::mutex listenerMutex_;\n\n        std::mutex m_mutex_;\n        std::list<std::shared_ptr<TfPoseTrack>> poseTracks_;\n    };\n} // namespace cl_move_base_z\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/include/move_group_interface_client/components/cp_trajectory_history.h",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#pragma once\n\n#include <smacc/component.h>\n\n#include <moveit_msgs/RobotTrajectory.h>\n#include <moveit_msgs/MoveItErrorCodes.h>\n\nnamespace cl_move_group_interface\n{\n\n    struct TrajectoryHistoryEntry\n    {\n        moveit_msgs::RobotTrajectory trajectory;\n        moveit_msgs::MoveItErrorCodes result;\n        std::string name;\n    };\n\n    class CpTrajectoryHistory : public smacc::ISmaccComponent\n    {\n\n    public:\n        bool getLastTrajectory(int backIndex, moveit_msgs::RobotTrajectory &trajectory);\n\n        bool getLastTrajectory(moveit_msgs::RobotTrajectory &trajectory);\n\n        void pushTrajectory(std::string name, const moveit_msgs::RobotTrajectory &trajectory, moveit_msgs::MoveItErrorCodes result);\n\n    private:\n        std::vector<TrajectoryHistoryEntry> trajectoryHistory_;\n    };\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>move_group_interface_client</name>\n    <version>1.4.16</version>\n  <description>The move_group_interface_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/move_group_interface_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>smacc</depend>\n  <depend>moveit</depend>\n  <depend>tf</depend>\n  <depend>moveit_ros_planning_interface</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/cl_movegroup.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/cl_movegroup.h>\nnamespace cl_move_group_interface\n{\n\nClMoveGroup::ClMoveGroup(std::string groupName)\n    : moveGroupClientInterface(groupName)\n{\n    ros::WallDuration(10.0).sleep();\n}\n\nClMoveGroup::~ClMoveGroup()\n{\n}\n\nvoid ClMoveGroup::postEventMotionExecutionSucceded()\n{\n    ROS_INFO(\"[ClMoveGroup] Post Motion Success Event\");\n    postEventMotionExecutionSucceded_();\n}\n\nvoid ClMoveGroup::postEventMotionExecutionFailed()\n{\n    ROS_INFO(\"[ClMoveGroup] Post Motion Failure Event\");\n    postEventMotionExecutionFailed_();\n}\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_attach_object.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_attach_object.h>\n#include <move_group_interface_client/components/cp_grasping_objects.h>\n\nnamespace cl_move_group_interface\n{\n    CbAttachObject::CbAttachObject(std::string targetObjectName)\n        : targetObjectName_(targetObjectName)\n    {\n    }\n\n    CbAttachObject::CbAttachObject()\n    {\n        }\n\n    void CbAttachObject::onEntry()\n    {\n        cl_move_group_interface::ClMoveGroup *moveGroup;\n        this->requiresClient(moveGroup);\n\n        cl_move_group_interface::GraspingComponent *graspingComponent;\n        this->requiresComponent(graspingComponent);\n\n        // auto cubepos = cubeinfo->pose_->toPoseStampedMsg();\n\n        moveit_msgs::CollisionObject targetCollisionObject;\n\n        bool found = graspingComponent->getGraspingObject(targetObjectName_, targetCollisionObject);\n\n        if (found)\n        {\n            targetCollisionObject.operation = moveit_msgs::CollisionObject::ADD;\n            targetCollisionObject.header.stamp = ros::Time::now();\n\n            moveGroup->planningSceneInterface.applyCollisionObject(targetCollisionObject);\n            // collisionObjects.push_back(cubeCollision);\n\n            graspingComponent->currentAttachedObjectName = targetObjectName_;\n            moveGroup->moveGroupClientInterface.attachObject(targetObjectName_, \"gripper_link\", graspingComponent->fingerTipNames);\n        }\n    }\n\n    void CbAttachObject::onExit()\n    {\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_circular_pivot_motion.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_circular_pivot_motion.h>\n\nnamespace cl_move_group_interface\n{\n    CbCircularPivotMotion::CbCircularPivotMotion(std::string tipLink)\n        : CbMoveEndEffectorTrajectory(tipLink)\n    {\n    }\n\n    CbCircularPivotMotion::CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, double deltaRadians, std::string tipLink)\n        : planePivotPose_(planePivotPose), deltaRadians_(deltaRadians), CbMoveEndEffectorTrajectory(tipLink)\n    {\n    }\n\n    CbCircularPivotMotion::CbCircularPivotMotion(const geometry_msgs::PoseStamped &planePivotPose, const geometry_msgs::Pose &relativeInitialPose, double deltaRadians, std::string tipLink)\n        : planePivotPose_(planePivotPose), relativeInitialPose_(relativeInitialPose), deltaRadians_(deltaRadians), CbMoveEndEffectorTrajectory(tipLink)\n    {\n    }\n\n    void CbCircularPivotMotion::generateTrajectory()\n    {\n        if (!relativeInitialPose_)\n        {\n            this->computeCurrentEndEffectorPoseRelativeToPivot();\n        }\n\n        // project offset into the xy-plane\n        // get the radius\n        double radius = sqrt(relativeInitialPose_->position.z * relativeInitialPose_->position.z + relativeInitialPose_->position.y * relativeInitialPose_->position.y);\n        double initialAngle = atan2(relativeInitialPose_->position.z, relativeInitialPose_->position.y);\n\n        double totallineardist = fabs(radius * deltaRadians_);\n        double totalangulardist = fabs(deltaRadians_);\n\n        // at least 1 sample per centimeter (average)\n        // at least 1 sample per ~1.1 degrees (average)\n\n        const double RADS_PER_SAMPLE = 0.02;\n        const double METERS_PER_SAMPLE = 0.01;\n\n        int totalSamplesCount = std::max(totallineardist / METERS_PER_SAMPLE, totalangulardist / RADS_PER_SAMPLE);\n\n        double linearSecondsPerSample;\n        double angularSecondsPerSamples;\n        double secondsPerSample;\n\n        if (linearSpeed_m_s_)\n        {\n            linearSecondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);\n        }\n        else\n        {\n            linearSecondsPerSample = std::numeric_limits<double>::max();\n        }\n\n        if (angularSpeed_rad_s_)\n        {\n            angularSecondsPerSamples = RADS_PER_SAMPLE / (*angularSpeed_rad_s_);\n        }\n        else\n        {\n            angularSecondsPerSamples = std::numeric_limits<double>::max();\n        }\n\n        if (!linearSpeed_m_s_ && !angularSpeed_rad_s_)\n        {\n            secondsPerSample = 0.5;\n        }\n        else\n        {\n            secondsPerSample = std::min(linearSecondsPerSample, angularSecondsPerSamples);\n        }\n\n        double currentAngle = initialAngle;\n\n        double angleStep = deltaRadians_ / (double)totalSamplesCount;\n\n        tf::Transform tfBasePose;\n        tf::poseMsgToTF(planePivotPose_.pose, tfBasePose);\n\n        for (int i = 0; i < totalSamplesCount; i++)\n        {\n            // relativePose i\n            currentAngle += angleStep;\n            double y = radius * cos(currentAngle);\n            double z = radius * sin(currentAngle);\n\n            geometry_msgs::Pose relativeCurrentPose;\n\n            relativeCurrentPose.position.x = relativeInitialPose_->position.x;\n            relativeCurrentPose.position.y = y;\n            relativeCurrentPose.position.z = z;\n\n            auto localquat = tf::createQuaternionFromRPY(currentAngle, 0, 0);\n            //relativeCurrentPose.orientation = relativeInitialPose_.orientation;\n            //tf::quaternionTFToMsg(localquat, relativeCurrentPose.orientation);\n            relativeCurrentPose.orientation.w = 1;\n\n            tf::Transform tfRelativeCurrentPose;\n            tf::poseMsgToTF(relativeCurrentPose, tfRelativeCurrentPose);\n\n            tf::Transform tfGlobalPose = tfRelativeCurrentPose * tfBasePose;\n\n            tfGlobalPose.setRotation(tfGlobalPose.getRotation() * localquat);\n\n            geometry_msgs::PoseStamped globalPose;\n            tf::poseTFToMsg(tfGlobalPose, globalPose.pose);\n            globalPose.header.frame_id = planePivotPose_.header.frame_id;\n            globalPose.header.stamp = planePivotPose_.header.stamp + ros::Duration(i * secondsPerSample);\n\n            this->endEffectorTrajectory_.push_back(globalPose);\n        }\n    }\n\n    void CbCircularPivotMotion::computeCurrentEndEffectorPoseRelativeToPivot()\n    {\n        //auto currentRobotEndEffectorPose = this->movegroupClient_->moveGroupClientInterface.getCurrentPose();\n\n        tf::TransformListener tfListener;\n        // tf::StampedTransform globalBaseLink;\n        tf::StampedTransform endEffectorInPivotFrame;\n\n        try\n        {\n            if (!tipLink_ || *tipLink_ == \"\")\n            {\n                tipLink_ = this->movegroupClient_->moveGroupClientInterface.getEndEffectorLink();\n            }\n\n            tfListener.waitForTransform(planePivotPose_.header.frame_id, *tipLink_, ros::Time(0), ros::Duration(10));\n            tfListener.lookupTransform(planePivotPose_.header.frame_id, *tipLink_, ros::Time(0), endEffectorInPivotFrame);\n\n            // we define here the global frame as the pivot frame id\n            // tfListener.waitForTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), ros::Duration(10));\n            // tfListener.lookupTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), globalBaseLink);\n        }\n        catch (const std::exception &e)\n        {\n            std::cerr << e.what() << '\\n';\n        }\n\n        // tf::Transform endEffectorInBaseLinkFrame;\n        // tf::poseMsgToTF(currentRobotEndEffectorPose.pose, endEffectorInBaseLinkFrame);\n\n        // tf::Transform endEffectorInPivotFrame = globalBaseLink * endEffectorInBaseLinkFrame; // pose composition\n\n        // now pivot and EndEffector share a common reference frame (let say map)\n        // now get the current pose from the pivot reference frame with inverse composition\n        tf::Transform pivotTransform;\n        tf::poseMsgToTF(planePivotPose_.pose, pivotTransform);\n        tf::Transform invertedNewReferenceFrame = pivotTransform.inverse();\n\n        tf::Transform currentPoseRelativeToPivot = invertedNewReferenceFrame * endEffectorInPivotFrame;\n\n        geometry_msgs::Pose finalEndEffectorRelativePose;\n        tf::poseTFToMsg(currentPoseRelativeToPivot, finalEndEffectorRelativePose);\n        relativeInitialPose_ = finalEndEffectorRelativePose;\n    }\n\n    void CbCircularPivotMotion::createMarkers()\n    {\n        CbMoveEndEffectorTrajectory::createMarkers();\n\n        tf::Transform localdirection;\n        localdirection.setIdentity();\n        localdirection.setOrigin(tf::Vector3(0.12, 0, 0));\n        auto frameid = planePivotPose_.header.frame_id;\n\n        visualization_msgs::Marker marker;\n        marker.header.frame_id = frameid;\n        marker.header.stamp = ros::Time::now();\n        marker.ns = \"trajectory\";\n        marker.id = beahiorMarkers_.markers.size();\n        marker.type = visualization_msgs::Marker::ARROW;\n        marker.action = visualization_msgs::Marker::ADD;\n        marker.scale.x = 0.01;\n        marker.scale.y = 0.02;\n        marker.scale.z = 0.02;\n        marker.color.a = 1.0;\n        marker.color.r = 0.0;\n        marker.color.g = 0;\n        marker.color.b = 1.0;\n\n        geometry_msgs::Point start, end;\n        start.x = planePivotPose_.pose.position.x;\n        start.y = planePivotPose_.pose.position.y;\n        start.z = planePivotPose_.pose.position.z;\n\n        tf::Transform basetransform;\n        tf::poseMsgToTF(planePivotPose_.pose, basetransform);\n        tf::Transform endarrow = localdirection * basetransform;\n\n        end.x = endarrow.getOrigin().x();\n        end.y = endarrow.getOrigin().y();\n        end.z = endarrow.getOrigin().z();\n\n        marker.pose.orientation.w = 1;\n        marker.points.push_back(start);\n        marker.points.push_back(end);\n\n        beahiorMarkers_.markers.push_back(marker);\n    }\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_detach_object.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_detach_object.h>\n#include <move_group_interface_client/cl_movegroup.h>\n\nnamespace cl_move_group_interface\n{\n    void CbDetachObject::onEntry()\n    {\n        cl_move_group_interface::GraspingComponent *graspingComponent;\n        this->requiresComponent(graspingComponent);\n\n        cl_move_group_interface::ClMoveGroup *moveGroupClient;\n        this->requiresClient(moveGroupClient);\n\n        auto &planningSceneInterface = moveGroupClient->planningSceneInterface;\n\n        moveGroupClient->moveGroupClientInterface.detachObject(*(graspingComponent->currentAttachedObjectName));\n        planningSceneInterface.removeCollisionObjects({*(graspingComponent->currentAttachedObjectName)});\n    }\n\n    void CbDetachObject::onExit()\n    {\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_end_effector_rotate.cpp",
    "content": "#include <move_group_interface_client/client_behaviors/cb_end_effector_rotate.h>\n\nnamespace cl_move_group_interface\n{\n    CbEndEffectorRotate::CbEndEffectorRotate(double deltaRadians, std::string tipLink)\n        : CbCircularPivotMotion(tipLink)\n    {\n        deltaRadians_ = deltaRadians;\n    }\n\n    CbEndEffectorRotate::~CbEndEffectorRotate()\n    {\n\n    }\n\n    void CbEndEffectorRotate::onEntry()\n    {\n        // autocompute pivot pose\n\n        tf::TransformListener tfListener;\n        // tf::StampedTransform globalBaseLink;\n        tf::StampedTransform endEffectorInPivotFrame;\n\n        int attempts = 3;\n\n        while (attempts > 0)\n        {\n            try\n            {\n                this->requiresClient(movegroupClient_);\n                if (!tipLink_ || *tipLink_ == \"\")\n                {\n                    tipLink_ = this->movegroupClient_->moveGroupClientInterface.getEndEffectorLink();\n                }\n\n                auto pivotFrame = this->movegroupClient_->moveGroupClientInterface.getPlanningFrame();\n\n                tf::StampedTransform endEffectorInPivotFrame;\n\n                tfListener.waitForTransform(pivotFrame, *tipLink_, ros::Time(0), ros::Duration(10));\n                tfListener.lookupTransform(pivotFrame, *tipLink_, ros::Time(0), endEffectorInPivotFrame);\n\n                tf::poseTFToMsg(endEffectorInPivotFrame, this->planePivotPose_.pose);\n                this->planePivotPose_.header.frame_id = endEffectorInPivotFrame.frame_id_;\n                this->planePivotPose_.header.stamp = endEffectorInPivotFrame.stamp_;\n                break;\n            }\n            catch (const std::exception &e)\n            {\n                ROS_ERROR_STREAM(e.what() << \". Attempt countdown: \" << attempts);\n                ros::Duration(0.5);\n                attempts--;\n            }\n        }\n\n        CbCircularPivotMotion::onEntry();\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_execute_last_trajectory.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_group_interface_client/client_behaviors/cb_execute_last_trajectory.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n    CbExecuteLastTrajectory::CbExecuteLastTrajectory()\n    {\n    }\n\n    CbExecuteLastTrajectory::~CbExecuteLastTrajectory()\n    {\n\n    }\n\n    void CbExecuteLastTrajectory::onEntry()\n    {\n        this->requiresClient(movegroupClient_);\n\n        CpTrajectoryHistory *trajectoryHistory;\n        this->requiresComponent(trajectoryHistory);\n\n        // this->generateTrajectory();\n        // endEffectorTrajectory_ =\n\n        // if (this->endEffectorTrajectory_.size() == 0)\n        // {\n        //     ROS_WARN_STREAM(\"[\" << smacc::demangleSymbol(typeid(*this).name()) << \"] No points in the trajectory. Skipping behavior.\");\n        //     return;\n        // }\n\n        //this->createMarkers();\n        //markersInitialized_ = true;\n\n        moveit_msgs::RobotTrajectory trajectory;\n\n        if (trajectoryHistory->getLastTrajectory(trajectory))\n        {\n            this->executeJointSpaceTrajectory(trajectory);\n        }\n    }\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_cartesian_relative.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_cartesian_relative.h>\n\nnamespace cl_move_group_interface\n{\nCbMoveCartesianRelative::CbMoveCartesianRelative()\n{\n}\n\nCbMoveCartesianRelative::CbMoveCartesianRelative(geometry_msgs::Vector3 offset) : offset_(offset)\n{\n}\n\nvoid CbMoveCartesianRelative::onEntry()\n{\n  this->requiresClient(moveGroupSmaccClient_);\n\n  if (this->group_)\n  {\n      moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));\n      this->moveRelativeCartesian(&move_group, offset_);\n  }\n  else\n  {\n      this->moveRelativeCartesian(&moveGroupSmaccClient_->moveGroupClientInterface, offset_);\n  }\n}\n\nvoid CbMoveCartesianRelative::onExit()\n{\n\n}\n\n// keeps the end efector orientation fixed\nvoid CbMoveCartesianRelative::moveRelativeCartesian(moveit::planning_interface::MoveGroupInterface *movegroupClient,\n                                                    geometry_msgs::Vector3 &offset)\n{\n  std::vector<geometry_msgs::Pose> waypoints;\n\n  // this one was working fine but the issue is that for relative motions it grows up on ABORT-State-Loop pattern.\n  // But, we need current pose because maybe setCurrentPose was not set by previous behaviors. The only solution would be\n  // distinguishing between the execution error and the planning error with no state change\n  //auto referenceStartPose = movegroupClient->getPoseTarget();\n  auto referenceStartPose = movegroupClient->getCurrentPose();\n  movegroupClient->setPoseReferenceFrame(referenceStartPose.header.frame_id);\n\n  ROS_INFO_STREAM(\"[CbMoveCartesianRelative] RELATIVE MOTION, SOURCE POSE: \" << referenceStartPose);\n  ROS_INFO_STREAM(\"[CbMoveCartesianRelative] Offset: \" << offset);\n\n  waypoints.push_back(referenceStartPose.pose);  // up and out\n\n  auto endPose = referenceStartPose.pose;\n\n  endPose.position.x += offset.x;\n  endPose.position.y += offset.y;\n  endPose.position.z += offset.z;\n\n  ROS_INFO_STREAM(\"[CbMoveCartesianRelative] DESTINY POSE: \" << endPose);\n\n  // target_pose2.position.x -= 0.15;\n  waypoints.push_back(endPose);  // left\n\n  movegroupClient->setPoseTarget(endPose);\n\n  float scalinf = 0.5;\n  if (scalingFactor_)\n    scalinf = *scalingFactor_;\n\n  ROS_INFO_STREAM(\"[CbMoveCartesianRelative] Using scaling factor: \" << scalinf);\n  movegroupClient->setMaxVelocityScalingFactor(scalinf);\n\n  moveit_msgs::RobotTrajectory trajectory;\n  double fraction = movegroupClient->computeCartesianPath(waypoints,\n                                                          0.01,  // eef_step\n                                                          0.00,  // jump_threshold\n                                                          trajectory);\n\n  moveit::core::MoveItErrorCode behaviorResult;\n  if (fraction != 1.0 || fraction == -1)\n  {\n    ROS_WARN_STREAM(\"[CbMoveCartesianRelative] Cartesian plan joint-continuity percentaje. Execution skipped because not 100% of cartesian motion: \" << fraction*100<<\"%\");\n    behaviorResult = moveit::core::MoveItErrorCode::PLANNING_FAILED;\n  }\n  else\n  {\n    ROS_INFO_STREAM(\"[CbMoveCartesianRelative] Cartesian plan joint-continuity percentaje: \" << fraction);\n\n    moveit::planning_interface::MoveGroupInterface::Plan grasp_pose_plan;\n\n    // grasp_pose_plan.start_state_ = *(moveGroupInterface.getCurrentState());\n    grasp_pose_plan.trajectory_ = trajectory;\n    behaviorResult = movegroupClient->execute(grasp_pose_plan);\n  }\n\n  if (behaviorResult == moveit_msgs::MoveItErrorCodes::SUCCESS)\n  {\n    ROS_INFO(\"[CbMoveCartesianRelative] relative motion execution succeeded: fraction %lf.\", fraction);\n    moveGroupSmaccClient_->postEventMotionExecutionSucceded();\n    this->postSuccessEvent();\n  }\n  else\n  {\n    movegroupClient->setPoseTarget(referenceStartPose); // undo changes since we did not executed the motion\n    ROS_INFO(\"[CbMoveCartesianRelative] relative motion execution failed: fraction %lf.\", fraction);\n    moveGroupSmaccClient_->postEventMotionExecutionFailed();\n    this->postFailureEvent();\n  }\n}\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_end_effector.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_end_effector.h>\n// #include <moveit/kinematic_constraints/kinematic_constraint.h>\n#include <moveit/kinematic_constraints/utils.h>\n#include <future>\n\nnamespace cl_move_group_interface\n{\nCbMoveEndEffector::CbMoveEndEffector()\n{\n}\n\nCbMoveEndEffector::CbMoveEndEffector(geometry_msgs::PoseStamped target_pose, std::string tip_link)\n  : targetPose(target_pose)\n{\n  tip_link_ = tip_link;\n}\n\nvoid CbMoveEndEffector::onEntry()\n{\n  this->requiresClient(movegroupClient_);\n\n  if (this->group_)\n  {\n      ROS_DEBUG(\"[CbMoveEndEfector] new thread started to move absolute end effector\");\n      moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));\n      this->moveToAbsolutePose(move_group, targetPose);\n      ROS_DEBUG(\"[CbMoveEndEfector] to move absolute end effector thread destroyed\");\n  }\n  else\n  {\n      ROS_DEBUG(\"[CbMoveEndEfector] new thread started to move absolute end effector\");\n      this->moveToAbsolutePose(movegroupClient_->moveGroupClientInterface, targetPose);\n      ROS_DEBUG(\"[CbMoveEndEfector] to move absolute end effector thread destroyed\");\n  }\n}\n\nbool CbMoveEndEffector::moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface,\n                                           geometry_msgs::PoseStamped &targetObjectPose)\n{\n  auto& planningSceneInterface = movegroupClient_->planningSceneInterface;\n  ROS_DEBUG(\"[CbMoveEndEffector] Synchronous sleep of 1 seconds\");\n  ros::Duration(0.5).sleep();\n\n  moveGroupInterface.setPlanningTime(1.0);\n\n  ROS_INFO_STREAM(\"[CbMoveEndEffector] Target End efector Pose: \" << targetObjectPose);\n\n  moveGroupInterface.setPoseTarget(targetObjectPose, tip_link_);\n  moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);\n\n  moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;\n  bool success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);\n  ROS_INFO_NAMED(\"CbMoveEndEffector\", \"Success Visualizing plan 1 (pose goal) %s\", success ? \"\" : \"FAILED\");\n\n  if (success)\n  {\n    auto executionResult = moveGroupInterface.execute(computedMotionPlan);\n\n    if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)\n    {\n      ROS_INFO(\"[CbMoveEndEffector] motion execution succeeded\");\n      movegroupClient_->postEventMotionExecutionSucceded();\n      this->postSuccessEvent();\n\n    }\n    else\n    {\n      ROS_INFO(\"[CbMoveEndEffector] motion execution failed\");\n      movegroupClient_->postEventMotionExecutionFailed();\n      this->postFailureEvent();\n    }\n  }\n  else\n  {\n    ROS_INFO(\"[CbMoveEndEffector] motion execution failed\");\n    movegroupClient_->postEventMotionExecutionFailed();\n    this->postFailureEvent();\n  }\n\n  ROS_DEBUG(\"[CbMoveEndEffector] Synchronous sleep of 1 seconds\");\n  ros::Duration(0.5).sleep();\n\n  return success;\n}\n\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_end_effector_relative.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_end_effector_relative.h>\n#include <tf/tf.h>\n#include <tf/transform_datatypes.h>\n#include <future>\n\nnamespace cl_move_group_interface\n{\n    CbMoveEndEffectorRelative::CbMoveEndEffectorRelative()\n    {\n        transform_.rotation.w = 1;\n    }\n\n    CbMoveEndEffectorRelative::CbMoveEndEffectorRelative(geometry_msgs::Transform transform)\n    {\n    }\n\n    void CbMoveEndEffectorRelative::onEntry()\n    {\n        ROS_INFO_STREAM(\"[CbMoveEndEffectorRelative] Transform end effector pose relative: \" << transform_);\n\n        this->requiresClient(movegroupClient_);\n\n        if (this->group_)\n        {\n            moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));\n            this->moveRelative(move_group, this->transform_);\n        }\n        else\n        {\n            this->moveRelative(movegroupClient_->moveGroupClientInterface, this->transform_);\n        }\n    }\n\n    void CbMoveEndEffectorRelative::onExit()\n    {\n    }\n\n    void CbMoveEndEffectorRelative::moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::Transform &transformOffset)\n    {\n        auto referenceStartPose = moveGroupInterface.getCurrentPose();\n        tf::Quaternion currentOrientation;\n        tf::quaternionMsgToTF(referenceStartPose.pose.orientation, currentOrientation);\n        tf::Quaternion desiredRelativeRotation;\n\n        tf::quaternionMsgToTF(transformOffset.rotation, desiredRelativeRotation);\n\n        auto targetOrientation = desiredRelativeRotation * currentOrientation;\n\n        geometry_msgs::PoseStamped targetObjectPose = referenceStartPose;\n\n        tf::quaternionTFToMsg(targetOrientation, targetObjectPose.pose.orientation);\n        targetObjectPose.pose.position.x += transformOffset.translation.x;\n        targetObjectPose.pose.position.y += transformOffset.translation.y;\n        targetObjectPose.pose.position.z += transformOffset.translation.z;\n\n        moveGroupInterface.setPlanningTime(1.0);\n\n        ROS_INFO_STREAM(\"[CbMoveEndEffectorRelative] Target End efector Pose: \" << targetObjectPose);\n\n        moveGroupInterface.setPoseTarget(targetObjectPose);\n        moveGroupInterface.setPoseReferenceFrame(\"map\");\n\n        moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;\n        bool success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);\n        ROS_INFO_NAMED(\"CbMoveEndEffectorRelative\", \"Success Visualizing plan 1 (pose goal) %s\", success ? \"\" : \"FAILED\");\n\n        if (success)\n        {\n            auto executionResult = moveGroupInterface.execute(computedMotionPlan);\n\n            if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)\n            {\n                ROS_INFO(\"[CbMoveEndEffectorRelative] motion execution succeeded\");\n                movegroupClient_->postEventMotionExecutionSucceded();\n                this->postSuccessEvent();\n            }\n            else\n            {\n                moveGroupInterface.setPoseTarget(referenceStartPose); // undo to avoid abort-repeat state issues with this relative motion\n                ROS_INFO(\"[CbMoveEndEffectorRelative] motion execution failed\");\n                movegroupClient_->postEventMotionExecutionFailed();\n                this->postFailureEvent();\n            }\n        }\n        else\n        {\n            moveGroupInterface.setPoseTarget(referenceStartPose); //undo since we did not executed the motion\n            ROS_INFO(\"[CbMoveEndEffectorRelative] motion execution failed\");\n            movegroupClient_->postEventMotionExecutionFailed();\n            this->postFailureEvent();\n        }\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_end_effector_trajectory.h>\n#include <moveit_msgs/GetPositionIK.h>\n#include <visualization_msgs/MarkerArray.h>\n#include <tf/transform_datatypes.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n#include <tf/transform_listener.h>\n\nnamespace cl_move_group_interface\n{\n    CbMoveEndEffectorTrajectory::CbMoveEndEffectorTrajectory(std::string tipLink)\n        : tipLink_(tipLink), markersInitialized_(false)\n    {\n        initializeROS();\n    }\n\n    CbMoveEndEffectorTrajectory::CbMoveEndEffectorTrajectory(const std::vector<geometry_msgs::PoseStamped> &endEffectorTrajectory, std::string tipLink)\n        : endEffectorTrajectory_(endEffectorTrajectory), tipLink_(tipLink), markersInitialized_(false)\n\n    {\n        initializeROS();\n    }\n\n    void CbMoveEndEffectorTrajectory::initializeROS()\n    {\n        ros::NodeHandle nh;\n        markersPub_ = nh.advertise<visualization_msgs::MarkerArray>(\"trajectory_markers\", 1);\n        iksrv_ = nh.serviceClient<moveit_msgs::GetPositionIK>(\"/compute_ik\");\n    }\n\n    ComputeJointTrajectoryErrorCode CbMoveEndEffectorTrajectory::computeJointSpaceTrajectory(moveit_msgs::RobotTrajectory &computedJointTrajectory)\n    {\n        // get current robot state\n        auto currentState = movegroupClient_->moveGroupClientInterface.getCurrentState();\n\n        // get the IK client\n        auto groupname = movegroupClient_->moveGroupClientInterface.getName();\n        auto currentjointnames = currentState->getJointModelGroup(groupname)->getActiveJointModelNames();\n\n        if (!tipLink_ || *tipLink_ == \"\")\n        {\n            tipLink_ = movegroupClient_->moveGroupClientInterface.getEndEffectorLink();\n        }\n\n        std::vector<double> jointPositions;\n        currentState->copyJointGroupPositions(groupname, jointPositions);\n\n        std::vector<std::vector<double>> trajectory;\n        std::vector<ros::Duration> trajectoryTimeStamps;\n\n        trajectory.push_back(jointPositions);\n        trajectoryTimeStamps.push_back(ros::Duration(0));\n\n        auto &first = endEffectorTrajectory_.front();\n        ros::Time referenceTime = first.header.stamp;\n\n        std::vector<int> discontinuityIndexes;\n\n        int ikAttempts = 4;\n        for (int k = 0; k < this->endEffectorTrajectory_.size(); k++)\n        {\n            auto &pose = this->endEffectorTrajectory_[k];\n            moveit_msgs::GetPositionIKRequest req;\n            // req.ik_request.attempts = 20;\n\n            req.ik_request.ik_link_name = *tipLink_;\n            req.ik_request.robot_state.joint_state.name = currentjointnames;\n            req.ik_request.robot_state.joint_state.position = jointPositions;\n\n            req.ik_request.group_name = groupname;\n            req.ik_request.avoid_collisions = true;\n\n            moveit_msgs::GetPositionIKResponse res;\n\n            //pose.header.stamp = ros::Time::now();\n            req.ik_request.pose_stamped = pose;\n\n            ROS_DEBUG_STREAM(\"IK request: \" << req);\n            if (iksrv_.call(req, res))\n            {\n                auto &prevtrajpoint = trajectory.back();\n                //jointPositions.clear();\n\n                std::stringstream ss;\n                for (int j = 0; j < res.solution.joint_state.position.size(); j++)\n                {\n                    auto &jointname = res.solution.joint_state.name[j];\n                    auto it = std::find(currentjointnames.begin(), currentjointnames.end(), jointname);\n                    if (it != currentjointnames.end())\n                    {\n                        int index = std::distance(currentjointnames.begin(), it);\n                        jointPositions[index] = res.solution.joint_state.position[j];\n                        ss << jointname << \"(\" << index << \"): \" << jointPositions[index] << std::endl;\n                    }\n                }\n\n                // continuity check\n                int jointindex = 0;\n                int discontinuityJointIndex = -1;\n                double discontinuityDeltaJointIndex = -1;\n                double deltajoint;\n\n                bool check = k > 0 || !allowInitialTrajectoryStateJointDiscontinuity_ || allowInitialTrajectoryStateJointDiscontinuity_ && !(*allowInitialTrajectoryStateJointDiscontinuity_);\n                if (check)\n                {\n                    for (jointindex = 0; jointindex < jointPositions.size(); jointindex++)\n                    {\n                        deltajoint = jointPositions[jointindex] - prevtrajpoint[jointindex];\n\n                        if (fabs(deltajoint) > 0.3 /*2.5 deg*/)\n                        {\n                            discontinuityDeltaJointIndex = deltajoint;\n                            discontinuityJointIndex = jointindex;\n                        }\n                    }\n                }\n\n                if (ikAttempts > 0 && discontinuityJointIndex != -1)\n                {\n                    k--;\n                    ikAttempts--;\n                    continue;\n                }\n                else\n                {\n                    bool discontinuity = false;\n                    if (ikAttempts == 0)\n                    {\n                        discontinuityIndexes.push_back(k);\n                        discontinuity = true;\n                    }\n\n                    ikAttempts = 4;\n\n                    if (discontinuity && discontinuityJointIndex != -1)\n                    {\n                        // show a message and stop the trajectory generation && jointindex!= 7 || fabs(deltajoint) > 0.1 /*2.5 deg*/  && jointindex== 7\n                        std::stringstream ss;\n                        ss << \"Traj[\" << k << \"/\" << endEffectorTrajectory_.size() << \"] \" << currentjointnames[discontinuityJointIndex] << \" IK discontinuity : \" << discontinuityDeltaJointIndex << std::endl\n                           << \"prev joint value: \" << prevtrajpoint[discontinuityJointIndex] << std::endl\n                           << \"current joint value: \" << jointPositions[discontinuityJointIndex] << std::endl;\n\n                        ss << std::endl;\n                        for (int ji = 0; ji < jointPositions.size(); ji++)\n                        {\n                            ss << currentjointnames[ji] << \": \" << jointPositions[ji] << std::endl;\n                        }\n\n                        for (int kindex = 0; kindex < trajectory.size(); kindex++)\n                        {\n                            ss << \"[\" << kindex << \"]: \" << trajectory[kindex][discontinuityJointIndex] << std::endl;\n                        }\n\n                        if (k == 0)\n                        {\n                            ss << \"This is the first posture of the trajectory. Maybe the robot initial posture is not coincident to the initial posture of the generated joint trajectory.\" << std::endl;\n                        }\n\n                        ROS_ERROR_STREAM(ss.str());\n\n                        trajectory.push_back(jointPositions);\n                        ros::Duration durationFromStart = pose.header.stamp - referenceTime;\n                        trajectoryTimeStamps.push_back(durationFromStart);\n\n                        continue;\n                    }\n                    else\n                    {\n                        trajectory.push_back(jointPositions);\n                        ros::Duration durationFromStart = pose.header.stamp - referenceTime;\n                        trajectoryTimeStamps.push_back(durationFromStart);\n\n                        ROS_DEBUG_STREAM(\"IK solution: \" << res.solution.joint_state);\n                        ROS_DEBUG_STREAM(\"trajpoint: \" << std::endl\n                                                      << ss.str());\n                    }\n                }\n            }\n            else\n            {\n                ROS_ERROR(\"[CbMoveEndEffectorTrajectory] wrong IK call\");\n            }\n\n            ROS_WARN_STREAM(\"-----\");\n        }\n\n        // interpolate speeds?\n\n        // interpolate accelerations?\n\n        // get current robot state\n        // fill plan message\n        // computedMotionPlan.start_state_.joint_state.name = currentjointnames;\n        // computedMotionPlan.start_state_.joint_state.position = trajectory.front();\n        // computedMotionPlan.trajectory_.joint_trajectory.joint_names = currentjointnames;\n\n        computedJointTrajectory.joint_trajectory.joint_names = currentjointnames;\n        int i = 0;\n        for (auto &p : trajectory)\n        {\n            if (i == 0) // not copy the current state in the trajectory (used to solve discontinuity in other behaviors)\n            {\n                i++;\n                continue;\n            }\n\n            trajectory_msgs::JointTrajectoryPoint jp;\n            jp.positions = p;\n            jp.time_from_start = trajectoryTimeStamps[i]; //ros::Duration(t);\n            computedJointTrajectory.joint_trajectory.points.push_back(jp);\n            i++;\n        }\n\n        if (discontinuityIndexes.size())\n        {\n            if (discontinuityIndexes[0] == 0)\n                return ComputeJointTrajectoryErrorCode::INCORRECT_INITIAL_STATE;\n            else\n                return ComputeJointTrajectoryErrorCode::JOINT_TRAJECTORY_DISCONTINUITY;\n        }\n\n        return ComputeJointTrajectoryErrorCode::SUCCESS;\n    }\n\n    void CbMoveEndEffectorTrajectory::executeJointSpaceTrajectory(const moveit_msgs::RobotTrajectory &computedJointTrajectory)\n    {\n        ROS_INFO_STREAM(\"[\" << this->getName() << \"] Executing joint trajectory\");\n        // call execute\n        auto executionResult = this->movegroupClient_->moveGroupClientInterface.execute(computedJointTrajectory);\n\n        if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)\n        {\n            ROS_INFO_STREAM(\"[\" << this->getName() << \"] motion execution succeeded\");\n            movegroupClient_->postEventMotionExecutionSucceded();\n            this->postSuccessEvent();\n        }\n        else\n        {\n            this->postMotionExecutionFailureEvents();\n            this->postFailureEvent();\n        }\n    }\n\n    void CbMoveEndEffectorTrajectory::onEntry()\n    {\n        this->requiresClient(movegroupClient_);\n\n        this->generateTrajectory();\n\n        if (this->endEffectorTrajectory_.size() == 0)\n        {\n            ROS_WARN_STREAM(\"[\" << smacc::demangleSymbol(typeid(*this).name()) << \"] No points in the trajectory. Skipping behavior.\");\n            return;\n        }\n\n        this->createMarkers();\n        markersInitialized_ = true;\n\n        moveit_msgs::RobotTrajectory computedTrajectory;\n\n        auto errorcode = computeJointSpaceTrajectory(computedTrajectory);\n\n        bool trajectoryGenerationSuccess = errorcode == ComputeJointTrajectoryErrorCode::SUCCESS;\n\n        CpTrajectoryHistory *trajectoryHistory;\n        this->requiresComponent(trajectoryHistory);\n\n        if (!trajectoryGenerationSuccess)\n        {\n            ROS_INFO_STREAM(\"[\" << this->getName() << \"] Incorrect trajectory. Posting failure event.\");\n            if (trajectoryHistory != nullptr)\n            {\n                moveit_msgs::MoveItErrorCodes error;\n                error.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;\n                trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);\n            }\n\n            movegroupClient_->postEventMotionExecutionFailed();\n            this->postFailureEvent();\n\n            if (errorcode == ComputeJointTrajectoryErrorCode::JOINT_TRAJECTORY_DISCONTINUITY)\n            {\n                this->postJointDiscontinuityEvent(computedTrajectory);\n            }\n            else if (errorcode == ComputeJointTrajectoryErrorCode::INCORRECT_INITIAL_STATE)\n            {\n                this->postIncorrectInitialStateEvent(computedTrajectory);\n            }\n            return;\n        }\n        else\n        {\n            if (trajectoryHistory != nullptr)\n            {\n                moveit_msgs::MoveItErrorCodes error;\n                error.val = moveit_msgs::MoveItErrorCodes::SUCCESS;\n                trajectoryHistory->pushTrajectory(this->getName(), computedTrajectory, error);\n            }\n\n            this->executeJointSpaceTrajectory(computedTrajectory);\n        }\n\n        // handle finishing events\n    } // namespace cl_move_group_interface\n\n    void CbMoveEndEffectorTrajectory::update()\n    {\n        if (markersInitialized_)\n        {\n            std::lock_guard<std::mutex> guard(m_mutex_);\n            markersPub_.publish(beahiorMarkers_);\n        }\n    }\n\n    void CbMoveEndEffectorTrajectory::onExit()\n    {\n        markersInitialized_ = false;\n\n        if (autocleanmarkers)\n        {\n            std::lock_guard<std::mutex> guard(m_mutex_);\n            for (auto &marker : this->beahiorMarkers_.markers)\n            {\n                marker.header.stamp = ros::Time::now();\n                marker.action = visualization_msgs::Marker::DELETE;\n            }\n\n            markersPub_.publish(beahiorMarkers_);\n        }\n    }\n\n    void CbMoveEndEffectorTrajectory::createMarkers()\n    {\n        tf::Transform localdirection;\n        localdirection.setIdentity();\n        localdirection.setOrigin(tf::Vector3(0.05, 0, 0));\n        auto frameid = this->endEffectorTrajectory_.front().header.frame_id;\n\n        for (auto &pose : this->endEffectorTrajectory_)\n        {\n            visualization_msgs::Marker marker;\n            marker.header.frame_id = frameid;\n            marker.header.stamp = ros::Time::now();\n            marker.ns = \"trajectory\";\n            marker.id = this->beahiorMarkers_.markers.size();\n            marker.type = visualization_msgs::Marker::ARROW;\n            marker.action = visualization_msgs::Marker::ADD;\n            marker.scale.x = 0.005;\n            marker.scale.y = 0.01;\n            marker.scale.z = 0.01;\n            marker.color.a = 0.8;\n            marker.color.r = 1.0;\n            marker.color.g = 0;\n            marker.color.b = 0;\n\n            geometry_msgs::Point start, end;\n            start.x = 0;\n            start.y = 0;\n            start.z = 0;\n\n            tf::Transform basetransform;\n            tf::poseMsgToTF(pose.pose, basetransform);\n            tf::Transform endarrow = localdirection * basetransform;\n\n            end.x = localdirection.getOrigin().x();\n            end.y = localdirection.getOrigin().y();\n            end.z = localdirection.getOrigin().z();\n\n            marker.pose.position = pose.pose.position;\n            marker.pose.orientation = pose.pose.orientation;\n            marker.points.push_back(start);\n            marker.points.push_back(end);\n\n            beahiorMarkers_.markers.push_back(marker);\n        }\n    }\n\n    void CbMoveEndEffectorTrajectory::generateTrajectory()\n    {\n        // bypass current trajectory, overridden in derived classes\n        // this->endEffectorTrajectory_ = ...\n    }\n\n    void CbMoveEndEffectorTrajectory::getCurrentEndEffectorPose(std::string globalFrame, tf::StampedTransform &currentEndEffectorTransform)\n    {\n        tf::TransformListener tfListener;\n\n        try\n        {\n            if (!tipLink_ || *tipLink_ == \"\")\n            {\n                tipLink_ = this->movegroupClient_->moveGroupClientInterface.getEndEffectorLink();\n            }\n\n            tfListener.waitForTransform(globalFrame, *tipLink_, ros::Time(0), ros::Duration(10));\n            tfListener.lookupTransform(globalFrame, *tipLink_, ros::Time(0), currentEndEffectorTransform);\n\n            // we define here the global frame as the pivot frame id\n            // tfListener.waitForTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), ros::Duration(10));\n            // tfListener.lookupTransform(currentRobotEndEffectorPose.header.frame_id, planePivotPose_.header.frame_id, ros::Time(0), globalBaseLink);\n        }\n        catch (const std::exception &e)\n        {\n            std::cerr << e.what() << '\\n';\n        }\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_joints.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_joints.h>\n#include <future>\n\nnamespace cl_move_group_interface\n{\n  CbMoveJoints::CbMoveJoints(const std::map<std::string, double> &jointValueTarget) : jointValueTarget_(jointValueTarget)\n  {\n  }\n\n  CbMoveJoints::CbMoveJoints()\n  {\n  }\n\n  void CbMoveJoints::onEntry()\n  {\n    this->requiresClient(movegroupClient_);\n\n    if (this->group_)\n    {\n      moveit::planning_interface::MoveGroupInterface move_group(*(this->group_));\n      this->moveJoints(move_group);\n    }\n    else\n    {\n      this->moveJoints(movegroupClient_->moveGroupClientInterface);\n    }\n  }\n\n  std::string currentJointStatesToString(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map<std::string, double>& targetJoints)\n  {\n    auto state = moveGroupInterface.getCurrentState();\n    auto vnames = state->getVariableNames();\n\n    std::stringstream ss;\n\n    for(auto& tgj: targetJoints)\n    {\n      auto it = std::find(vnames.begin(),vnames.end(), tgj.first);\n      auto index = std::distance(vnames.begin(), it);\n\n      ss << tgj.first << \":\" << state->getVariablePosition(index) << std::endl;\n    }\n\n    return ss.str();\n  }\n\n  void CbMoveJoints::moveJoints(moveit::planning_interface::MoveGroupInterface &moveGroupInterface)\n  {\n    if (scalingFactor_)\n      moveGroupInterface.setMaxVelocityScalingFactor(*scalingFactor_);\n\n    bool success;\n    moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;\n\n    if (jointValueTarget_.size() == 0)\n    {\n      ROS_WARN(\"[CbMoveJoints] No joint was value specified. Skipping planning call.\");\n      success = false;\n    }\n    else\n    {\n      moveGroupInterface.setJointValueTarget(jointValueTarget_);\n      //moveGroupInterface.setGoalJointTolerance(0.01);\n      success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);\n      ROS_INFO_NAMED(\"CbMoveJoints\", \"Success Visualizing plan 1 (pose goal) %s\", success ? \"\" : \"FAILED\");\n    }\n\n    if (success)\n    {\n      auto executionResult = moveGroupInterface.execute(computedMotionPlan);\n\n      auto statestr = currentJointStatesToString(moveGroupInterface, jointValueTarget_);\n\n      if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)\n      {\n        ROS_INFO_STREAM(\"[\" << this->getName() << \"] motion execution succeeded. Throwing success event. \" << std::endl\n                                                                                              << statestr);\n        movegroupClient_->postEventMotionExecutionSucceded();\n        this->postSuccessEvent();\n      }\n      else\n      {\n        ROS_WARN_STREAM(\"[\" << this->getName() << \"] motion execution failed. Throwing fail event.\" << std::endl\n                                                                                       << statestr);\n        movegroupClient_->postEventMotionExecutionFailed();\n        this->postFailureEvent();\n      }\n    }\n    else\n    {\n      auto statestr = currentJointStatesToString(moveGroupInterface, jointValueTarget_);\n      ROS_WARN_STREAM(\"[\" << this->getName() << \"] motion execution failed. Throwing fail event.\" << std::endl << statestr);\n      movegroupClient_->postEventMotionExecutionFailed();\n      this->postFailureEvent();\n    }\n  }\n\n  void CbMoveJoints::onExit()\n  {\n  }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_known_state.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_known_state.h>\n#include <yaml-cpp/yaml.h>\n#include <fstream>\n#include <ros/package.h>\n#include <experimental/filesystem>\n\nnamespace cl_move_group_interface\n{\nCbMoveKnownState::CbMoveKnownState(std::string pkg, std::string config_path)\n  : CbMoveJoints(loadJointStatesFromFile(pkg, config_path))\n{\n}\n\nCbMoveKnownState::~CbMoveKnownState()\n{\n\n}\n\n\n#define HAVE_NEW_YAMLCPP\nstd::map<std::string, double> CbMoveKnownState::loadJointStatesFromFile(std::string pkg, std::string filepath)\n{\n  auto pkgpath = ros::package::getPath(pkg);\n  std::map<std::string, double> jointStates;\n\n  if(pkgpath == \"\")\n  {\n    ROS_ERROR_STREAM(\"[CbMoveKnownState] package not found for the known poses file: \" << pkg << std::endl << \" [IGNORING BEHAVIOR]\");\n    return jointStates;\n  }\n\n  filepath =  pkgpath +\"/\" + filepath;\n\n\n  ROS_INFO(\"[CbMoveKnownState] Opening file with joint known state: %s\",  filepath.c_str());\n\n\n  if(std::experimental::filesystem::exists(filepath))\n  {\n    ROS_INFO_STREAM(\"[CbMoveKnownState] known state file exists: \" << filepath);\n  }\n  else\n  {\n    ROS_ERROR_STREAM(\"[CbMoveKnownState] known state file does not exists: \" << filepath);\n  }\n\n  std::ifstream ifs(filepath.c_str(), std::ifstream::in);\n  if (ifs.good() == false)\n  {\n    ROS_ERROR(\"[CbMoveKnownState] Error opening file with joint known states: %s\",  filepath.c_str());\n    throw std::string(\"joint state files not found\");\n  }\n\n  try\n  {\n#ifdef HAVE_NEW_YAMLCPP\n    YAML::Node node = YAML::Load(ifs);\n#else\n    YAML::Parser parser(ifs);\n    parser.GetNextDocument(node);\n#endif\n\n#ifdef HAVE_NEW_YAMLCPP\n    const YAML::Node &wp_node_tmp = node[\"joint_states\"];\n    const YAML::Node *wp_node = wp_node_tmp ? &wp_node_tmp : NULL;\n#else\n    const YAML::Node *wp_node = node.FindValue(\"waypoints\");\n#endif\n\n    if (wp_node != NULL)\n    {\n      try\n      {\n        for(YAML::const_iterator it=wp_node->begin();it != wp_node->end();++it)\n        {\n          std::string key = it->first.as<std::string>();\n          double value = it->second.as<double>();\n          ROS_DEBUG_STREAM(\" joint - \" << key << \": \" << value);\n          jointStates[key] = value;\n        }\n\n        return jointStates;\n      }\n      catch(std::exception& ex)\n      {\n        ROS_ERROR(\"trying to convert to map, failed, errormsg: %s\", ex.what());\n      }\n\n      ROS_INFO_STREAM(\"Parsed \" << jointStates.size() << \" joint entries.\");\n    }\n    else\n    {\n      ROS_WARN_STREAM(\"Couldn't find any jointStates in the provided yaml file.\");\n    }\n  }\n  catch (const YAML::ParserException &ex)\n  {\n    ROS_ERROR_STREAM(\"Error loading the Waypoints YAML file. Incorrect syntax: \" << ex.what());\n  }\n  return jointStates;\n}\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_last_trajectory_initial_state.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_last_trajectory_initial_state.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n    CbMoveLastTrajectoryInitialState::CbMoveLastTrajectoryInitialState()\n    {\n    }\n\n    CbMoveLastTrajectoryInitialState::CbMoveLastTrajectoryInitialState(int backIndex)\n        : backIndex_(backIndex)\n    {\n    }\n\n    CbMoveLastTrajectoryInitialState::~CbMoveLastTrajectoryInitialState()\n    {\n    }\n\n    void CbMoveLastTrajectoryInitialState::onEntry()\n    {\n        CpTrajectoryHistory *trajectoryHistory;\n        this->requiresComponent(trajectoryHistory);\n\n        if (trajectoryHistory != nullptr)\n        {\n            moveit_msgs::RobotTrajectory trajectory;\n\n            bool trajectoryFound = trajectoryHistory->getLastTrajectory(backIndex_, trajectory);\n\n            if (trajectoryFound)\n            {\n                trajectory_msgs::JointTrajectoryPoint &initialPoint = trajectory.joint_trajectory.points.front();\n\n                std::stringstream ss;\n                for (int i = 0; i < trajectory.joint_trajectory.joint_names.size(); i++)\n                {\n                    auto &name = trajectory.joint_trajectory.joint_names[i];\n\n                    jointValueTarget_[name] = initialPoint.positions[i];\n                    ss << name << \": \" << jointValueTarget_[name] << std::endl;\n                }\n                ROS_INFO_STREAM(\"[\" << this->getName() << \"]\" << std::endl\n                                    << ss.str());\n\n                ROS_INFO_STREAM(\"[\" << this->getName() << \"] move joint onEntry\");\n                CbMoveJoints::onEntry();\n                ROS_INFO_STREAM(\"[\" << this->getName() << \"] move joint onEntry finished\");\n            }\n        }\n\n        //call base OnEntry\n    }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_move_named_target.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_move_named_target.h>\n\nnamespace cl_move_group_interface\n{\nCbMoveNamedTarget::CbMoveNamedTarget(std::string namedtarget)\n: namedTarget_(namedtarget)\n{\n}\n\nvoid CbMoveNamedTarget::onEntry()\n{\n    this->requiresClient(movegroupClient_);\n    movegroupClient_->moveGroupClientInterface.setNamedTarget(this->namedTarget_);\n}\n\nvoid CbMoveNamedTarget::onExit()\n{\n}\n\nstd::map<std::string, double> CbMoveNamedTarget::getNamedTargetValues()\n{\n    return movegroupClient_->moveGroupClientInterface.getNamedTargetValues(this->namedTarget_);\n}\n}  // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_pouring_motion.cpp",
    "content": "#include <move_group_interface_client/client_behaviors/cb_pouring_motion.h>\n\n/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/client_behaviors/cb_circular_pivot_motion.h>\n\nnamespace cl_move_group_interface\n{\n    CbCircularPouringMotion::CbCircularPouringMotion(const geometry_msgs::Point &relativePivotPoint, double deltaHeight, std::string tipLink, std::string globalFrame)\n        : relativePivotPoint_(relativePivotPoint)\n        , deltaHeight_(deltaHeight)\n        , CbMoveEndEffectorTrajectory(tipLink)\n        , globalFrame_(globalFrame)\n    {\n    }\n\n    void CbCircularPouringMotion::generateTrajectory()\n    {\n        // at least 1 sample per centimeter (average)\n        const double METERS_PER_SAMPLE = 0.001;\n\n        float dist_meters =0;\n        float totallineardist = fabs(this->deltaHeight_);\n\n        int totalSamplesCount = totallineardist / METERS_PER_SAMPLE;\n        int steps = totallineardist/ METERS_PER_SAMPLE;\n\n        float interpolation_factor_step = 1.0/totalSamplesCount;\n\n        double secondsPerSample;\n\n        if (linearSpeed_m_s_)\n        {\n            secondsPerSample = METERS_PER_SAMPLE / (*linearSpeed_m_s_);\n        }\n        else\n        {\n            secondsPerSample = std::numeric_limits<double>::max();\n        }\n\n        tf::StampedTransform currentEndEffectorTransform;\n\n        this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);\n\n        tf::Transform lidEndEffectorTransform;\n        tf::poseMsgToTF(this->pointerRelativePose_, lidEndEffectorTransform);\n\n        tf::Vector3 v0, v1;\n        v0 = (currentEndEffectorTransform * lidEndEffectorTransform).getOrigin();\n\n        tf::Point pivotPoint;\n        tf::pointMsgToTF(this->relativePivotPoint_, pivotPoint);\n\n        tf::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);\n\n        v0 = v0 - pivot;\n        v1 = v0;\n        v1.setZ(v1.z() + this->deltaHeight_);\n\n        tf::Vector3 vp1(v1);\n        tf::Vector3 vp0(v0);\n        tf::Quaternion rotation = tf::shortestArcQuatNormalize2(vp0, vp1);\n\n        tf::Quaternion initialEndEffectorOrientation = currentEndEffectorTransform.getRotation();\n        auto finalEndEffectorOrientation = initialEndEffectorOrientation* rotation;\n\n        tf::Quaternion initialPointerOrientation = initialEndEffectorOrientation * lidEndEffectorTransform.getRotation();\n        tf::Quaternion finalPointerOrientation = finalEndEffectorOrientation * lidEndEffectorTransform.getRotation();\n\n        auto shortestAngle = tf::angleShortestPath(initialEndEffectorOrientation, finalEndEffectorOrientation);\n\n        v0+=pivot;\n        v1+=pivot;\n\n        float linc = deltaHeight_/steps;// METERS_PER_SAMPLE with sign\n        float interpolation_factor = 0;\n        tf::Vector3 vi = v0;\n\n        tf::Transform invertedLidTransform = lidEndEffectorTransform.inverse();\n        ros::Time startTime = ros::Time::now();\n\n        for (float i =0; i < steps; i++)\n        {\n            auto currentEndEffectorOrientation = tf::slerp(initialEndEffectorOrientation, finalEndEffectorOrientation, interpolation_factor);\n            auto currentPointerOrientation = tf::slerp(initialPointerOrientation, finalPointerOrientation, interpolation_factor);\n\n            interpolation_factor += interpolation_factor_step;\n            dist_meters += linc;\n\n            vi = v0;\n            vi.setZ(vi.getZ() + dist_meters);\n\n            tf::Transform pose;\n            pose.setOrigin(vi);\n            pose.setRotation(currentPointerOrientation);\n\n            geometry_msgs::PoseStamped pointerPose;\n            tf::poseTFToMsg(pose, pointerPose.pose);\n            pointerPose.header.frame_id = globalFrame_;\n            pointerPose.header.stamp = startTime + ros::Duration(i * secondsPerSample);\n            this->pointerTrajectory_.push_back(pointerPose);\n\n            tf::Transform poseEndEffector = pose * invertedLidTransform;\n\n            geometry_msgs::PoseStamped globalEndEffectorPose;\n            tf::poseTFToMsg(poseEndEffector, globalEndEffectorPose.pose);\n            globalEndEffectorPose.header.frame_id = globalFrame_;\n            globalEndEffectorPose.header.stamp = startTime + ros::Duration(i * secondsPerSample);\n\n            this->endEffectorTrajectory_.push_back(globalEndEffectorPose);\n        }\n    }\n\n    void CbCircularPouringMotion::createMarkers()\n    {\n        CbMoveEndEffectorTrajectory::createMarkers();\n\n        tf::StampedTransform currentEndEffectorTransform;\n        this->getCurrentEndEffectorPose(globalFrame_, currentEndEffectorTransform);\n        tf::Point pivotPoint;\n        tf::pointMsgToTF(this->relativePivotPoint_, pivotPoint);\n        tf::Vector3 pivot = (currentEndEffectorTransform * pivotPoint);\n\n\n        visualization_msgs::Marker marker;\n\n        marker.ns = \"trajectory\";\n        marker.id = beahiorMarkers_.markers.size();\n        marker.type = visualization_msgs::Marker::SPHERE;\n        marker.action = visualization_msgs::Marker::ADD;\n        marker.scale.x = 0.01;\n        marker.scale.y = 0.01;\n        marker.scale.z = 0.01;\n\n        marker.color.a = 1.0;\n        marker.color.r = 0.0;\n        marker.color.g = 0;\n        marker.color.b = 1.0;\n\n        tf::pointTFToMsg(pivot, marker.pose.position);\n        marker.header.frame_id = globalFrame_;\n        marker.header.stamp = ros::Time::now();\n\n        beahiorMarkers_.markers.push_back(marker);\n\n        tf::Transform localdirection;\n        localdirection.setIdentity();\n        localdirection.setOrigin(tf::Vector3(0.05, 0, 0));\n        auto frameid = this->pointerTrajectory_.front().header.frame_id;\n\n        for (auto &pose : this->pointerTrajectory_)\n        {\n            visualization_msgs::Marker marker;\n            marker.header.frame_id = frameid;\n            marker.header.stamp = ros::Time::now();\n            marker.ns = \"trajectory\";\n            marker.id = this->beahiorMarkers_.markers.size();\n            marker.type = visualization_msgs::Marker::ARROW;\n            marker.action = visualization_msgs::Marker::ADD;\n            marker.scale.x = 0.005;\n            marker.scale.y = 0.01;\n            marker.scale.z = 0.01;\n            marker.color.a = 0.8;\n            marker.color.r = 0.0;\n            marker.color.g = 1;\n            marker.color.b = 0.0;\n\n            geometry_msgs::Point start, end;\n            start.x = 0;\n            start.y = 0;\n            start.z = 0;\n\n            tf::Transform basetransform;\n            tf::poseMsgToTF(pose.pose, basetransform);\n            tf::Transform endarrow = localdirection * basetransform;\n\n            end.x = localdirection.getOrigin().x();\n            end.y = localdirection.getOrigin().y();\n            end.z = localdirection.getOrigin().z();\n\n            marker.pose.position = pose.pose.position;\n            marker.pose.orientation = pose.pose.orientation;\n            marker.points.push_back(start);\n            marker.points.push_back(end);\n\n            beahiorMarkers_.markers.push_back(marker);\n        }\n    }\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/client_behaviors/cb_undo_last_trajectory.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <move_group_interface_client/client_behaviors/cb_undo_last_trajectory.h>\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n\n    CbUndoLastTrajectory::CbUndoLastTrajectory()\n    {\n    }\n\n    CbUndoLastTrajectory::CbUndoLastTrajectory(int backIndex)\n        : backIndex_(backIndex)\n    {\n    }\n\n    CbUndoLastTrajectory::~CbUndoLastTrajectory()\n    {\n    }\n\n    void CbUndoLastTrajectory::onEntry()\n    {\n        CpTrajectoryHistory *trajectoryHistory;\n        this->requiresComponent(trajectoryHistory);\n        this->requiresClient(movegroupClient_);\n\n        if (trajectoryHistory->getLastTrajectory(backIndex_, trajectory))\n        {\n            auto initialTime = trajectory.joint_trajectory.points.back().time_from_start;\n\n            reversed = trajectory;\n\n            std::reverse(reversed.joint_trajectory.points.begin(), reversed.joint_trajectory.points.end());\n\n            for (auto &jp : reversed.joint_trajectory.points)\n            {\n                jp.time_from_start = ros::Duration(fabs(jp.time_from_start.toSec() - initialTime.toSec())); //ros::Duration(t);\n            }\n\n            this->executeJointSpaceTrajectory(reversed);\n        }\n    }\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/components/cp_grasping_objects.cpp",
    "content": "#include <move_group_interface_client/components/cp_grasping_objects.h>\n\nnamespace cl_move_group_interface\n{\n   bool GraspingComponent::getGraspingObject(std::string name, moveit_msgs::CollisionObject &object)\n   {\n      if (this->graspingObjects.count(name))\n      {\n         object = this->graspingObjects[name];\n         return true;\n      }\n      else\n      {\n         return false;\n      }\n   }\n\n   void GraspingComponent::createGraspableBox(std::string frameid, float x, float y, float z, float xl, float yl, float zl)\n   {\n      moveit_msgs::CollisionObject collision;\n      auto boxname = frameid;\n      ;\n      collision.id = boxname;\n      collision.header.frame_id = frameid;\n\n      collision.primitives.resize(1);\n      collision.primitives[0].type = collision.primitives[0].BOX;\n      collision.primitives[0].dimensions.resize(3);\n\n      collision.primitives[0].dimensions[0] = xl;\n      collision.primitives[0].dimensions[1] = yl;\n      collision.primitives[0].dimensions[2] = zl;\n\n      collision.primitive_poses.resize(1);\n      collision.primitive_poses[0].position.x = x;\n      collision.primitive_poses[0].position.y = y;\n      collision.primitive_poses[0].position.z = z;\n      collision.primitive_poses[0].orientation.w = 1.0;\n\n      graspingObjects[boxname] = collision;\n   }\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/move_group_interface_client/src/move_group_interface_client/components/cp_trajectory_history.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018-2020\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n\n#include <move_group_interface_client/components/cp_trajectory_history.h>\n\nnamespace cl_move_group_interface\n{\n\n    bool CpTrajectoryHistory::getLastTrajectory(int backIndex, moveit_msgs::RobotTrajectory &trajectory)\n    {\n        if (trajectoryHistory_.size() == 0 )\n        {\n            return false;\n        }\n\n        if (backIndex < 0)\n        {\n            backIndex = 0;\n        }\n        else if(backIndex >= this->trajectoryHistory_.size())\n        {\n            return false;\n        }\n\n        trajectory = this->trajectoryHistory_[this->trajectoryHistory_.size() - 1 - backIndex].trajectory;\n        return true;\n    }\n\n    bool CpTrajectoryHistory::getLastTrajectory(moveit_msgs::RobotTrajectory &trajectory)\n    {\n        return getLastTrajectory(-1, trajectory);\n    }\n\n    void CpTrajectoryHistory::pushTrajectory(std::string name, const moveit_msgs::RobotTrajectory &trajectory, moveit_msgs::MoveItErrorCodes result)\n    {\n        TrajectoryHistoryEntry entry;\n        this->trajectoryHistory_.push_back(entry);\n\n        auto &last = this->trajectoryHistory_.back();\n        last.trajectory = trajectory;\n        last.result = result;\n        last.name = name;\n    }\n\n} // namespace cl_move_group_interface\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package multirole_sensor_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(multirole_sensor_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc smacc_msgs)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n   INCLUDE_DIRS include\n#  LIBRARIES multirole_sensor_client\n   CATKIN_DEPENDS smacc smacc_msgs\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n# include\n# ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/multirole_sensor_client.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/multirole_sensor_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_multirole_sensor_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/README.md",
    "content": ""
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/include/multirole_sensor_client/cl_multirole_sensor.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <boost/statechart/event.hpp>\n\n#include <ros/ros.h>\n#include <ros/duration.h>\n#include <boost/signals2.hpp>\n#include <boost/optional/optional_io.hpp>\n\nnamespace cl_multirole_sensor\n{\nusing namespace smacc;\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvTopicMessageTimeout : sc::event<EvTopicMessageTimeout<TSource, TOrthogonal>>\n{\n  ros::TimerEvent timerData;\n};\n\nusing namespace smacc::client_bases;\n\n//---------------------------------------------------------------\ntemplate <typename MessageType>\nclass ClMultiroleSensor : public smacc::client_bases::SmaccSubscriberClient<MessageType>\n{\npublic:\n  typedef MessageType TMessageType;\n  SmaccSignal<void(const ros::TimerEvent &)> onMessageTimeout_;\n\n  ClMultiroleSensor()\n      : smacc::client_bases::SmaccSubscriberClient<MessageType>()\n  {\n    ROS_INFO(\"[ClMultiroleSensor] constructor\");\n    initialized_ = false;\n  }\n\n  template <typename T>\n  boost::signals2::connection onMessageTimeout(void (T::*callback)(const ros::TimerEvent &), T *object)\n  {\n    return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object);\n  }\n\n  std::function<void(const ros::TimerEvent &ev)> postTimeoutMessageEvent;\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    SmaccSubscriberClient<MessageType>::template onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n\n    this->postTimeoutMessageEvent = [=](auto &timerdata) {\n      onMessageTimeout_(timerdata);\n\n      auto event = new EvTopicMessageTimeout<TSourceObject, TOrthogonal>();\n      event->timerData = timerdata;\n      this->postEvent(event);\n    };\n  }\n\n  virtual void initialize() override\n  {\n    if (!initialized_)\n    {\n      SmaccSubscriberClient<MessageType>::initialize();\n\n      this->onMessageReceived(&ClMultiroleSensor<MessageType>::resetTimer, this);\n\n      if (timeout_)\n      {\n        timeoutTimer_ = this->nh_.createTimer(*timeout_, boost::bind(&ClMultiroleSensor<MessageType>::timeoutCallback, this, _1));\n        timeoutTimer_.start();\n      }\n      else\n      {\n        ROS_WARN(\"Timeout sensor client not set, skipping timeout watchdog funcionality\");\n      }\n\n      initialized_ = true;\n    }\n  }\n\n  boost::optional<ros::Duration> timeout_;\n\nprotected:\n  void resetTimer(const MessageType &msg)\n  {\n    //resetting the timer\n    this->timeoutTimer_.stop();\n    this->timeoutTimer_.start();\n  }\n\nprivate:\n  ros::Timer timeoutTimer_;\n  bool initialized_;\n\n  void timeoutCallback(const ros::TimerEvent &timerdata)\n  {\n    postTimeoutMessageEvent(timerdata);\n  }\n};\n} // namespace cl_multirole_sensor\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/include/multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h",
    "content": "#pragma once\n\n#include <smacc/smacc_client_behavior.h>\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n\nnamespace cl_multirole_sensor\n{\ntemplate <typename ClientType>\nclass CbDefaultMultiRoleSensorBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n  typedef typename ClientType::TMessageType TMessageType;\n\n  ClientType *sensor_;\n\n  CbDefaultMultiRoleSensorBehavior()\n  {\n    sensor_ = nullptr;\n  }\n\n  static std::string getEventLabel()\n  {\n    // show ros message type\n    return demangleSymbol(typeid(TMessageType).name());\n  }\n\n  std::function<void()> deferedEventPropagation;\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    deferedEventPropagation = [=]() {\n      // just propagate the client events from this client behavior source.\n      sensor_->onMessageReceived(&CbDefaultMultiRoleSensorBehavior<ClientType>::propagateEvent<EvTopicMessage<TSourceObject, TOrthogonal>>, this);\n      sensor_->onFirstMessageReceived(&CbDefaultMultiRoleSensorBehavior<ClientType>::propagateEvent<EvTopicInitialMessage<TSourceObject, TOrthogonal>>, this);\n      sensor_->onMessageTimeout(&CbDefaultMultiRoleSensorBehavior<ClientType>::propagateEvent2<EvTopicMessageTimeout<TSourceObject, TOrthogonal>>, this);\n    };\n  }\n\n  template <typename EvType>\n  void propagateEvent(const TMessageType &msg)\n  {\n    this->postEvent<EvType>();\n  }\n\n  template <typename EvType>\n  void propagateEvent2(const ros::TimerEvent &tdata)\n  {\n    this->postEvent<EvType>();\n  }\n\n  virtual void onEntry() override\n  {\n    ROS_INFO(\"[CbDefaultMultiRoleSensorBehavior] onEntry. Requires client of type '%s'\", demangleSymbol<ClientType>().c_str());\n\n    this->requiresClient(sensor_);\n\n    if (sensor_ == nullptr)\n    {\n      ROS_FATAL_STREAM(\"Sensor client behavior needs a client of type: \" << demangleSymbol<ClientType>() << \" but it is not found.\");\n    }\n    else\n    {\n      deferedEventPropagation();\n      ROS_INFO(\"[CbDefaultMultiRoleSensorBehavior] onEntry. sensor initialize\");\n      sensor_->initialize();\n    }\n  }\n\n  void onExit()\n  {\n  }\n\n  virtual void onMessageCallback(const TMessageType &msg)\n  {\n    // empty to fill by sensor customization based on inheritance\n  }\n};\n} // namespace smacc\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>multirole_sensor_client</name>\n    <version>1.4.16</version>\n  <description>The multirole_sensor_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/multirole_sensor_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>smacc_msgs</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/multirole_sensor_client/rosdoc.yaml",
    "content": " - builder: doxygen\n   name: C++ API\n   output_dir: c++\n   file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package ros_publisher_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* unpushed code\n* second pass refactoring namespaces\n* more refactoring/renaming and refining examples\n* ros publisher client\n* segregating ros_publisher_client\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* unpushed code\n* second pass refactoring namespaces\n* more refactoring/renaming and refining examples\n* ros publisher client\n* segregating ros_publisher_client\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(ros_publisher_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED roscpp smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES ros_publisher_client\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/ros_publisher_client.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/ros_publisher_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_publisher_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/README.md",
    "content": ""
  },
  {
    "path": "smacc_client_library/ros_publisher_client/include/ros_publisher_client/cl_ros_publisher.h",
    "content": "\n#pragma once\n\n#include <smacc/client_bases/smacc_publisher_client.h>\n\nnamespace cl_ros_publisher\n{\n\nclass ClRosPublisher : public smacc::client_bases::SmaccPublisherClient\n{\npublic:\n    ClRosPublisher()\n    {\n    }\n\n    template <typename MessageType>\n    void configure(std::string topicName)\n    {\n        SmaccPublisherClient::configure<MessageType>(topicName);\n    }\n\n    template <typename MessageType>\n    void publish(const MessageType &msg)\n    {\n        SmaccPublisherClient::publish(msg);\n    }\n};\n} // namespace cl_ros_publisher\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/include/ros_publisher_client/client_behaviors/cb_default_publish_loop.h",
    "content": "\n#pragma once\n#include <smacc/smacc_client_behavior.h>\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nnamespace cl_ros_publisher\n{\n\nclass CbDefaultPublishLoop : public smacc::SmaccClientBehavior,\n                             public smacc::ISmaccUpdatable\n{\nprivate:\n    std::function<void()> deferedPublishFn;\n    ClRosPublisher *client_;\n\npublic:\n    CbDefaultPublishLoop()\n        : deferedPublishFn(nullptr)\n    {\n    }\n\n    template <typename TMessage>\n    CbDefaultPublishLoop(const TMessage &data)\n    {\n        this->setMessage(data);\n    }\n\n    template <typename TMessage>\n    void setMessage(const TMessage &data)\n    {\n        deferedPublishFn = [=]() {\n            client_->publish(data);\n        };\n    }\n\n    virtual void onEntry() override\n    {\n        this->requiresClient(client_);\n    }\n\n    virtual void update()\n    {\n        if (deferedPublishFn != nullptr)\n            deferedPublishFn();\n    }\n\n    virtual void onExit() override\n    {\n    }\n};\n} // namespace cl_ros_publisher\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/include/ros_publisher_client/client_behaviors/cb_muted_behavior.h",
    "content": "\n#pragma once\n#include <smacc/smacc_client_behavior.h>\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nnamespace cl_ros_publisher\n{\ntemplate <typename RosMsgType>\nclass CbMutedBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    virtual void onEntry() override\n    {\n    }\n    virtual void onExit() override\n    {\n    }\n};\n} // namespace cl_ros_publisher\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/include/ros_publisher_client/client_behaviors/cb_publish_once.h",
    "content": "\n#pragma once\n#include <smacc/smacc_client_behavior.h>\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nnamespace cl_ros_publisher\n{\ntemplate <typename RosMsgType>\nclass CbPublishOnce : public smacc::SmaccClientBehavior\n{\nprivate:\n    std::function<void()> deferedPublishFn;\n    ClRosPublisher *client_;\n\npublic:\n    CbPublishOnce()\n        : deferedPublishFn(nullptr)\n    {\n    }\n\n    template <typename TMessage>\n    CbPublishOnce(const TMessage &data)\n    {\n        this->setMessage(data);\n    }\n\n    template <typename TMessage>\n    void setMessage(const TMessage &data)\n    {\n        deferedPublishFn = [=]() {\n            client_->publish(data);\n        };\n    }\n\n    virtual void onEntry() override\n    {\n        this->requiresClient(client_);\n\n        if (deferedPublishFn != nullptr)\n            deferedPublishFn();\n    }\n\n    virtual void onExit() override\n    {\n    }\n};\n} // namespace cl_ros_publisher\n"
  },
  {
    "path": "smacc_client_library/ros_publisher_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>ros_publisher_client</name>\n    <version>1.4.16</version>\n  <description>The ros_publisher_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/ros_publisher_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package ros_timer_client\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Added Readme's to Client Library\n* Merge branch 'master' into melodic-devel\n* improving/fixing bugs on smacc signals related with the smacc objects life-time. Also clients improved in the related to this.\n* standarizing private/public access to state machine reference, current state, clients, etc\n* unpushed code\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic and logic unit hierarchy. other improvements on rosout\n* renaming move_base client to ClMoveBaseZ (zorro)\n* more on refactoring renaming\n* fixing broken build related with C++11/14 build for package ros_timer_client\n* ros_timer_client refactoring\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(ros_timer_client)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES ros_timer_client\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/timer_client.cpp\n   src/${PROJECT_NAME}/cb_timer.cpp\n   src/${PROJECT_NAME}/cb_timer_countdown_loop.cpp\n   src/${PROJECT_NAME}/cb_timer_countdown_once.cpp\n )\n\n target_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/ros_timer_client_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n install(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_timer_client.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/README.md",
    "content": ""
  },
  {
    "path": "smacc_client_library/ros_timer_client/include/ros_timer_client/cl_ros_timer.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <boost/signals2.hpp>\n#include <boost/optional/optional_io.hpp>\n\nnamespace cl_ros_timer\n{\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvTimer : sc::event<EvTimer<TSource, TOrthogonal>>\n{\n    /*\n    ClRosTimer *sender;\n    ros::TimerEvent timedata;\n\n    EvTimer(ClRosTimer *sender, const ros::TimerEvent &timedata)\n    {\n        this->sender = sender;\n        this->timedata = timedata;\n    }\n    */\n};\n\nclass ClRosTimer : public smacc::ISmaccClient\n{\npublic:\n    ClRosTimer(ros::Duration duration, bool oneshot = false);\n\n    virtual ~ClRosTimer();\n\n    virtual void initialize();\n\n    template <typename T>\n    boost::signals2::connection onTimerTick(void (T::*callback)(), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onTimerTick_, callback, object);\n    }\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        this->postTimerEvent_ = [=]() {\n            this->postEvent<EvTimer<TSourceObject, TOrthogonal>>();\n        };\n    }\n\nprotected:\n    ros::NodeHandle nh_;\n\n    ros::Timer timer;\n    ros::Duration duration;\n    bool oneshot;\n\n    void timerCallback(const ros::TimerEvent &timedata);\n    std::function<void()> postTimerEvent_;\n    smacc::SmaccSignal<void()> onTimerTick_;\n};\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/include/ros_timer_client/client_behaviors/cb_ros_timer.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace cl_ros_timer\n{\nclass CbTimer : public smacc::SmaccClientBehavior\n{\npublic:\n  virtual void onEntry() override;\n  virtual void onExit() override;\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    this->postTimerEvent_ = [=]() {\n      this->template postEvent<EvTimer<TSourceObject, TOrthogonal>>();\n    };\n  }\n\n  void onClientTimerTickCallback();\n\nprivate:\n  ClRosTimer *timerClient_;\n  std::function<void()> postTimerEvent_;\n  boost::signals2::scoped_connection c_;\n};\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/include/ros_timer_client/client_behaviors/cb_timer_countdown_loop.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace cl_ros_timer\n{\n\nclass CbTimerCountdownLoop : public smacc::SmaccClientBehavior\n{\npublic:\n    CbTimerCountdownLoop(uint64_t triggerTickCount);\n\n    virtual void onEntry() override;\n    virtual void onExit() override;\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        this->postCountDownEvent_ = [=]() {\n            this->template postEvent<EvTimer<TSourceObject, TOrthogonal>>();\n        };\n    }\n\n    template <typename T>\n    boost::signals2::connection onTimerTick(void (T::*callback)(), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onTimerTick_, callback, object);\n    }\n\nprivate:\n    uint64_t tickCounter_;\n    uint64_t tickTriggerCount_;\n\n    ClRosTimer *timerClient_;\n    std::function<void()> postCountDownEvent_;\n    smacc::SmaccSignal<void()> onTimerTick_;\n    void onClientTimerTickCallback();\n};\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/include/ros_timer_client/client_behaviors/cb_timer_countdown_once.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace cl_ros_timer\n{\nclass CbTimerCountdownOnce : public smacc::SmaccClientBehavior\n{\npublic:\n    CbTimerCountdownOnce(uint64_t triggerTickCount);\n\n    virtual void onEntry() override;\n    virtual void onExit() override;\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        this->postCountDownEvent_ = [=]() {\n            this->template postEvent<EvTimer<TSourceObject, TOrthogonal>>();\n        };\n    }\n\n    template <typename T>\n    boost::signals2::connection onTimerTick(void (T::*callback)(), T *object)\n    {\n        return this->getStateMachine()->createSignalConnection(onTimerTick_, callback, object);\n    }\n\nprivate:\n    uint64_t tickCounter_;\n    uint64_t tickTriggerCount_;\n\n    ClRosTimer *timerClient_;\n    std::function<void()> postCountDownEvent_;\n    smacc::SmaccSignal<void()> onTimerTick_;\n    void onClientTimerTickCallback();\n};\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>ros_timer_client</name>\n    <version>1.4.16</version>\n  <description>The ros_timer_client package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/ros_timer_client</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/src/ros_timer_client/cb_timer.cpp",
    "content": "#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n\nnamespace cl_ros_timer\n{\nvoid CbTimer::onEntry()\n{\n    this->requiresClient(timerClient_);\n\n    timerClient_->onTimerTick(&CbTimer::onClientTimerTickCallback, this);\n}\n\nvoid CbTimer::onClientTimerTickCallback()\n{\n    this->postTimerEvent_();\n}\n\nvoid CbTimer::onExit()\n{\n}\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/src/ros_timer_client/cb_timer_countdown_loop.cpp",
    "content": "#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n\nnamespace cl_ros_timer\n{\n\nCbTimerCountdownLoop::CbTimerCountdownLoop(uint64_t triggerTickCount)\n    : tickTriggerCount_(triggerTickCount),\n      tickCounter_(0)\n{\n}\n\nvoid CbTimerCountdownLoop::onClientTimerTickCallback()\n{\n    tickCounter_++;\n\n    if (tickCounter_ % tickTriggerCount_ == 0)\n    {\n        onTimerTick_();\n        postCountDownEvent_();\n    }\n}\n\nvoid CbTimerCountdownLoop::onEntry()\n{\n    this->requiresClient(timerClient_);\n    timerClient_->onTimerTick(&CbTimerCountdownLoop::onClientTimerTickCallback, this);\n}\n\nvoid CbTimerCountdownLoop::onExit()\n{\n}\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/src/ros_timer_client/cb_timer_countdown_once.cpp",
    "content": "#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nnamespace cl_ros_timer\n{\n\nCbTimerCountdownOnce::CbTimerCountdownOnce(uint64_t triggerTickCount)\n    : tickTriggerCount_(triggerTickCount),\n      tickCounter_(0)\n{\n}\n\nvoid CbTimerCountdownOnce::onClientTimerTickCallback()\n{\n    tickCounter_++;\n\n    if (tickCounter_ % tickTriggerCount_ == 0)\n    {\n        onTimerTick_();\n        postCountDownEvent_();\n    }\n}\n\nvoid CbTimerCountdownOnce::onEntry()\n{\n    this->requiresClient(timerClient_);\n    timerClient_->onTimerTick(&CbTimerCountdownOnce::onClientTimerTickCallback, this);\n}\n\nvoid CbTimerCountdownOnce::onExit()\n{\n}\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_client_library/ros_timer_client/src/ros_timer_client/timer_client.cpp",
    "content": "#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace cl_ros_timer\n{\n\nClRosTimer::ClRosTimer(ros::Duration duration, bool oneshot)\n{\n    this->duration = duration;\n    this->oneshot = oneshot;\n}\n\nClRosTimer::~ClRosTimer()\n{\n    timer.stop();\n}\n\nvoid ClRosTimer::initialize()\n{\n    timer = nh_.createTimer(duration, boost::bind(&ClRosTimer::timerCallback, this, _1), oneshot);\n}\n\nvoid ClRosTimer::timerCallback(const ros::TimerEvent &timedata)\n{\n    if (!onTimerTick_.empty())\n    {\n        this->onTimerTick_();\n    }\n    postTimerEvent_();\n}\n\n} // namespace cl_ros_timer\n"
  },
  {
    "path": "smacc_diagnostics/readme.md",
    "content": ""
  },
  {
    "path": "smacc_diagnostics/scripts/regex_template.py",
    "content": "import re\n\n\nclass TypeInfo:\n    def __init__(self, tkey, codedtype, finaltype):\n        self.tkey = tkey\n        self.codedtype = codedtype\n        self.finaltype = finaltype\n        self.template_parameters = []\n\n    def __str__(self):\n        return self.tkey + \":\" + self.finaltype\n\n\ndef getRootTypeInfo(inputtext):\n    ok = False\n    typecount = 0\n    typesdict = {}\n    originalinputtext = inputtext\n\n    # this loop flatterns the template type tree\n    while not ok:\n        simpletypeRE = r\"[^<>,\\s]+<[^<>]+>\"\n        print(\"input: \" + inputtext)\n\n        matches = [m for m in enumerate(re.finditer(simpletypeRE, inputtext))]\n        if len(matches) == 0:\n            if len(typesdict) == 0:\n                typekey = \"$T\" + str(typecount)\n                typesdict[typekey] = inputtext\n            break\n\n        for i, m in matches:\n            tstr = m.group(0)\n\n            typekey = \"$T\" + str(typecount)\n            inputtext = inputtext.replace(tstr, typekey)\n            print(\"updating input text: \" + inputtext)\n            typecount += 1\n            typesdict[typekey] = tstr\n\n    # once the tree is flatterned we may get some template with flat types\n    simpletypeRE = r\"<(.*)>\"\n\n    allbasetypes = set()\n    for tkey in typesdict.keys():\n        flat = typesdict[tkey]\n        print(flat)\n        startindex = flat.index(\"<\")\n        flat = flat[(startindex + 1) : -1]\n        basetypes = [t.strip() for t in flat.split(\",\")]\n        for b in basetypes:\n            if \"$\" not in b:\n                allbasetypes.add(b)\n\n    for b in allbasetypes:\n        typesdict[b] = b\n\n    def replace_back(roottype, typesdict):\n        # replace back\n        while \"$\" in roottype:\n            # print roottype\n            for tkey in typesdict:\n                tval = typesdict[tkey]\n                roottype = roottype.replace(tkey, tval)\n\n        return roottype\n\n    types = []\n    for tkey in typesdict:\n        finaltype = replace_back(typesdict[tkey], typesdict)\n        t = TypeInfo(tkey, typesdict[tkey], finaltype)\n        types.append(t)\n\n        print(t)\n\n    print(typesdict)\n    roottype = [t for t in types if t.finaltype == originalinputtext][0]\n\n    print(\"---------------------------------\")\n\n    # fill template parameters\n    for t in types:\n        for t2 in types:\n            if t2.tkey in t.codedtype:\n                index = t.codedtype.index(t2.tkey)\n                t.template_parameters.append((index, t2))\n\n        t.template_parameters = [x[1] for x in sorted(t.template_parameters, key=lambda e: e[0])]\n\n    return roottype\n\n\ninputtext = \"smacc::Transition<Ev1<LidarSensor<sensor_msgs::LaserScan, std::allocator<none>>, EVTAG>, State1, TAG>\"\nroottypeinfo = getRootTypeInfo(inputtext)\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package smacc_runtime_test\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* 0.9.4\n* noetic versioning update\n* code format and spelling - code quality via pre-commit\n* Merge branch 'master' into noetic-devel\n* fixing some package xmls\n* fixing build with catkin_make\n* updating melodic\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* creating feature smacc_runtime test\n* Contributors: Pablo Iñigo Blasco, Pabo Iñigo Blasco, pabloinigoblasco\n\n0.9.1 (2020-06-29)\n------------------\n\n0.9.0 (2020-06-26)\n------------------\n* build version errors\n* missing changelog files\n* Contributors: Pablo Iñigo Blasco\n\n0.0.1 (2019-11-18)\n------------------\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(smacc_runtime_test)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED roscpp rosgraph_msgs smacc_msgs)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES smacc_runtime_test_node\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/smacc_runtime_test_node.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/smacc_runtime_test_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n)\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# catkin_install_python(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_smacc_runtime_test_node.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/config/state_machine_config_test_file.yaml",
    "content": "state_machine_rosparam_ws: sm_dance_bot\nsuccess_switch:\n   - type: state_reached\n     state_name: state_1\nfailure_switch:\n   - type: timeout\n     duration: 10.0 # sec\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/launch/meta_test.launch",
    "content": "<launch>\n    <node pkg=\"smacc_runtime_test\" name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\" output=\"screen\">\n        <rosparam file=\"$(find smacc_runtime_test)/config/state_machine_config_test_file.yaml\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>smacc_runtime_test</name>\n    <version>1.4.16</version>\n  <description>The smacc_runtime_test package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag -->\n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>BSDv3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/smacc_runtime_test_node</url> -->\n\n\n  <!-- Author tags are optional, multiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintainers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->\n  <!--   <depend>roscpp</depend> -->\n  <!--   Note that this is equivalent to the following: -->\n  <!--   <build_depend>roscpp</build_depend> -->\n  <!--   <exec_depend>roscpp</exec_depend> -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use build_export_depend for packages you need in order to build against this package: -->\n  <!--   <build_export_depend>message_generation</build_export_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use exec_depend for packages you need at runtime: -->\n  <!--   <exec_depend>message_runtime</exec_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <!-- Use doc_depend for packages you need only for building documentation: -->\n  <!--   <doc_depend>doxygen</doc_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>rosgraph_msgs</depend>\n  <depend>smacc_msgs</depend>\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_diagnostics/smacc_runtime_test/src/smacc_runtime_test_node.cpp",
    "content": "#include <ros/ros.h>\n#include <rosgraph_msgs/Log.h>\n#include <smacc_msgs/SmaccTransitionLogEntry.h>\n#include <boost/signals2.hpp>\n#include <memory>\n#include <vector>\n\nclass SmaccTestRuntimeNode;\nclass TimeoutFailureTestPolicy;\nclass ReachedStateSuccessTestPolicy;\n\n//---------------------------------------------------------------------------------------------------\nclass TestPolicy\n{\npublic:\n  SmaccTestRuntimeNode* owner_;\n\n  virtual void init(XmlRpc::XmlRpcValue& initXmlRpcValue)\n  {\n  }\n\n  virtual void update()\n  {\n  }\n};\n//---------------------------------------------------------------------------------------------------\n\nclass SmaccTestRuntimeNode\n{\npublic:\n  ros::NodeHandle nh_;\n  ros::Subscriber rosoutSub_;\n  ros::Subscriber smaccTransitionSub_;\n\n\n  std::vector<std::shared_ptr<TestPolicy>> testPolicies;\n  boost::signals2::signal<void(const rosgraph_msgs::Log&)> onRosOutMsg;\n  boost::signals2::signal<void(const smacc_msgs::SmaccTransitionLogEntry&)> onSmaccTransition;\n\n  template <typename T>\n  std::shared_ptr<TestPolicy> tryTestPolicyFactory(std::string matchname, XmlRpc::XmlRpcValue& initXmlRpcValue)\n  {\n    std::shared_ptr<TestPolicy> policy = nullptr;\n    ROS_INFO_STREAM(initXmlRpcValue);\n\n    auto type = (std::string)initXmlRpcValue[\"type\"];\n\n    if (type == matchname)\n    {\n      auto specificPolicy = std::make_shared<T>();\n      policy = std::dynamic_pointer_cast<TestPolicy>(specificPolicy);\n      testPolicies.push_back(policy);\n\n      policy->owner_ = this;\n      policy->init(initXmlRpcValue);\n    }\n\n    return policy;\n  }\n\n  void init()\n  {\n    ROS_INFO(\"[SmaccTestruntimeNode] subscribing rosout\");\n\n    ros::NodeHandle private_nh(\"~\");\n    std::string stateMachineROSParamWs;\n    if (private_nh.getParam(\"state_machine_rosparam_ws\", stateMachineROSParamWs))\n    {\n      ROS_INFO_STREAM(\"state machine param ws: \" << stateMachineROSParamWs);\n    }\n\n    rosoutSub_ = nh_.subscribe(\"/rosout\", 1, &SmaccTestRuntimeNode::onRosOutCallback, this);\n    smaccTransitionSub_ = nh_.subscribe(stateMachineROSParamWs + \"/smacc/transition_log\", 1, &SmaccTestRuntimeNode::onSmaccTransitionCallback, this);\n\n    XmlRpc::XmlRpcValue successSwitchParam;\n    private_nh.getParam(\"success_switch\", successSwitchParam);\n    ROS_INFO_STREAM(\"[SmaccTestruntimeNode] success switch\" << successSwitchParam);\n    ROS_ASSERT(successSwitchParam.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n    for (int32_t i = 0; i < successSwitchParam.size(); ++i)\n    {\n      auto initXmlRpcValue = successSwitchParam[i];\n      if (tryTestPolicyFactory<ReachedStateSuccessTestPolicy>(\"state_reached\", initXmlRpcValue) != nullptr)\n        continue;\n    }\n\n    XmlRpc::XmlRpcValue failureSwitchParam;\n    private_nh.getParam(\"failure_switch\", failureSwitchParam);\n    ROS_INFO_STREAM(\"[SmaccTestruntimeNode] failure switch\" << failureSwitchParam);\n    ROS_ASSERT(failureSwitchParam.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n    for (int32_t i = 0; i < failureSwitchParam.size(); ++i)\n    {\n      auto initXmlRpcValue = failureSwitchParam[i];\n      if (tryTestPolicyFactory<TimeoutFailureTestPolicy>(\"timeout\", initXmlRpcValue) != nullptr)\n        continue;\n    }\n  }\n  void success(std::string msg)\n  {\n    ROS_INFO_STREAM(\"SmaccRuntimeTestNode policy thrown success exit: \" << msg);\n    exit(-1);\n  }\n\n  void failure(std::string msg)\n  {\n    ROS_FATAL_STREAM(\"SmaccRuntimeTestNode policy thrown failure exit: \" << msg);\n    exit(-1);\n  }\n\n  void update()\n  {\n    for (auto& policy : testPolicies)\n    {\n      policy->update();\n    }\n  }\n\n  void onRosOutCallback(const rosgraph_msgs::Log& msg)\n  {\n      this->onRosOutMsg(msg);\n  }\n\n  void onSmaccTransitionCallback(const smacc_msgs::SmaccTransitionLogEntry& msg)\n  {\n      this->onSmaccTransition(msg);\n  }\n};\n\n//---------------------------------------------------------------------------------------------------\nclass TimeoutFailureTestPolicy : public TestPolicy\n{\n  ros::Duration timeout_;\n  ros::Time startTime_;\n\n  virtual void init(XmlRpc::XmlRpcValue& initXmlRpcValue) override\n  {\n    ROS_INFO(\"[TimeoutFailureTestPolicy] initializating\");\n    startTime_ = ros::Time::now();\n    timeout_ = ros::Duration((double)initXmlRpcValue[\"duration\"]);\n\n    ROS_INFO_STREAM(\"[TimeoutFailureTestPolicy] duration: \" << timeout_);\n  }\n\n  virtual void update()\n  {\n    auto now = ros::Time::now();\n\n    auto elapsed = now - startTime_;\n\n    if (elapsed > timeout_)\n    {\n      this->owner_->failure(std::string(\"timeout failure: \") + std::to_string(timeout_.toSec()));\n    }\n  }\n};\n//---------------------------------------------------------------------------------------------------\nclass ReachedStateSuccessTestPolicy : public TestPolicy\n{\n  std::string targetStateName_;\n  virtual void init(XmlRpc::XmlRpcValue& initXmlRpcValue) override\n  {\n    ROS_INFO(\"[ReachedStateSuccessTestPolicy] initializating\");\n    targetStateName_ = ((std::string)initXmlRpcValue[\"state_name\"]);\n    ROS_INFO_STREAM(\"[ReachedStateSuccessTestPolicy] success state: \" << targetStateName_);\n    this->owner_->onSmaccTransition.connect(\n    [=](auto& msg)\n    {\n        ROS_INFO_STREAM(\"[ReachedStateSuccessTestPolicy] received state: \" << msg.transition.destiny_state_name);\n\n        if(msg.transition.destiny_state_name == targetStateName_)\n        {\n            this->owner_->success(std::string(\"success destiny state \") + targetStateName_);\n        }\n    });\n  }\n\n  virtual void update()\n  {\n\n  }\n};\n//---------------------------------------------------------------------------------------------------\n\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"smacc_runtime_test_node\");\n\n  SmaccTestRuntimeNode testNode;\n  testNode.init();\n\n  ros::Rate r(20);\n\n  while (ros::ok())\n  {\n    testNode.update();\n    ros::spinOnce();\n    r.sleep();\n  }\n  // ros::Subscriber sub = nh.subscribe();\n}\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package smacc_rviz_plugin\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Progressing on transition log\n* progress on viewer, modestates and history mode\n* progress in the viewer and examples\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Added SMACC thumbnail for RViz Plugin\n* creating four rays for dance_bot and media folder missing\n* fixing-moving from cxx version from 17 to 14\n* fixing build\n* missing file\n* testing status message, creation of rviz display plugin, refactoring of sm_dance_bot.launch to make it lightweight, readme.md for launching\n* Contributors: Pablo Iñigo Blasco, brett2@robosoft-ai.com\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(smacc_rviz_plugin)\nfind_package(catkin REQUIRED COMPONENTS rviz smacc_msgs)\ncatkin_package()\ninclude_directories(${catkin_INCLUDE_DIRS})\nlink_directories(${catkin_LIBRARY_DIRS})\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## This setting causes Qt's \"MOC\" generation to happen automatically.\nset(CMAKE_AUTOMOC ON)\n\n## This plugin includes Qt widgets, so we must include Qt.\n## We'll use the version that rviz used so they are compatible.\nif(rviz_QT_VERSION VERSION_LESS \"5\")\n  message(STATUS \"Using Qt4 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}\")\n  find_package(Qt4 ${rviz_QT_VERSION} EXACT REQUIRED QtCore QtGui)\n  ## pull in all required include dirs, define QT_LIBRARIES, etc.\n  include(${QT_USE_FILE})\nelse()\n  message(STATUS \"Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}\")\n  find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets)\n  ## make target_link_libraries(${QT_LIBRARIES}) pull in all required dependencies\n  set(QT_LIBRARIES Qt5::Widgets)\nendif()\n\n## I prefer the Qt signals and slots to avoid defining \"emit\", \"slots\",\n## etc because they can conflict with boost signals, so define QT_NO_KEYWORDS here.\nadd_definitions(-DQT_NO_KEYWORDS)\n\n## Here we specify the list of source files.\n## The generated MOC files are included automatically as headers.\nset(SRC_FILES\n  src/smacc_rviz_display.cpp\n  src/imu_visual.cpp\n)\n\n## An rviz plugin is just a shared library, so here we declare the\n## library to be called ``${PROJECT_NAME}`` (which is\n## \"rviz_plugin_tutorials\", or whatever your version of this project\n## is called) and specify the list of source files we collected above\n## in ``${SRC_FILES}``.\nadd_library(${PROJECT_NAME} ${SRC_FILES})\n\n## Link the myviz executable with whatever Qt libraries have been defined by\n## the ``find_package(Qt4 ...)`` line above, or by the\n## ``set(QT_LIBRARIES Qt5::Widgets)``, and with whatever libraries\n## catkin has included.\n##\n## Although this puts \"rviz_plugin_tutorials\" (or whatever you have\n## called the project) as the name of the library, cmake knows it is a\n## library and names the actual file something like\n## \"librviz_plugin_tutorials.so\", or whatever is appropriate for your\n## particular OS.\ntarget_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES})\n## END_TUTORIAL\n\n## Install rules\n\ninstall(TARGETS\n  ${PROJECT_NAME}\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\ninstall(FILES\n  plugin_description.xml\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\ninstall(DIRECTORY media/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/media)\n\ninstall(DIRECTORY icons/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons)\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/media/.empty",
    "content": ""
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>smacc_rviz_plugin</name>\n    <version>1.4.16</version>\n  <description>The smacc_rviz_plugin package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>qtbase5-dev</build_depend>\n  <build_depend>rviz</build_depend>\n\n  <exec_depend>libqt5-core</exec_depend>\n  <exec_depend>libqt5-gui</exec_depend>\n  <exec_depend>libqt5-widgets</exec_depend>\n  <exec_depend>rviz</exec_depend>\n  <exec_depend>smacc_msgs</exec_depend>\n\n\n\n  <export>\n\n    <rviz plugin=\"${prefix}/plugin_description.xml\"/>\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/plugin_description.xml",
    "content": "<library path=\"libsmacc_rviz_plugin\">\n  <class name=\"smacc_rviz_plugin/SmaccRvizDisplay\"\n         type=\"smacc_rviz_plugin::SmaccRvizDisplay\"\n         base_class_type=\"rviz::Display\">\n    <description>\n    </description>\n        <message_type>smacc_msgs/SmaccStatus</message_type>\n\n  </class>\n</library>\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/src/imu_visual.cpp",
    "content": "/*\n * Copyright (c) 2012, Willow Garage, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n *     * Redistributions of source code must retain the above copyright\n *       notice, this list of conditions and the following disclaimer.\n *     * Redistributions in binary form must reproduce the above copyright\n *       notice, this list of conditions and the following disclaimer in the\n *       documentation and/or other materials provided with the distribution.\n *     * Neither the name of the Willow Garage, Inc. nor the names of its\n *       contributors may be used to endorse or promote products derived from\n *       this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <OGRE/OgreVector3.h>\n#include <OGRE/OgreSceneNode.h>\n#include <OGRE/OgreSceneManager.h>\n\n#include <rviz/ogre_helpers/arrow.h>\n\n#include \"imu_visual.h\"\n\nnamespace smacc_rviz_plugin\n{\n\n// BEGIN_TUTORIAL\nImuVisual::ImuVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node )\n{\n  scene_manager_ = scene_manager;\n\n  // Ogre::SceneNode s form a tree, with each node storing the\n  // transform (position and orientation) of itself relative to its\n  // parent.  Ogre does the math of combining those transforms when it\n  // is time to render.\n  //\n  // Here we create a node to store the pose of the Imu's header frame\n  // relative to the RViz fixed frame.\n  frame_node_ = parent_node->createChildSceneNode();\n\n  // We create the arrow object within the frame node so that we can\n  // set its position and direction relative to its header frame.\n  acceleration_arrow_.reset(new rviz::Arrow( scene_manager_, frame_node_ ));\n}\n\nImuVisual::~ImuVisual()\n{\n  // Destroy the frame node since we don't need it anymore.\n  scene_manager_->destroySceneNode( frame_node_ );\n}\n\nvoid ImuVisual::setMessage( const sensor_msgs::Imu::ConstPtr& msg )\n{\n  const geometry_msgs::Vector3& a = msg->linear_acceleration;\n\n  // Convert the geometry_msgs::Vector3 to an Ogre::Vector3.\n  Ogre::Vector3 acc( a.x, a.y, a.z );\n\n  // Find the magnitude of the acceleration vector.\n  float length = acc.length();\n\n  // Scale the arrow's thickness in each dimension along with its length.\n  Ogre::Vector3 scale( length, length, length );\n  acceleration_arrow_->setScale( scale );\n\n  // Set the orientation of the arrow to match the direction of the\n  // acceleration vector.\n  acceleration_arrow_->setDirection( acc );\n}\n\n// Position and orientation are passed through to the SceneNode.\nvoid ImuVisual::setFramePosition( const Ogre::Vector3& position )\n{\n  frame_node_->setPosition( position );\n}\n\nvoid ImuVisual::setFrameOrientation( const Ogre::Quaternion& orientation )\n{\n  frame_node_->setOrientation( orientation );\n}\n\n// Color is passed through to the Arrow object.\nvoid ImuVisual::setColor( float r, float g, float b, float a )\n{\n  acceleration_arrow_->setColor( r, g, b, a );\n}\n// END_TUTORIAL\n\n} // end namespace rviz_plugin_tutorials\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/src/imu_visual.h",
    "content": "/*\n * Copyright (c) 2012, Willow Garage, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n *     * Redistributions of source code must retain the above copyright\n *       notice, this list of conditions and the following disclaimer.\n *     * Redistributions in binary form must reproduce the above copyright\n *       notice, this list of conditions and the following disclaimer in the\n *       documentation and/or other materials provided with the distribution.\n *     * Neither the name of the Willow Garage, Inc. nor the names of its\n *       contributors may be used to endorse or promote products derived from\n *       this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef IMU_VISUAL_H\n#define IMU_VISUAL_H\n\n#include <sensor_msgs/Imu.h>\n#include <rviz/ogre_helpers/arrow.h>\n\nusing namespace rviz;\nusing namespace Ogre;\n\nnamespace smacc_rviz_plugin\n{\n\n// BEGIN_TUTORIAL\n// Declare the visual class for this display.\n//\n// Each instance of ImuVisual represents the visualization of a single\n// sensor_msgs::Imu message.  Currently it just shows an arrow with\n// the direction and magnitude of the acceleration vector, but could\n// easily be expanded to include more of the message data.\nclass ImuVisual\n{\npublic:\n  // Constructor.  Creates the visual stuff and puts it into the\n  // scene, but in an unconfigured state.\n  ImuVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );\n\n  // Destructor.  Removes the visual stuff from the scene.\n  virtual ~ImuVisual();\n\n  // Configure the visual to show the data in the message.\n  void setMessage( const sensor_msgs::Imu::ConstPtr& msg );\n\n  // Set the pose of the coordinate frame the message refers to.\n  // These could be done inside setMessage(), but that would require\n  // calls to FrameManager and error handling inside setMessage(),\n  // which doesn't seem as clean.  This way ImuVisual is only\n  // responsible for visualization.\n  void setFramePosition( const Ogre::Vector3& position );\n  void setFrameOrientation( const Ogre::Quaternion& orientation );\n\n  // Set the color and alpha of the visual, which are user-editable\n  // parameters and therefore don't come from the Imu message.\n  void setColor( float r, float g, float b, float a );\n\nprivate:\n  // The object implementing the actual arrow shape\n  boost::shared_ptr<rviz::Arrow> acceleration_arrow_;\n\n  // A SceneNode whose pose is set to match the coordinate frame of\n  // the Imu message header.\n  Ogre::SceneNode* frame_node_;\n\n  // The SceneManager, kept here only so the destructor can ask it to\n  // destroy the ``frame_node_``.\n  Ogre::SceneManager* scene_manager_;\n};\n// END_TUTORIAL\n\n} // end namespace rviz_plugin_tutorials\n\n#endif // IMU_VISUAL_H\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/src/smacc_rviz_display.cpp",
    "content": "/*\n * Copyright (c) 2012, Willow Garage, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n *     * Redistributions of source code must retain the above copyright\n *       notice, this list of conditions and the following disclaimer.\n *     * Redistributions in binary form must reproduce the above copyright\n *       notice, this list of conditions and the following disclaimer in the\n *       documentation and/or other materials provided with the distribution.\n *     * Neither the name of the Willow Garage, Inc. nor the names of its\n *       contributors may be used to endorse or promote products derived from\n *       this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <OGRE/OgreSceneNode.h>\n#include <OGRE/OgreSceneManager.h>\n\n#include <tf/transform_listener.h>\n\n#include <rviz/visualization_manager.h>\n#include <rviz/properties/color_property.h>\n#include <rviz/properties/float_property.h>\n#include <rviz/properties/int_property.h>\n#include <rviz/frame_manager.h>\n\n#include \"imu_visual.h\"\n\n#include \"smacc_rviz_display.h\"\n\nnamespace smacc_rviz_plugin\n{\n\n// BEGIN_TUTORIAL\n// The constructor must have no arguments, so we can't give the\n// constructor the parameters it needs to fully initialize.\nSmaccRvizDisplay::SmaccRvizDisplay()\n{\n\n  /*\n  color_property_ = new rviz::ColorProperty( \"Color\", QColor( 204, 51, 204 ),\n                                             \"Color to draw the acceleration arrows.\",\n                                             this, SLOT( updateColorAndAlpha() ));\n\n  alpha_property_ = new rviz::FloatProperty( \"Alpha\", 1.0,\n                                             \"0 is fully transparent, 1.0 is fully opaque.\",\n                                             this, SLOT( updateColorAndAlpha() ));\n\n  history_length_property_ = new rviz::IntProperty( \"History length\", 1,\n                                                    \"Number of prior measurements to display.\",\n                                                    this, SLOT( updateHistoryLength() ));\n                                                    */\n\n  current_state_ = new rviz::StringProperty( \"CurrentState\", \"\",\n                                                    \"current smacc state\",\n                                                    this, SLOT( updateCurrentState() ));\n\n\n  topic_property_ = new rviz::RosTopicProperty( \"Topic\", \"\",\n                                            \"\", \"\",\n                                            this, SLOT( updateTopic() ));\n\n  QString message_type = QString::fromStdString( ros::message_traits::datatype<smacc_msgs::SmaccStatus>() );\n      topic_property_->setMessageType( message_type );\n      topic_property_->setDescription( message_type + \" topic to subscribe to.\" );\n\n\n  //history_length_property_->setMin( 1 );\n  //history_length_property_->setMax( 100000 );\n}\n\n  void SmaccRvizDisplay::updateTopic()\n  {\n    unsubscribe();\n    reset();\n    subscribe();\n    context_->queueRender();\n  }\n\n  void SmaccRvizDisplay::subscribe()\n  {\n      current_state_->setValue(QString(\"\"));\n      sub_ = nh_.subscribe<smacc_msgs::SmaccStatus>(topic_property_->getTopic().toStdString(), 1, &SmaccRvizDisplay::processMessage , this);\n  }\n\n  void SmaccRvizDisplay::unsubscribe()\n  {\n    current_state_->setValue(QString(\"\"));\n    sub_.shutdown();\n\n  }\n// After the top-level rviz::Display::initialize() does its own setup,\n// it calls the subclass's onInitialize() function.  This is where we\n// instantiate all the workings of the class.  We make sure to also\n// call our immediate super-class's onInitialize() function, since it\n// does important stuff setting up the message filter.\n//\n//  Note that \"MFDClass\" is a typedef of\n// ``MessageFilterDisplay<message type>``, to save typing that long\n// templated class name every time you need to refer to the\n// superclass.\nvoid SmaccRvizDisplay::onInitialize()\n{\n  //MFDClass::onInitialize();\n  current_state_->setValue(QString(\"\"));\n}\n\nSmaccRvizDisplay::~SmaccRvizDisplay()\n{\n}\n\n// Clear the visuals by deleting their objects.\nvoid SmaccRvizDisplay::reset()\n{\n  //MFDClass::reset();\n  //visuals_.clear();\n  current_state_->setValue(QString(\"\"));\n}\n\nvoid SmaccRvizDisplay::updateCurrentState()\n{\n}\n\n// This is our callback to handle an incoming message.\nvoid SmaccRvizDisplay::processMessage( const smacc_msgs::SmaccStatus::ConstPtr& msg )\n{\n  std::string concatenated;\n\n  for(auto& state: msg->current_states)\n  {\n    concatenated = concatenated + std::string(\"/\")+ state;\n  }\n\n  ROS_DEBUG(\"current state: %s\", concatenated.c_str());\n  current_state_->setValue(QString(concatenated.c_str()));\n  // Here we call the rviz::FrameManager to get the transform from the\n  // fixed frame to the frame in the header of this Imu message.  If\n  // it fails, we can't do anything else so we return.\n  /*\n  Ogre::Quaternion orientation;\n  Ogre::Vector3 position;\n  if( !context_->getFrameManager()->getTransform( msg->header.frame_id,\n                                                  msg->header.stamp,\n                                                  position, orientation ))\n  {\n    ROS_DEBUG( \"Error transforming from frame '%s' to frame '%s'\",\n               msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));\n    return;\n  }\n\n  // We are keeping a circular buffer of visual pointers.  This gets\n  // the next one, or creates and stores it if the buffer is not full\n  boost::shared_ptr<ImuVisual> visual;\n  if( visuals_.full() )\n  {\n    visual = visuals_.front();\n  }\n  else\n  {\n    visual.reset(new ImuVisual( context_->getSceneManager(), scene_node_ ));\n  }*/\n\n  // Now set or update the contents of the chosen visual.\n  //visual->setMessage( msg );\n  //visual->setFramePosition( position );\n  //visual->setFrameOrientation( orientation );\n\n  /*\n  float alpha = alpha_property_->getFloat();\n  Ogre::ColourValue color = color_property_->getOgreColor();\n  visual->setColor( color.r, color.g, color.b, alpha );\n\n  // And send it to the end of the circular buffer\n  visuals_.push_back(visual);\n  */\n}\n\n} // end namespace rviz_plugin_tutorials\n\n// Tell pluginlib about this class.  It is important to do this in\n// global scope, outside our package's namespace.\n#include <pluginlib/class_list_macros.h>\nPLUGINLIB_EXPORT_CLASS(smacc_rviz_plugin::SmaccRvizDisplay,rviz::Display )\n// END_TUTORIAL\n"
  },
  {
    "path": "smacc_diagnostics/smacc_rviz_plugin/src/smacc_rviz_display.h",
    "content": "/*\n * Copyright (c) 2012, Willow Garage, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n *     * Redistributions of source code must retain the above copyright\n *       notice, this list of conditions and the following disclaimer.\n *     * Redistributions in binary form must reproduce the above copyright\n *       notice, this list of conditions and the following disclaimer in the\n *       documentation and/or other materials provided with the distribution.\n *     * Neither the name of the Willow Garage, Inc. nor the names of its\n *       contributors may be used to endorse or promote products derived from\n *       this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef IMU_DISPLAY_H\n#define IMU_DISPLAY_H\n\n#ifndef Q_MOC_RUN\n#include <ros/ros.h>\n#include <ros/network.h>\n#endif\n\n#include <boost/circular_buffer.hpp>\n\n#include <smacc_msgs/SmaccStatus.h>\n#include <rviz/message_filter_display.h>\n#include <rviz/ogre_helpers/arrow.h>\n\n\nusing namespace Ogre;\nusing namespace rviz;\n\n// All the source in this plugin is in its own namespace.  This is not\n// required but is good practice.\nnamespace smacc_rviz_plugin\n{\n\nclass ImuVisual;\n\n// BEGIN_TUTORIAL\n// Here we declare our new subclass of rviz::Display.  Every display\n// which can be listed in the \"Displays\" panel is a subclass of\n// rviz::Display.\n//\n// SmaccRvizDisplay will show a 3D arrow showing the direction and magnitude\n// of the IMU acceleration vector.  The base of the arrow will be at\n// the frame listed in the header of the Imu message, and the\n// direction of the arrow will be relative to the orientation of that\n// frame.  It will also optionally show a history of recent\n// acceleration vectors, which will be stored in a circular buffer.\n//\n// The SmaccRvizDisplay class itself just implements the circular buffer,\n// editable parameters, and Display subclass machinery.  The visuals\n// themselves are represented by a separate class, ImuVisual.  The\n// idiom for the visuals is that when the objects exist, they appear\n// in the scene, and when they are deleted, they disappear.\nclass SmaccRvizDisplay: public rviz::Display\n{\nQ_OBJECT\npublic:\n  // Constructor.  pluginlib::ClassLoader creates instances by calling\n  // the default constructor, so make sure you have one.\n  SmaccRvizDisplay();\n  virtual ~SmaccRvizDisplay();\n\n  virtual void subscribe();\n  virtual void unsubscribe();\n\n  // Overrides of protected virtual functions from Display.  As much\n  // as possible, when Displays are not enabled, they should not be\n  // subscribed to incoming data and should not show anything in the\n  // 3D view.  These functions are where these connections are made\n  // and broken.\nprotected:\n  virtual void onInitialize();\n\n  // A helper to clear this display back to the initial state.\n  virtual void reset();\n\n  // These Qt slots get connected to signals indicating changes in the user-editable properties.\nprivate Q_SLOTS:\n  void updateCurrentState();\n  void updateTopic();\n\n  // Function to handle an incoming ROS message.\nprivate:\n\n  void processMessage( const smacc_msgs::SmaccStatus::ConstPtr& msg );\n\n  // Storage for the list of visuals.  It is a circular buffer where\n  // data gets popped from the front (oldest) and pushed to the back (newest)\n  //boost::circular_buffer<boost::shared_ptr<ImuVisual> > visuals_;\n\n  // User-editable property variables.\n  /*\n  rviz::ColorProperty* color_property_;\n  rviz::FloatProperty* alpha_property_;\n  rviz::IntProperty* history_length_property_;\n  */\n\n  rviz::StringProperty* current_state_;\n  rviz::RosTopicProperty* topic_property_ ;\n  ros::NodeHandle nh_;\n  ros::Subscriber sub_;\n};\n// END_TUTORIAL\n\n} // end namespace rviz_plugin_tutorials\n\n#endif // IMU_DISPLAY_H\n// %EndTag(FULL_SOURCE)%\n"
  },
  {
    "path": "smacc_event_generator_library/eg_conditional_generator/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package eg_random_generator\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "smacc_event_generator_library/eg_conditional_generator/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(eg_conditional_generator)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES eg_conditional_generator\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/eg_conditional_generator.cpp\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/eg_conditional_generator_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_eg_conditional_generator.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_event_generator_library/eg_conditional_generator/include/eg_conditional_generator/eg_conditional_generator.h",
    "content": "#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_event_generator.h>\n#include <smacc/smacc_updatable.h>\n#include <typeinfo>\n#include <boost/statechart/event.hpp>\n#include <functional>\n\nnamespace smacc\n{\n    namespace event_generators\n    {\n        template <typename TSource, typename TState>\n        struct EvTrue : sc::event<EvTrue<TSource, TState>>\n        {\n        };\n\n        template <typename TSource, typename TState>\n        struct EvFalse : sc::event<EvFalse<TSource, TState>>\n        {\n        };\n\n        enum class ConditionalGeneratorMode\n        {\n            ONE_SHOT,\n            ON_UPDATE\n        };\n\n        //-----------------------------------------------------------------------\n        class EgConditionalGenerator : public smacc::SmaccEventGenerator, public ISmaccUpdatable\n        {\n        public:\n            EgConditionalGenerator(ConditionalGeneratorMode mode, std::function <bool()> updatePredicate = nullptr);\n\n            virtual void onEntry() override;\n\n            template <typename TState, typename TSource>\n            void onStateAllocation()\n            {\n                this->postEventTrue = [this]() { this->postEvent<EvTrue<TSource, TState>>(); };\n                this->postEventFalse = [this]() { this->postEvent<EvFalse<TSource, TState>>(); };\n            }\n\n            virtual void update() override;\n            ConditionalGeneratorMode mode_;\n\n            void setPredicateFunction(std::function <bool()> updatePredicate);\n\n        private:\n            void checkPredicateAndPost();\n            std::function<void()> postEventTrue;\n            std::function<void()> postEventFalse;\n            std::function<bool()> updatePredicate_;\n        };\n    } // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_event_generator_library/eg_conditional_generator/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>eg_conditional_generator</name>\n    <version>1.4.16</version>\n  <description>The eg_conditional_generator package</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n  <license>BSD-3</license>\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/eg_conditional_generator</url> -->\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>catkin</depend>\n  <depend>smacc</depend>\n  <export>\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_event_generator_library/eg_conditional_generator/src/eg_conditional_generator/eg_conditional_generator.cpp",
    "content": "#include <eg_conditional_generator/eg_conditional_generator.h>\n\nnamespace smacc\n{\n    namespace event_generators\n    {\n        EgConditionalGenerator::EgConditionalGenerator(ConditionalGeneratorMode mode, std::function <bool()> updatePredicate)\n            :mode_(mode),\n            updatePredicate_(updatePredicate)\n        {\n\n        }\n\n        void EgConditionalGenerator::checkPredicateAndPost()\n        {\n            if(this->updatePredicate_())\n            {\n                this->postEventTrue();\n            }\n            else\n            {\n                this->postEventFalse();\n            }\n        }\n\n        void EgConditionalGenerator::onEntry()\n        {\n            if (mode_ == ConditionalGeneratorMode::ONE_SHOT)\n            {\n                this->checkPredicateAndPost();\n            }\n        }\n\n        void EgConditionalGenerator::update()\n        {\n            if (mode_ == ConditionalGeneratorMode::ON_UPDATE)\n            {\n                this->checkPredicateAndPost();\n            }\n        }\n\n        void EgConditionalGenerator::setPredicateFunction(std::function <bool()> updatePredicate)\n        {\n            updatePredicate_ = updatePredicate;\n        }\n\n    } // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_event_generator_library/eg_random_generator/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package eg_random_generator\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "smacc_event_generator_library/eg_random_generator/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(eg_random_generator)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES eg_random_generator\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/eg_random_generator.cpp\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/eg_random_generator_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_eg_random_generator.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_event_generator_library/eg_random_generator/include/eg_random_generator/eg_random_generator.h",
    "content": "#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_event_generator.h>\n#include <smacc/smacc_updatable.h>\n#include <typeinfo>\n#include <boost/statechart/event.hpp>\n#include <functional>\n\nnamespace smacc\n{\n    namespace state_reactors\n    {\n        template <typename TSource, typename TState>\n        struct EventA : sc::event<EventA<TSource, TState>>\n        {\n        };\n\n        template <typename TSource, typename TState>\n        struct EventB : sc::event<EventB<TSource, TState>>\n        {\n        };\n\n        template <typename TSource, typename TState>\n        struct EventC : sc::event<EventC<TSource, TState>>\n        {\n        };\n\n        enum class RandomGenerateReactorMode\n        {\n            INPUT_EVENT_TRIGGERED,\n            ONE_SHOT,\n            ON_UPDATE\n        };\n\n        //-----------------------------------------------------------------------\n        class EgRandomGenerator : public SmaccEventGenerator, public ISmaccUpdatable\n        {\n        public:\n            EgRandomGenerator(RandomGenerateReactorMode mode, double evAMin = 1, double evAMax = 4, double evBMin = 5, double evBMax = 8, double evCMin = 9, double evCMax = 12);\n\n            virtual void onEntry() override;\n\n            template <typename TState, typename TSource>\n            void onStateAllocation()\n            {\n                this->postEventA = [this]() { this->postEvent<EventA<TSource, TState>>(); };\n                this->postEventB = [this]() { this->postEvent<EventB<TSource, TState>>(); };\n                this->postEventC = [this]() { this->postEvent<EventC<TSource, TState>>(); };\n            }\n\n            void postRandomEvents();\n\n            virtual void update() override;\n\n            RandomGenerateReactorMode mode_;\n\n        private:\n            std::function<void()> postEventA;\n            std::function<void()> postEventB;\n            std::function<void()> postEventC;\n\n            double evAMin_;\n            double evAMax_;\n            double evBMin_;\n            double evBMax_;\n            double evCMin_;\n            double evCMax_;\n\n            double minValue;\n            double maxValue;\n        };\n    } // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_event_generator_library/eg_random_generator/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>eg_random_generator</name>\n    <version>1.4.16</version>\n  <description>The eg_random_generator package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/eg_random_generator</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>catkin</depend>\n  <depend>smacc</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_event_generator_library/eg_random_generator/src/eg_random_generator/eg_random_generator.cpp",
    "content": "#include <eg_random_generator/eg_random_generator.h>\n\nnamespace smacc\n{\n    namespace state_reactors\n    {\n        EgRandomGenerator::EgRandomGenerator(RandomGenerateReactorMode mode, double evAMin, double evAMax, double evBMin, double evBMax, double evCMin, double evCMax)\n            :\n              mode_(mode),\n              evAMin_(evAMin),\n              evAMax_(evAMax),\n              evBMin_(evBMin),\n              evBMax_(evBMax),\n              evCMin_(evCMin),\n              evCMax_(evCMax)\n        {\n\n            auto values = {evAMin, evAMax, evBMin, evBMax, evCMin, evCMax};\n\n            this->minValue = std::numeric_limits<double>::max();\n            this->maxValue = std::numeric_limits<double>::min();\n            for (auto &v : values)\n            {\n                if (v < minValue)\n                {\n                    minValue = v;\n                }\n\n                if (v > maxValue)\n                {\n                    maxValue = v;\n                }\n            }\n        }\n\n        void EgRandomGenerator::postRandomEvents()\n        {\n            int range = this->maxValue - this->minValue;\n            int result = (rand() % range) + minValue;\n\n            if (result >= evAMin_ && result <= evAMax_)\n            {\n                this->postEventA();\n            }\n\n            if (result >= evBMin_ && result <= evBMax_)\n            {\n                this->postEventB();\n            }\n\n            if (result >= evCMin_ && result <= evCMax_)\n            {\n                this->postEventC();\n            }\n        }\n\n        void EgRandomGenerator::onEntry()\n        {\n            if (mode_ == RandomGenerateReactorMode::ONE_SHOT)\n            {\n                this->postRandomEvents();\n            }\n        }\n\n        void EgRandomGenerator::update()\n        {\n            if (mode_ == RandomGenerateReactorMode::ON_UPDATE)\n            {\n                this->postRandomEvents();\n            }\n        }\n    } // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_msgs/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package smacc_msgs\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* removing error changelog\n* Contributors: Pablo Iñigo Blasco\n\n* removing error changelog\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_msgs/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\n\nproject(smacc_msgs)\n\nfind_package(catkin REQUIRED COMPONENTS\n  message_generation std_msgs)\n\nadd_message_files(FILES\n  SmaccSMCommand.msg\n  SmaccStatus.msg\n  SmaccContainerInitialStatusCmd.msg\n  SmaccContainerStructure.msg\n  SmaccContainerStatus.msg\n\n  SmaccState.msg\n  SmaccTransition.msg\n  SmaccEvent.msg\n  SmaccOrthogonal.msg\n  SmaccStateReactor.msg\n  SmaccEventGenerator.msg\n  SmaccStateMachine.msg\n  SmaccTransitionLogEntry.msg\n  )\n\n add_service_files(\n   FILES\n   SmaccGetTransitionHistory.srv\n )\n\ngenerate_messages(DEPENDENCIES std_msgs)\n\ncatkin_package(CATKIN_DEPENDS message_runtime)\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccContainerInitialStatusCmd.msg",
    "content": "# The path to the node in the server\nstring path\n\n# The desired initial state(s)\nstring[] initial_states\n\n# Initial values for the local user data of the state machine\n# A pickled user data structure\n# i.e. the UserData's internal dictionary\nstring local_data\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccContainerStatus.msg",
    "content": "Header header\n\n# The path to this node in the server\nstring path\n\n# The initial state description\n# Effects an arc from the top state to each one\nstring[] initial_states\n\n# The current state description\nstring[] active_states\n\n# A pickled user data structure\n# i.e. the UserData's internal dictionary\nstring local_data\n\n# Debugging info string\nstring info\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccContainerStructure.msg",
    "content": "Header header\n\n# The path to this node in the server\nstring path\n\n# The children of this node\nstring[] children\n\n# The outcome edges\n# Each index across these arrays denote one edge\nstring[] internal_outcomes\nstring[] outcomes_from\nstring[] outcomes_to\n\n# The potential outcomes from this container\nstring[] container_outcomes\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccEvent.msg",
    "content": "string event_type\nstring event_object_tag\nstring event_source # the client, client behavior or component that generated that event\nstring label\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccEventGenerator.msg",
    "content": "int32 index\nstring type_name\nstring object_tag\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccOrthogonal.msg",
    "content": "string name\nstring[] client_behavior_names\nstring[] client_names\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccSMCommand.msg",
    "content": "int8 command\n\nint8 SM_STOP = 0\nint8 E_STOP = 0\nint8 SM_RESET = 1\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccState.msg",
    "content": "int32 index\nstring name\nstring[] children_states\nint8 level\nsmacc_msgs/SmaccTransition[] transitions\nsmacc_msgs/SmaccOrthogonal[] orthogonals\nsmacc_msgs/SmaccStateReactor[] state_reactors\nsmacc_msgs/SmaccEventGenerator[] event_generators\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccStateMachine.msg",
    "content": "smacc_msgs/SmaccState[] states\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccStateReactor.msg",
    "content": "int32 index\nstring type_name\nstring object_tag\n\nsmacc_msgs/SmaccEvent[] event_sources\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccStatus.msg",
    "content": "std_msgs/Header header\n\n#returns the list of current states (the complete hierarchy)\n#from ancestor active states to descendents active states), ie: [Superstate1, State3]\nstring[] current_states\n\nstring[] global_variable_names\nstring[] global_variable_values\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccTransition.msg",
    "content": "int32 index\nstring transition_name\nstring transition_type\nstring destiny_state_name\nstring source_state_name\nbool history_node\nsmacc_msgs/SmaccEvent event\n"
  },
  {
    "path": "smacc_msgs/msg/SmaccTransitionLogEntry.msg",
    "content": "time timestamp\nsmacc_msgs/SmaccTransition transition\n"
  },
  {
    "path": "smacc_msgs/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>smacc_msgs</name>\n    <version>1.4.16</version>\n  <description>\n    this package contains a set of messages that are used by the introspection\n    interfaces for smacc.\n  </description>\n\n\n  <license>BSD</license>\n\n  <author>Brett Aldrich</author>\n  <author>Pablo Iñigo Blasco</author>\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>std_msgs</depend>\n\n  <build_depend>message_generation</build_depend>\n\n  <exec_depend>message_runtime</exec_depend>\n  <build_export_depend>message_runtime</build_export_depend>\n\n\n  <export>\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_msgs/srv/SmaccGetTransitionHistory.srv",
    "content": "---\nsmacc_msgs/SmaccTransitionLogEntry[] history\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_atomic\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_atomic)\n\n## Find catkin macros and libraries\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package()\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n  include\n  ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ executable\nadd_executable(${PROJECT_NAME}_node src/sm_atomic_node.cpp)\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}_node\n  ${catkin_LIBRARIES}\n)\n\n#############\n## Install ##\n#############\n\n## Mark executables for installation\ninstall(TARGETS ${PROJECT_NAME}_node\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark other files for installation (e.g. launch and config files, etc.)\ninstall(FILES\n  launch/sm_atomic.launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n  config/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_atomic/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_atomic sm_atomic.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/config/sm_atomic_config.yaml",
    "content": "SmAtomic:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/config/sm_atomic_test.yaml",
    "content": "state_machine_rosparam_ws: /SmAtomic\nsuccess_switch:\n   - type: state_reached\n     state_name: \"sm_atomic::State2\"\nfailure_switch:\n   - type: timeout\n     duration: 10.0 # sec\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/include/sm_atomic/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_atomic\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_atomic\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/include/sm_atomic/sm_atomic.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_atomic/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_atomic\n{\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmAtomic\n    : public smacc::SmaccStateMachineBase<SmAtomic, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n    }\n};\n\n} // namespace sm_atomic\n\n#include <sm_atomic/states/st_state_1.h>\n#include <sm_atomic/states/st_state_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/include/sm_atomic/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmAtomic>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State2, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownLoop>(3);  // EvTimer triggers each 3 client ticks\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_atomic\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/include/sm_atomic/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, SmAtomic>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State1, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Entering State2\");\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/launch/sm_atomic.launch",
    "content": "<launch>\n\n    <rosparam command=\"load\" file=\"$(find sm_atomic)/config/sm_atomic_config.yaml\" />\n    <node pkg=\"sm_atomic\" type=\"sm_atomic_node\" name=\"sm_atomic\"/>\n        <node pkg=\"smacc_runtime_test\" name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\" output=\"screen\">\n        <rosparam file=\"$(find sm_atomic)/config/sm_atomic_test.yaml\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_atomic</name>\n    <version>1.4.16</version>\n  <description>The sm_atomic package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_atomic</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n  <depend>xterm</depend>\n  <depend>smacc_runtime_test</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/src/sm_atomic_node.cpp",
    "content": "#include <sm_atomic/sm_atomic.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_atomic\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_atomic::SmAtomic>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic/test/sm_atomic.test",
    "content": "<launch>\n<include file=\"$(find sm_atomic)/launch/sm_atomic.launch\"/>\n    <test pkg=\"smacc_runtime_test\" test-name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\">\n        <rosparam file=\"$(find sm_atomic)/config/sm_atomic_test.yaml\"/>\n    </test>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_atomic_cb\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Updated CbTimer CB function Comments\n* Final CbTimer Push\n* Contributors: Brett Aldrich, Unknown\n\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Updated CbTimer CB function Comments\n* Final CbTimer Push\n* Contributors: Brett Aldrich, Unknown\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_atomic_cb)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_atomic_cb\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_atomic_cb.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_atomic_cb_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_atomic_cb.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic_cb.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_atomic_cb/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_atomic_cb sm_atomic_cb.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/config/sm_atomic_cb_config.yaml",
    "content": "SmAtomicCB:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/include/sm_atomic_cb/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_atomic_cb\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_atomic_cb\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/include/sm_atomic_cb/sm_atomic_cb.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_atomic_cb/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_atomic_cb\n{\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmAtomicCB\n    : public smacc::SmaccStateMachineBase<SmAtomicCB, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n    }\n};\n\n} // namespace sm_atomic_cb\n\n#include <sm_atomic_cb/states/st_state_1.h>\n#include <sm_atomic_cb/states/st_state_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/include/sm_atomic_cb/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_cb\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmAtomicCB>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State2, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownLoop>(3);  // EvTimer triggers each 3 client ticks\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n        // get reference to the client\n        ClRosTimer *client;\n        this->requiresClient(client);\n\n        // subscribe to the timer client callback\n        client->onTimerTick(&State1::onTimerClientTickCallback, this);\n\n        // getting reference to the repeat countdown behavior\n        auto *cbrepeat = this->getOrthogonal<OrTimer>()\n                             ->getClientBehavior<CbTimerCountdownLoop>();\n\n        // subscribe to the repeat countdown behavior callback\n        cbrepeat->onTimerTick(&State1::onRepeatBehaviorTickCallback, this);\n\n        // getting reference to the single countdown behavior\n        auto *cbsingle = this->getOrthogonal<OrTimer>()\n                             ->getClientBehavior<CbTimerCountdownOnce>();\n\n        // subscribe to the single countdown behavior callback\n        cbsingle->onTimerTick(&State1::onSingleBehaviorTickCallback, this);\n    }\n\n    // fire callback function\n    void onTimerClientTickCallback()\n    {\n        ROS_INFO(\"timer client tick!\");\n    }\n\n    // fire callback function\n    void onRepeatBehaviorTickCallback()\n    {\n        ROS_INFO(\"repeat behavior tick!\");\n    }\n\n    // fire callback function\n    void onSingleBehaviorTickCallback()\n    {\n        ROS_INFO(\"single behavior tick!\");\n    }\n};\n} // namespace sm_atomic_cb\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/include/sm_atomic_cb/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_cb\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, SmAtomicCB>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State1, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Entering State2\");\n\n        // get reference to the client\n        ClRosTimer *client;\n        this->requiresClient(client);\n\n        // subscribe to the timer client callback\n        client->onTimerTick(&State2::onTimerClientTickCallback, this);\n\n         // getting reference to the single countdown behavior\n        auto *cbsingle = this->getOrthogonal<OrTimer>()\n                             ->getClientBehavior<CbTimerCountdownOnce>();\n\n        // subscribe to the single countdown behavior callback\n        cbsingle->onTimerTick(&State2::onSingleBehaviorTickCallback, this);\n    }\n\n    // fire callback function\n    void onTimerClientTickCallback()\n    {\n        ROS_INFO(\"timer client tick!\");\n    }\n\n    // fire callback function\n    void onSingleBehaviorTickCallback()\n    {\n        ROS_INFO(\"single behavior tick!\");\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/launch/sm_atomic_cb.launch",
    "content": "<launch>\n    <rosparam command=\"load\" file=\"$(find sm_atomic_cb)/config/sm_atomic_cb_config.yaml\" />\n    <node pkg=\"sm_atomic_cb\" type=\"sm_atomic_cb_node\" name=\"sm_atomic_cb\"/>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_atomic_cb</name>\n    <version>1.4.16</version>\n  <description>The sm_atomic_cb package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_atomic_cb</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n  <depend>xterm</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_cb/src/sm_atomic_cb_node.cpp",
    "content": "#include <sm_atomic_cb/sm_atomic_cb.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_atomic_cb\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_atomic_cb::SmAtomicCB>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_atomic_mode_states\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic_mode_states diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic_mode_states\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic_mode_states\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic_mode_states and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic_mode_states diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic_mode_states\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic_mode_states\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic_mode_states and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_atomic_mode_states)\n\n## Find catkin macros and libraries\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n###################################\n## catkin specific configuration ##\n###################################\ncatkin_package()\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n  include\n  ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ executable\nadd_executable(${PROJECT_NAME}_node src/sm_atomic_node.cpp)\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}_node\n  ${catkin_LIBRARIES}\n)\n\n#############\n## Install ##\n#############\n\n## Mark executables for installation\ninstall(TARGETS ${PROJECT_NAME}_node\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark other files for installation (e.g. launch and config files, etc.)\ninstall(FILES\n  launch/sm_atomic_mode_states.launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n  config/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_atomic_mode_states/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_atomic_mode_states sm_atomic_mode_states.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/config/sm_atomic_config.yaml",
    "content": "SmAtomic:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/config/sm_atomic_test.yaml",
    "content": "state_machine_rosparam_ws: /SmAtomic\nsuccess_switch:\n   - type: state_reached\n     state_name: \"sm_atomic_mode_states::State2\"\nfailure_switch:\n   - type: timeout\n     duration: 10.0 # sec\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/client_behaviors/cb_updatable_test.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n\nclass CbUpdatableTest : public smacc::ISmaccUpdatable, public smacc::ISmaccClientBehavior\n{\npublic:\n    CbUpdatableTest()\n    {\n        this->counter_ = 0;\n    }\n\n    virtual void onEntry()\n    {\n        ROS_INFO(\"CbUpdatableTest::onEntry\");\n    }\n\n    virtual void onExit()\n    {\n        ROS_INFO(\"CbUpdatableTest::onExit\");\n    }\n\n    virtual void update() override\n    {\n        auto currentState = this->getCurrentState();\n        this->counter_++;\n        ROS_INFO(\"CbUpdatableTest::onUpdate %d in state %s\", this->counter_, currentState->getClassName().c_str());\n    }\n\n    int counter_;\n};\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_atomic_mode_states\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_atomic_mode_states\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/sm_atomic_mode_states.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_atomic_mode_states/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n#include <sm_atomic_mode_states/client_behaviors/cb_updatable_test.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_atomic_mode_states\n{\n\n//STATE\nclass State1;\nclass State2;\nclass MsState1;\nclass MsState2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmAtomic\n    : public smacc::SmaccStateMachineBase<SmAtomic, MsState1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n    }\n};\n\n} // namespace sm_atomic_mode_states\n\n#include <sm_atomic_mode_states/states/ms_state_1.h>\n#include <sm_atomic_mode_states/states/ms_state_2.h>\n\n#include <sm_atomic_mode_states/states/st_state_1.h>\n#include <sm_atomic_mode_states/states/st_state_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/states/ms_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_mode_states\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct MsState1 : smacc::SmaccState<MsState1, SmAtomic, State1>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbUpdatableTest>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_atomic_mode_states\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/states/ms_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_mode_states\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct MsState2 : smacc::SmaccState<MsState2, SmAtomic, State2>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbUpdatableTest>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_atomic_mode_states\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_mode_states\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, MsState1>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, MsState2, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownLoop>(3);  // EvTimer triggers each 3 client ticks\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(2); // EvTimer triggers once at 10 client ticks\n        configure_orthogonal<OrTimer, CbUpdatableTest>();\n\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_atomic_mode_states\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/include/sm_atomic_mode_states/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_mode_states\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, MsState2>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, MsState1, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(2); // EvTimer triggers once at 10 client ticks\n        configure_orthogonal<OrTimer, CbUpdatableTest>();\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Entering State2\");\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/launch/sm_atomic_mode_states.launch",
    "content": "<launch>\n\n    <rosparam command=\"load\" file=\"$(find sm_atomic_mode_states)/config/sm_atomic_config.yaml\" />\n    <node pkg=\"sm_atomic_mode_states\" type=\"sm_atomic_mode_states_node\" name=\"sm_atomic_mode_states\"/>\n\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_atomic_mode_states</name>\n    <version>1.4.16</version>\n  <description>The sm_atomic_mode_states package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_atomic_mode_states</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n  <depend>xterm</depend>\n  <depend>smacc_runtime_test</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/src/sm_atomic_node.cpp",
    "content": "#include <sm_atomic_mode_states/sm_atomic_mode_states.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_atomic_mode_states\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_atomic_mode_states::SmAtomic>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_mode_states/test/sm_atomic.test",
    "content": "<launch>\n<include file=\"$(find sm_atomic_mode_states)/launch/sm_atomic_mode_states.launch\"/>\n    <test pkg=\"smacc_runtime_test\" test-name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\">\n        <rosparam file=\"$(find sm_atomic_mode_states)/config/sm_atomic_test.yaml\"/>\n    </test>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_atomic\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n\n* creating feature smacc_runtime test\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* Final CbTimer Push\n* Merge branch 'master' into melodic-devel\n* fixed Doxygen Client Namespaces\n* refactoring client namespaces names\n* Merge branch 'master' into melodic-devel\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* sm_atomic diagrams\n* Update README.md\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Improved sm_atomic\n* more formatting & commenting\n* renaming runtimeConfiguration to runtimeConfigure\n* pushing renaming of runtimeConfigure\n* more on smacc behaviors\n* Changed static_configure to configure_orthogonal\n* unpushed code\n* Replaced all smacc::transition's with Transition\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* Update README.md\n* Adding sm images\n* Update README.md\n* Update README.md\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Update README.md\n* adding launch file to sm_atomic\n* Renaming transition\n* sm dance bot and refactoring namings\n* namespaces iteration 3, orthogonal recurrent pattern, more tsts on sm_dance_bot_2\n* more refactoring and renaming examples and namespaces\n* progressing in the API and testing timers and callbacks\n* ros timer client behaviors, refactoring sm_atomic and logic unit hierarchy. other improvements on rosout\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Update README.md\n* Create README.md\n* more naming refactoring in move_base_z_client\n* renaming move_base client to ClMoveBaseZ (zorro)\n* renaming orthogonals\n* more on refactoring renaming\n* adding object tagging to clients, specifically action clients\n* renaming consistently SmAtomic\n* testing countdown logic unit more refactoring and analyzing propagating issue\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Pabo Iñigo Blasco, Unknown, Víctor Ferrer García, brett2@robosoft-ai.com, brettpac, pablo.inigo.blasco, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_atomic_services)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_atomic\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_atomic.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_atomic_services_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_atomic_services.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_atomic_services/docs/smacc_state_machine_20220330-064659.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic__services.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_atomic_services sm_atomic_services.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/config/sm_atomic_services_config.yaml",
    "content": "SmAtomicServices:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/config/sm_atomic_services_test.yaml",
    "content": "state_machine_rosparam_ws: /SmAtomicServices\nsuccess_switch:\n   - type: state_reached\n     state_name: \"sm_atomic_services::State2\"\nfailure_switch:\n   - type: timeout\n     duration: 10.0 # sec\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/clients/cl_service_client.h",
    "content": "#include <smacc/smacc.h>\n#include <smacc/client_bases/smacc_service_client.h>\n\n#include <std_srvs/Empty.h>\n\nnamespace sm_atomic_services\n{\n    class ClServiceClient : public smacc::client_bases::SmaccServiceClient<std_srvs::Empty>\n    {\n        public:\n          ClServiceClient(const std::string& service_name) : smacc::client_bases::SmaccServiceClient<std_srvs::Empty>(service_name) {}\n    };\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/clients/cl_service_server.h",
    "content": "#include <smacc/smacc.h>\n#include <smacc/client_bases/smacc_service_server_client.h>\n\n#include <std_srvs/Empty.h>\n\nnamespace sm_atomic_services\n{\n    class ClServiceServer : public smacc::client_bases::SmaccServiceServerClient<std_srvs::Empty>\n    {\n        public:\n          ClServiceServer(const std::string& service_name) : smacc::client_bases::SmaccServiceServerClient<std_srvs::Empty>(service_name) {}\n    };\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/clients/client_behaviors/cb_service_server.h",
    "content": "#include <smacc/client_behavior_bases/cb_service_server_callback_base.h>\n#include <smacc/smacc_client_behavior.h>\n\nnamespace sm_atomic_services\n{\n    template <typename TSource, typename TOrthogonal>\n    struct EvServiceRequestReceieved : sc::event<EvServiceRequestReceieved<TSource, TOrthogonal>> {};\n\n    class CbServiceServer : public smacc::CbServiceServerCallbackBase<std_srvs::Empty>\n    {\n      public:\n        void onServiceRequestReceived(std_srvs::Empty::Request& req, std::shared_ptr<std_srvs::Empty::Response> res) override\n        {\n            requestReceived();\n            // res->success = true;\n        }\n\n        template <typename TOrthogonal, typename TSourceObject>\n        void onOrthogonalAllocation()\n        {\n          this->requestReceived = [=]()\n          {\n            this->template postEvent<EvServiceRequestReceieved<TSourceObject, TOrthogonal>>();\n          };\n        }\n      private:\n        std::function<void()> requestReceived;\n  };\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/orthogonals/or_services.h",
    "content": "#include <smacc/smacc.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_atomic_services\n{\n    class OrServices : public smacc::Orthogonal<OrServices>\n    {\n        virtual void onInitialize() override\n        {\n            auto service_server_client = this->createClient<ClServiceServer>(\"service\");\n            service_server_client->initialize();\n\n            auto service_client = this->createClient<ClServiceClient>(\"service\");\n            service_client->initialize();\n        }\n    };\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_atomic_services\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_atomic\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/sm_atomic_services.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include \"sm_atomic_services/clients/cl_service_server.h\"\n#include \"sm_atomic_services/clients/cl_service_client.h\"\n\n// ORTHOGONALS\n#include <sm_atomic_services/orthogonals/or_timer.h>\n#include <sm_atomic_services/orthogonals/or_services.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n#include \"sm_atomic_services/clients/client_behaviors/cb_service_server.h\"\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_atomic_services\n{\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmAtomicServices\n    : public smacc::SmaccStateMachineBase<SmAtomicServices, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrServices>();\n    }\n};\n\n} // namespace sm_atomic\n\n#include <sm_atomic_services/states/st_state_1.h>\n#include <sm_atomic_services/states/st_state_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_services\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmAtomicServices>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State2, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_atomic\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/include/sm_atomic_services/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_atomic_services\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, SmAtomicServices>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvServiceRequestReceieved<CbServiceServer, OrServices>, State1, SUCCESS>\n\n    >reactions;\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrServices, CbServiceServer>();\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Entering State2\");\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/launch/sm_atomic_services.launch",
    "content": "<launch>\n\n    <rosparam command=\"load\" file=\"$(find sm_atomic)/config/sm_atomic_config.yaml\" />\n    <node pkg=\"sm_atomic_services\" type=\"sm_atomic_services_node\" name=\"sm_atomic_services\"/>\n        <node pkg=\"smacc_runtime_test\" name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\" output=\"screen\">\n        <rosparam file=\"$(find sm_atomic_services)/config/sm_atomic_services_test.yaml\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_atomic_services</name>\n    <version>1.4.16</version>\n  <description>The sm_atomic_services package</description>\n\n\n  <maintainer email=\"jacobus.lock@fox-robotics.com\">Jacobus Lock</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_atomic</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n  <depend>xterm</depend>\n  <depend>smacc_runtime_test</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/src/sm_atomic_services_node.cpp",
    "content": "#include <sm_atomic_services/sm_atomic_services.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_atomic_services\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_atomic_services::SmAtomicServices>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_atomic_services/test/sm_atomic_services.test",
    "content": "<launch>\n<include file=\"$(find sm_atomic_services)/launch/sm_atomic_services.launch\"/>\n    <test pkg=\"smacc_runtime_test\" test-name=\"smacc_runtime_test_node\" type=\"smacc_runtime_test_node\">\n        <rosparam file=\"$(find sm_atomic_services)/config/sm_atomic_services_test.yaml\"/>\n    </test>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_calendar_week\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_calendar_week)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_packML_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_calendar_week_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_calendar_week.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/README.md",
    "content": "  <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_calendar_week/docs/smacc_state_machine_20200206-003738.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> Another simple, but complete state machine example that uses the ros_timer_client & keyboard client to iterate through the states, which correspond to the days of the week. This example is another excellent starting point for new users state machine projects.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__calendar__week.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_calendar_week sm_calendar_week.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/config/sm_calendar_week_config.yaml",
    "content": "SmCalendarWeek:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nnamespace sm_calendar_week\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\n};\n} // namespace client_1\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_calendar_week/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_calendar_week\n{\nnamespace cl_subscriber\n{\nclass CbDefaultSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n    //-------------------------------------------------------------------------------\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_calendar_week/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_calendar_week\n{\nnamespace cl_subscriber\n{\nclass CbWatchdogSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/mode_states/ms_weekend.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_calendar_week\n{\n// STATE DECLARATION\nclass MsWeekend : public smacc::SmaccState<MsWeekend, SmCalendarWeek, StSaturday>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n //  typedef mpl::list<\n\n  // >reactions;\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/mode_states/ms_workweek.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_calendar_week\n{\n// STATE DECLARATION\nclass MsWorkweek : public smacc::SmaccState<MsWorkweek, SmCalendarWeek, StMonday>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_calendar_week\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_calendar_week\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/sm_calendar_week.h",
    "content": "#pragma once\n\n#include <ros/ros.h>\n#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n#include <sm_calendar_week/orthogonals/or_timer.h>\n#include <sm_calendar_week/orthogonals/or_keyboard.h>\n\nusing namespace cl_ros_timer;\nusing namespace cl_keyboard;\n\n//CLIENT BEHAVIORS\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n\n#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\n\nusing namespace smacc;\nusing namespace cl_ros_timer;\nusing namespace smacc::default_events;\n\nnamespace sm_calendar_week\n{\n\n//STATES\nclass StFriday; // first state specially needs a forward declaration\nclass StMonday;\nclass StTuesday;\nclass StWednesday;\nclass StThursday;\nclass StSaturday;\nclass StSunday;\n\nclass MsWorkweek;\nclass MsWeekend;\n\n// struct EvToDeep : sc::event<EvToDeep>{};\n\n// struct EvFail : sc::event<EvFail>{};\n\n// struct EvEStop : sc::event<EvEStop>{};\n\n// STATE MACHINE\nstruct SmCalendarWeek\n    : public smacc::SmaccStateMachineBase<SmCalendarWeek, MsWorkweek>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        // this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        // this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_calendar_week\n\n// MODE STATES\n#include <sm_calendar_week/mode_states/ms_workweek.h>\n#include <sm_calendar_week/mode_states/ms_weekend.h>\n\n//STATES\n#include <sm_calendar_week/states/st_friday.h>\n#include <sm_calendar_week/states/st_monday.h>\n#include <sm_calendar_week/states/st_tuesday.h>\n#include <sm_calendar_week/states/st_wednesday.h>\n#include <sm_calendar_week/states/st_thursday.h>\n#include <sm_calendar_week/states/st_saturday.h>\n#include <sm_calendar_week/states/st_sunday.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_friday.h",
    "content": "namespace sm_calendar_week\n{\n// STATE DECLARATION\nstruct StFriday : smacc::SmaccState<StFriday, MsWorkweek>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, MsWeekend, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, MsWeekend, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer,  CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_monday.h",
    "content": "namespace sm_calendar_week\n{\n\n// STATE DECLARATION\nstruct StMonday : smacc::SmaccState<StMonday, MsWorkweek>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StTuesday, SUCCESS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StTuesday, PREEMPT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_saturday.h",
    "content": "namespace sm_calendar_week\n{\n// STATE DECLARATION\nstruct StSaturday : smacc::SmaccState<StSaturday, MsWeekend>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StSunday, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StSunday, SUCCESS> //,\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer,  CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_sunday.h",
    "content": "namespace sm_calendar_week\n{\n// STATE DECLARATION\nstruct StSunday : smacc::SmaccState<StSunday, MsWeekend>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, MsWorkweek, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, MsWorkweek, SUCCESS> //,\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer,  CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_thursday.h",
    "content": "namespace sm_calendar_week\n{\n// STATE DECLARATION\nstruct StThursday : smacc::SmaccState<StThursday, MsWorkweek>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StFriday, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StFriday, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer,  CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_tuesday.h",
    "content": "namespace sm_calendar_week\n{\n\n// STATE DECLARATION\nstruct StTuesday : smacc::SmaccState<StTuesday, MsWorkweek>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StWednesday, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StWednesday, SUCCESS> //,\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/include/sm_calendar_week/states/st_wednesday.h",
    "content": "namespace sm_calendar_week\n{\n// STATE DECLARATION\nstruct StWednesday : smacc::SmaccState<StWednesday, MsWorkweek>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StThursday, PREEMPT>,\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StThursday, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer,  CbTimerCountdownOnce>(5);\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n       void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_calendar_week\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/launch/sm_calendar_week.launch",
    "content": "<launch>\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -e\" />\n\n    <rosparam command=\"load\" file=\"$(find sm_calendar_week)/config/sm_calendar_week_config.yaml\" />\n    <node pkg=\"sm_calendar_week\" type=\"sm_calendar_week_node\" name=\"sm_calendar_week\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_calendar_week</name>\n    <version>1.4.16</version>\n  <description>The sm_calendar_week package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_calendar_week</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/package_REMOTE_32590.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_calendar_week</name>\n  <version>0.9.3</version>\n  <description>The sm_calendar_week package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_calendar_week</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_calendar_week/src/sm_calendar_week_node.cpp",
    "content": "#include <sm_calendar_week/sm_calendar_week.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"CalendarWeek\");\n    smacc::run<sm_calendar_week::SmCalendarWeek>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_dance_bot\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco, brett2@robosoft-ai.com, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_dance_bot)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin multirole_sensor_client tf sr_all_events_go sr_event_countdown ros_timer_client sr_conditional ros_publisher_client actionlib actionlib_msgs)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\nadd_action_files(\n   DIRECTORY\n   servers/led_action_server/action/\n\n   FILES\n   LEDControl.action\n)\n\ngenerate_messages(\n   DEPENDENCIES\n   actionlib_msgs\n )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES sm_dance_bot\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}\n              src/sm_dance_bot.cpp\n              src/clients/cl_led/cl_led.cpp)\n\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n\n add_executable(temperature_sensor_node_${PROJECT_NAME} servers/temperature_sensor_node/src/temperature_sensor_node.cpp)\n set_target_properties(temperature_sensor_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"temperature_sensor_node\")\n\n target_link_libraries(temperature_sensor_node_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n add_executable(led_action_server_node_${PROJECT_NAME} servers/led_action_server/src/led_action_server_node.cpp)\n set_target_properties(led_action_server_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"led_action_server_node\")\n target_link_libraries(\n   led_action_server_node_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n)\n\nadd_dependencies(led_action_server_node_${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\ninstall(PROGRAMS\n   servers/service_node_3/src/service_node_3.py\n   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS\n  ${PROJECT_NAME}\n   temperature_sensor_node_${PROJECT_NAME}\n   led_action_server_node_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME} temperature_sensor_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(DIRECTORY\n    launch/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\ninstall(DIRECTORY\n    urdf/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf\n)\n\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_dance_bot.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_dance_bot/docs/smacc_state_machine_20200222-125058.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> A full-featured state machine example, that highlights the capabilities of SMACC & the ROS Navigation Stack via the MoveBaseZ Client.<br></br>\n\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__dance__bot.html\">Doxygen Namespace & Class Reference</a>\n\nTo see a video of this state machine in action click <a href=\"https://www.youtube.com/watch?v=9iyX_x05d3Q&t=7s\">here</a>.\n\n<br></br>\n\n<p align=\"center\">\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_dance_bot/docs/sm_dance_bot.JPG\" width=\"800\"/>\n </p>\n <br></br>\n\n<h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file for the full gazebo demo...\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch\n```\n\nOr, you can run the lightweight demo...\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n\nThis launch command starts the process by hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/backward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nBackwardLocalPlanner:\n    k_rho: -1.4 # linear distance to the goal gain, default = -1.0 (related with carrot distance)\n    k_alpha: -0.1\n    k_betta: -1.0\n    carrot_distance: 0.3 #meters default 0.5\n    carrot_angular_distance: 0.3 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.003 # 3 mm\n    yaw_goal_tolerance: 0.3\n    pure_spinning_straight_line_mode: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.157\n  xy_goal_tolerance: 0.15\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/costmap_common_params.yaml",
    "content": "\nmap_type: costmap\norigin_z: 0.0\nz_resolution: 1\nz_voxels: 2\n\nobstacle_range: 12.5\nraytrace_range: 3.0\n\npublish_voxel_map: false\ntransform_tolerance: 0.5\nmeter_scoring: true\n\nfootprint: [[0.48, -0.40], [0.48, 0.40], [-0.48, 0.40], [-0.48, -0.40]]\nfootprint_padding: 0.3\n\nplugins:\n- {name: obstacles_layer, type: \"costmap_2d::ObstacleLayer\"}\n- {name: inflater_layer, type: \"costmap_2d::InflationLayer\"}\n\nobstacles_layer:\n  observation_sources: scan\n  scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 10.5, raytrace_range: 3.0}\n\ninflater_layer:\n inflation_radius: 0.2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/forward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nForwardLocalPlanner:\n    k_rho: 2.0\n    k_alpha: -0.4\n    k_betta: -1.0\n    carrot_distance: 0.2 #meters\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.04\n    yaw_goal_tolerance: 0.01\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/global_costmap_params.yaml",
    "content": "global_costmap:\n  global_frame: odom\n  robot_base_frame: base_link\n  update_frequency: 20\n  publish_frequency: 5\n  width: 40.0\n  height: 40.0\n  resolution: 0.05\n  origin_x: -20.0\n  origin_y: -20.0\n  static_map: true\n  rolling_window: false\n  inflater_layer:\n    inflation_radius: 0.6\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: odom\n   robot_base_frame: base_link\n   update_frequency: 20.0\n   publish_frequency: 5.0\n   width: 10.0\n   height: 10.0\n   resolution: 0.05\n   static_map: false\n   rolling_window: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/move_base_client/waypoints_plan.yaml",
    "content": "waypoints:\n  # POINT 0\n  - position:\n      x: 3.0\n      y: -2.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 1\n  - position:\n      x: -5.75\n      y: 3.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 2\n  - position:\n      x: -10.25\n      y: -4.25\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 3\n  - position:\n      x: 2.0\n      y: -8.58 # north west corner of the room\n      #y: -12.35 # south west corner of the room\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n    # POINT 4\n  - position:\n      x: -10\n      y: 13.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 4\n  - position:\n      x: -0.0\n      y: 0.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  #POINT 5\n  - position:\n      x: 6.0\n      y: 8.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/navigation.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 83\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /OdomTrackerPath1\n        - /BW Plan1\n        - /Odometry1/Shape1\n        - /TF1/Frames1\n        - /SmaccRvizDisplay1\n      Splitter Ratio: 0.3861111104488373\n    Tree Height: 411\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nPreferences:\n  PromptSaveOnExit: true\nToolbars:\n  toolButtonStyle: 2\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 209; 209; 214\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 40\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.4000000059604645\n      Class: rviz/RobotModel\n      Collision Enabled: false\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        axle_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        chassis_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        mid_mount:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        rear_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        top_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.25\n      Name: Axes\n      Radius: 0.05000000074505806\n      Reference Frame: odom\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.05000000074505806\n      Style: Flat Squares\n      Topic: front/scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: true\n      Enabled: false\n      Name: Costmaps\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Alpha: 1\n      Axes Length: 1\n      Axes Radius: 0.10000000149011612\n      Class: rviz/Pose\n      Color: 255; 0; 255\n      Enabled: true\n      Head Length: 0.20000000298023224\n      Head Radius: 0.10000000149011612\n      Name: MoveBase Goal\n      Shaft Length: 0.5\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow\n      Topic: /move_base/current_goal\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 85; 255\n      Enabled: true\n      Name: Polygon\n      Topic: /move_base/local_costmap/obstacles_layer_footprint/footprint_stamped\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.10000000149011612\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: Axes\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 85; 170; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path_stacked\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 255; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: FW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 255; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/ForwardGlobalPlanner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 170; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: BW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 170; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /undo_path_planner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Global Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/NavfnROS/plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Local Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/TrajectoryPlannerROS/local_plan\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/ForwardLocalPlanner/goal_marker\n      Name: FW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/BackwardLocalPlanner/goal_marker\n      Name: BW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/backward_planner/markers\n      Name: BackwardMotionPlanner\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Angle Tolerance: 0.10000000149011612\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.30000001192092896\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 15000\n      Name: Odometry\n      Position Tolerance: 0.10000000149011612\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.10000000149011612\n        Color: 255; 25; 0\n        Head Length: 0.003000000026077032\n        Head Radius: 0\n        Shaft Length: 0.05000000074505806\n        Shaft Radius: 0.019999999552965164\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        axle_link:\n          Value: false\n        base_link:\n          Value: true\n        chassis_link:\n          Value: false\n        front_cover_link:\n          Value: false\n        front_laser:\n          Value: false\n        front_left_wheel_link:\n          Value: false\n        front_lights_link:\n          Value: false\n        front_right_wheel_link:\n          Value: false\n        front_rocker_link:\n          Value: false\n        imu_link:\n          Value: false\n        left_side_cover_link:\n          Value: false\n        map:\n          Value: true\n        mid_mount:\n          Value: false\n        odom:\n          Value: true\n        rear_cover_link:\n          Value: false\n        rear_left_wheel_link:\n          Value: false\n        rear_lights_link:\n          Value: false\n        rear_right_wheel_link:\n          Value: false\n        rear_rocker_link:\n          Value: false\n        right_side_cover_link:\n          Value: false\n        top_link:\n          Value: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: false\n      Show Axes: true\n      Show Names: true\n      Tree:\n        map:\n          {}\n        odom:\n          base_link:\n            chassis_link:\n              axle_link:\n                front_rocker_link:\n                  front_left_wheel_link:\n                    {}\n                  front_right_wheel_link:\n                    {}\n                rear_rocker_link:\n                  rear_left_wheel_link:\n                    {}\n                  rear_right_wheel_link:\n                    {}\n              front_cover_link:\n                {}\n              front_laser:\n                {}\n              front_lights_link:\n                {}\n              imu_link:\n                {}\n              left_side_cover_link:\n                {}\n              rear_cover_link:\n                {}\n              rear_lights_link:\n                {}\n              right_side_cover_link:\n                {}\n              top_link:\n                {}\n            mid_mount:\n              {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 25; 255; 0\n      Enabled: true\n      Name: GridCells\n      Topic: \"\"\n      Value: true\n    - Alpha: 1\n      Arrow Length: 0.05000000074505806\n      Axes Length: 0.30000001192092896\n      Axes Radius: 0.009999999776482582\n      Class: rviz/PoseArray\n      Color: 255; 25; 0\n      Enabled: true\n      Head Length: 0.07000000029802322\n      Head Radius: 0.029999999329447746\n      Name: Pose Estimation\n      Shaft Length: 0.23000000417232513\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow (Flat)\n      Topic: /particlecloud\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /tool_markers\n      Name: MarkerArray\n      Namespaces:\n        tool_namespace: true\n      Queue Size: 1\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: Global Planner Costmap\n      Topic: /move_base/global_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: false\n      Name: LocalPlanner Costmap\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Class: smacc_rviz_plugin/SmaccRvizDisplay\n      CurrentState: /sm_dance_bot::MsDanceBotRunMode/sm_dance_bot::StNavigateToWaypointsX\n      Enabled: true\n      Name: SmaccRvizDisplay\n      Topic: /remap_smacc_status\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: odom\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Theta std deviation: 0.2617993950843811\n      Topic: /initialpose\n      X std deviation: 0.5\n      Y std deviation: 0.5\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: -0.004999920725822449\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Scale: 78.65935516357422\n      Target Frame: base_link\n      Value: TopDownOrtho (rviz)\n      X: 0.6073487401008606\n      Y: 0.41081807017326355\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: true\n  Height: 713\n  Hide Left Dock: true\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001b50000022bfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d0000022b000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000050d0000003efc0100000002fb0000000800540069006d006501000000000000050d000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000050d0000022b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1293\n  X: 67\n  Y: 27\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.backward_local_planner=DEBUG\nlog4j.logger.ros.move_base=DEBUG\nlog4j.logger.ros.forward_local_planner=DEBUG\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/config/sm_dance_bot_config.yaml",
    "content": "SmDanceBot:\n   signal_detector_loop_freq: 20\n\n# RadialMotionStateMachine:\n#     NavigateToRadialStart:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 start_position_x: 3\n#                 start_position_y: 0\n#     RotateDegress:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 initial_orientation_index: 0 # the initial index of the linear motion (factor of angle_increment_degrees)\n#                 angle_increment_degree: 15    # the increment of angle between to linear motions\n#                 linear_trajectories_count: 12  # the number of linear trajectories of the radial motion\n#     NavigateToEndPoint:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 straight_motion_distance: 3.5\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/docs/Global Transition Rules.txt",
    "content": "GLOBAL TRANSITION RULES\n---------------------------------\n\nFor all states, superstates, If any sensor is lost, transition back to st_acquire_sensors.\n\nFor all states, If the Navigation Orthogonal is aborted, transition to st_navigate_to_waypoints_x.\n\n\nFor all states, superstates, but not ssrs, If Keyboard Orthogonal = N, transition to next success state.\n\nFor all states, superstates, but not ssrs, If Keyboard Orthogonal = P, transition to previous state.\n\nFor all states, If Navigation Orthogonal is prempted, transition to previous state.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_led/cl_led.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_action_client_base.h>\n#include <sm_dance_bot/LEDControlAction.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_led\n{\nclass ClLED : public smacc::client_bases::SmaccActionClientBase<sm_dance_bot::LEDControlAction>\n{\n\npublic:\n    SMACC_ACTION_CLIENT_DEFINITION(sm_dance_bot::LEDControlAction);\n\n    ClLED(std::string actionServerName);\n    virtual std::string getName() const override;\n    virtual ~ClLED();\n};\n} // namespace cl_led\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_led/client_behaviors/cb_led_off.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_led\n{\nclass CbLEDOff : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_OFF;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_led/client_behaviors/cb_led_on.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_led\n{\nclass CbLEDOn : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_ON;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_lidar/cl_lidar.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/LaserScan.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_lidar\n{\n\nclass ClLidarSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::LaserScan>\n{\npublic:\n    ClLidarSensor()\n    {\n    }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n#include <sensor_msgs/LaserScan.h>\n#include <sm_dance_bot/clients/cl_lidar/cl_lidar.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_lidar\n{\nstruct CbLidarSensor : cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClLidarSensor>\n{\npublic:\n  CbLidarSensor()\n  {\n    ROS_INFO(\"CbLidarSensor Constructor\");\n  }\n\n  virtual void onEntry() override\n  {\n    ROS_INFO(\"[CbLidarSensor] onEntry\");\n    cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClLidarSensor>::onEntry();\n  }\n\n  virtual void onMessageCallback(const sensor_msgs::LaserScan &msg) override\n  {\n  }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_service3/cl_service3.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_service_client.h>\n#include <std_srvs/SetBool.h>\nnamespace sm_dance_bot\n{\nnamespace cl_service3\n{\nclass ClService3 : public smacc::client_bases::SmaccServiceClient<std_srvs::SetBool>\n{\npublic:\n  ClService3()\n  {\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_service3/client_behaviors/cb_service3.h",
    "content": "#include <smacc/smacc_client_behavior.h>\n#include <sm_dance_bot/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_service3\n{\nenum class Service3Command\n{\n  SERVICE3_ON,\n  SERVICE3_OFF\n};\n\nclass CbService3 : public smacc::SmaccClientBehavior\n{\nprivate:\n  ClService3 *serviceClient_;\n  Service3Command value_;\n\npublic:\n  CbService3(Service3Command value)\n  {\n    value_ = value;\n  }\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(serviceClient_);\n\n    std_srvs::SetBool req;\n    if (value_ == Service3Command::SERVICE3_ON)\n      req.request.data = true;\n    else\n      req.request.data = false;\n\n    serviceClient_->call(req);\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_string_publisher/cl_string_publisher.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_publisher_client.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_string_publisher\n{\nclass ClStringPublisher : public smacc::client_bases::SmaccPublisherClient\n{\npublic:\n    ClStringPublisher(std::string topicName)\n        : smacc::client_bases::SmaccPublisherClient()\n    {\n        this->configure<std_msgs::String>(topicName);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_client_behavior.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_string_publisher\n{\nclass CbStringPublisher : public smacc::SmaccClientBehavior\n{\npublic:\n    ClStringPublisher *publisherClient_;\n    std::string msg_;\n\n    CbStringPublisher(std::string msg)\n    {\n        ROS_INFO_STREAM(\"Creating CbStringPublisher behavior with stored message: \" << msg);\n        msg_ = msg;\n    }\n\n    virtual void onEntry()\n    {\n        this->requiresClient(publisherClient_);\n    }\n\n    virtual void onExit() override\n    {\n        std_msgs::String rosmsg;\n        rosmsg.data = msg_;\n        publisherClient_->publish(rosmsg);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_temperature_sensor/cl_temperature_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/Temperature.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_temperature_sensor\n{\nclass ClTemperatureSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::Temperature>\n{\npublic:\n    ClTemperatureSensor()\n    {\n    }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h",
    "content": "\n#pragma once\n#include <sensor_msgs/Temperature.h>\n#include <sm_dance_bot/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_temperature_sensor\n{\nstruct EvCustomTemperatureAlert : sc::event<EvCustomTemperatureAlert>\n{\n};\n\n//--------------------------------------------------------------------------------------\nclass CbConditionTemperatureSensor : public cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClTemperatureSensor>\n{\npublic:\n  CbConditionTemperatureSensor()\n  {\n  }\n  virtual void onMessageCallback(const sensor_msgs::Temperature &msg) override\n  {\n    if (msg.temperature > 40)\n    {\n      auto ev = new EvCustomTemperatureAlert();\n      this->postEvent(ev);\n    }\n  }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/modestates/ms_dance_bot_recovery_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nclass MsDanceBotRecoveryMode : public smacc::SmaccState<MsDanceBotRecoveryMode, SmDanceBot>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, sc::deep_history<MsDanceBotRunMode::LastDeepState>>\n\n   >reactions;\n   // typedef Transition<EvGlobalError, MsDanceBotRunMode> reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/modestates/ms_dance_bot_run_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nclass MsDanceBotRunMode : public smacc::SmaccState<MsDanceBotRunMode, SmDanceBot, StAcquireSensors>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n   >reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_led.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot\n{\nclass OrLED : public smacc::Orthogonal<OrLED>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_led::ClLED>(\"led_action_server\");\n        actionclient->initialize();\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_navigation.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace sm_dance_bot\n{\nusing namespace cl_move_base_z;\n\nclass OrNavigation : public smacc::Orthogonal<OrNavigation>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto movebaseClient = this->createClient<ClMoveBaseZ>();\n        movebaseClient->initialize();\n\n        // create planner switcher\n        movebaseClient->createComponent<PlannerSwitcher>();\n\n        movebaseClient->createComponent<cl_move_base_z::Pose>();\n\n        // create odom tracker\n        movebaseClient->createComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n\n        // create waypoints navigator component\n        auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();\n        loadWaypointsFromYaml(waypointsNavigator);\n\n        // change this to skip some points of the yaml file, default = 0\n        waypointsNavigator->currentWaypoint_ = 1;\n    }\n\n    void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)\n    {\n        // if it is the first time and the waypoints navigator is not configured\n\n        std::string planfilepath;\n        ros::NodeHandle nh(\"~\");\n        if (nh.getParam(\"/sm_dance_bot/waypoints_plan\", planfilepath))\n        {\n            waypointsNavigator->loadWayPointsFromFile(planfilepath);\n        }\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_obstacle_perception.h",
    "content": "#pragma once\n\n#include <sm_dance_bot/clients/cl_lidar/cl_lidar.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot\n{\nclass OrObstaclePerception : public smacc::Orthogonal<OrObstaclePerception>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto lidarClient = this->createClient<ClLidarSensor>();\n\n        lidarClient->topicName = \"/front/scan\";\n        //lidarClient->queueSize = \"/front/scan\";\n        lidarClient->timeout_ = ros::Duration(10);\n\n        lidarClient->initialize();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_service3.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot\n{\nclass OrService3 : public smacc::Orthogonal<OrService3>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto serviceClient = this->createClient<ClService3>();\n        serviceClient->serviceName_ = \"/service_node3\";\n        serviceClient->initialize();\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_dance_bot\n{\nclass OrStringPublisher : public smacc::Orthogonal<OrStringPublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        this->createClient<ClStringPublisher>(\"/string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_temperature_sensor.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sensor_msgs/Temperature.h>\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <sm_dance_bot/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n\nnamespace sm_dance_bot\n{\nclass OrTemperatureSensor : public smacc::Orthogonal<OrTemperatureSensor>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clTemperatureSensor = this->createClient<ClTemperatureSensor>();\n\n        clTemperatureSensor->topicName = \"/temperature\";\n        //ClTemperatureSensor->queueSize = \"/front/scan\";\n        clTemperatureSensor->timeout_ = ros::Duration(10);\n\n        clTemperatureSensor->initialize();\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_timer.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_dance_bot\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot\n{\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto publisherClient_ = this->createClient<cl_ros_publisher::ClRosPublisher>();\n        publisherClient_->configure<std_msgs::String>(\"/updatable_string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/sm_dance_bot.h",
    "content": "#include <smacc/smacc.h>\n\n#include <sensor_msgs/LaserScan.h>\n\n// CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/client_behaviors.h>\n\nusing namespace cl_move_base_z;\n\n#include <sm_dance_bot/clients/cl_led/client_behaviors/cb_led_on.h>\n#include <sm_dance_bot/clients/cl_led/client_behaviors/cb_led_off.h>\n\n#include <sm_dance_bot/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h>\n#include <sm_dance_bot/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h>\n\n#include <sm_dance_bot/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h>\n#include <sm_dance_bot/clients/cl_service3/client_behaviors/cb_service3.h>\n\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nusing namespace sm_dance_bot::cl_lidar;\nusing namespace sm_dance_bot::cl_service3;\nusing namespace sm_dance_bot::cl_string_publisher;\nusing namespace sm_dance_bot::cl_temperature_sensor;\nusing namespace sm_dance_bot::cl_led;\n//using namespace sm_dance_bot::cl_move_base_z;\n//using namespace sm_dance_bot::cl_updatable_publisher;\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n#include <sr_event_countdown/sr_event_countdown.h>\n#include <sr_conditional/sr_conditional.h>\n\nusing namespace smacc::state_reactors;\n\n// ORTHOGONALS\n#include <sm_dance_bot/orthogonals/or_navigation.h>\n#include <sm_dance_bot/orthogonals/or_obstacle_perception.h>\n#include <sm_dance_bot/orthogonals/or_led.h>\n#include <sm_dance_bot/orthogonals/or_temperature_sensor.h>\n#include <sm_dance_bot/orthogonals/or_string_publisher.h>\n#include <sm_dance_bot/orthogonals/or_service3.h>\n#include <sm_dance_bot/orthogonals/or_timer.h>\n#include <sm_dance_bot/orthogonals/or_updatable_publisher.h>\n\nnamespace sm_dance_bot\n{\n//STATE FORWARD DECLARATIONS\nclass StAcquireSensors;\nclass StEventCountDown;\nclass StRotateDegrees4;\nclass StNavigateForward1;\nclass StNavigateToWaypoint1;\nclass StNavigateToWaypointsX;\nclass StRotateDegrees2;\nclass StRotateDegrees1;\nclass StNavigateReverse2;\nclass StRotateDegrees3;\nclass StNavigateReverse1;\nclass StNavigateForward2;\nclass StRotateDegrees5;\nclass StNavigateReverse3;\nclass StRotateDegrees6;\nclass StNavigateReverse3;\n\n//SUPERSTATE FORWARD DECLARATIONS\n\n//MODE STATES FORWARD DECLARATIONS\nclass MsDanceBotRunMode;\nclass MsDanceBotRecoveryMode;\n\nnamespace SS1\n{\nclass SsRadialPattern1;\n}\n\nnamespace SS2\n{\nclass SsRadialPattern2;\n}\n\nnamespace SS3\n{\nclass SsRadialPattern3;\n}\n\nnamespace SS4\n{\nclass SsFPattern1;\n}\n\nnamespace SS5\n{\nclass SsSPattern1;\n}\n\n// custom smd_dance_bot event\nstruct EvGlobalError : sc::event<EvGlobalError>\n{\n};\n\n} // namespace sm_dance_bot\n\nusing namespace sm_dance_bot;\nusing namespace cl_ros_timer;\nusing namespace smacc;\n\n\nnamespace sm_dance_bot\n{\n/// \\brief Advanced example of state machine with smacc that shows multiple techniques\n///  for the development of state machines\nstruct SmDanceBot\n    : public smacc::SmaccStateMachineBase<SmDanceBot, MsDanceBotRunMode>\n{\n    int counter_1;\n    bool rt_ready_flag;\n\n    typedef mpl::bool_<false> shallow_history;\n    typedef mpl::bool_<false> deep_history;\n    typedef mpl::bool_<false> inherited_deep_history;\n\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->setGlobalSMData(\"counter_1\", counter_1);\n        this->setGlobalSMData(\"rt_ready_flag\", rt_ready_flag);\n\n        this->createOrthogonal<OrNavigation>();\n        this->createOrthogonal<OrObstaclePerception>();\n        this->createOrthogonal<OrLED>();\n        this->createOrthogonal<OrTemperatureSensor>();\n        this->createOrthogonal<OrStringPublisher>();\n        this->createOrthogonal<OrService3>();\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n    }\n};\n\n} // namespace sm_dance_bot\n\n//MODE STATES\n#include <sm_dance_bot/modestates/ms_dance_bot_run_mode.h>\n#include <sm_dance_bot/modestates/ms_dance_bot_recovery_mode.h>\n\n//SUPERSTATES\n#include <sm_dance_bot/superstates/ss_radial_pattern_1.h>\n#include <sm_dance_bot/superstates/ss_radial_pattern_2.h>\n#include <sm_dance_bot/superstates/ss_radial_pattern_3.h>\n#include <sm_dance_bot/superstates/ss_f_pattern_1.h>\n#include <sm_dance_bot/superstates/ss_s_pattern_1.h>\n\n//STATES\n#include <sm_dance_bot/states/st_acquire_sensors.h>\n#include <sm_dance_bot/states/st_event_count_down.h>\n\n#include <sm_dance_bot/states/st_navigate_to_waypoints_x.h>\n\n#include <sm_dance_bot/states/st_rotate_degrees_6.h>\n#include <sm_dance_bot/states/st_rotate_degrees_5.h>\n#include <sm_dance_bot/states/st_navigate_forward_2.h>\n#include <sm_dance_bot/states/st_rotate_degrees_4.h>\n#include <sm_dance_bot/states/st_navigate_forward_1.h>\n#include <sm_dance_bot/states/st_navigate_to_waypoint_1.h>\n#include <sm_dance_bot/states/st_rotate_degrees_2.h>\n#include <sm_dance_bot/states/st_rotate_degrees_1.h>\n#include <sm_dance_bot/states/st_navigate_reverse_2.h>\n#include <sm_dance_bot/states/st_rotate_degrees_3.h>\n#include <sm_dance_bot/states/st_navigate_reverse_1.h>\n#include <sm_dance_bot/states/st_navigate_reverse_3.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_forward_1.h",
    "content": "\nnamespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward1 : public smacc::SmaccState<StiFPatternForward1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternReturn1<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n     TSti::template configure_orthogonal<OrNavigation, CbNavigateForward>(SS::ray_lenght_meters());\n     TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n    ROS_INFO(\"[SsrFpattern] Fpattern rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_forward_2.h",
    "content": "namespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward2 : smacc::SmaccState<StiFPatternForward2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward2<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternStartLoop<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n    ROS_INFO(\"[SsrFpattern] Fpattern rotate: SS current iteration: %d/%d\", superstate.iteration_count, superstate.total_iterations());\n\n    TSti::template configure<OrNavigation, CbNavigateForward>(SS::pitch_lenght_meters());\n    TSti::template configure<OrLED, CbLEDOff>();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_loop_start.h",
    "content": "namespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternStartLoop : smacc::SmaccState<StiFPatternStartLoop<SS>, SS>\n{\n  typedef SmaccState<StiFPatternStartLoop<SS>, SS> TSti;\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiFPatternStartLoop<SS>>, StiFPatternRotate1<SS>, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    auto &superstate = TSti::template context<SS>();\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    TSti::checkWhileLoopConditionAndThrowEvent(&StiFPatternStartLoop<SS>::loopCondition);\n  }\n};\n} // namespace f_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_return_1.h",
    "content": "namespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternReturn1 : smacc::SmaccState<StiFPatternReturn1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternReturn1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiFPatternRotate2<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    TSti::template configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_rotate_1.h",
    "content": "namespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate1 : smacc::SmaccState<StiFPatternRotate1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternForward1<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    float angle = 0;\n    double offset = 7; // for a better behaving\n\n    if (SS::direction() == TDirection::LEFT)\n      angle = 90 + offset;\n    else\n      angle = -90 - offset;\n\n     //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n     TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(angle); // absolute aligned to the y-axis\n     TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/f_pattern_states/sti_fpattern_rotate_2.h",
    "content": "namespace sm_dance_bot\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate2 : smacc::SmaccState<StiFPatternRotate2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate2<SS>, SS> TSti;\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternForward2<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    double offset = 7; // for a better behaving\n    float angle = 0;\n    if (SS::direction() == TDirection::LEFT)\n      angle = -90 - offset;\n    else\n      angle = 90 + offset;\n\n    //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n    TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(0 + offset); // absolute horizontal\n    TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace f_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/radial_motion_states/sti_radial_end_point.h",
    "content": "namespace sm_dance_bot\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialEndPoint : smacc::SmaccState<StiRadialEndPoint, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiRadialReturn, SUCCESS>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiRadialRotate, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    ROS_INFO(\"ssr radial end point, distance in meters: %lf\", SS::ray_length_meters());\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::ray_length_meters());\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/radial_motion_states/sti_radial_loop_start.h",
    "content": "namespace sm_dance_bot\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialLoopStart : smacc::SmaccState<StiRadialLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiRadialLoopStart>, StiRadialRotate, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiRadialLoopStart::loopWhileCondition);\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/radial_motion_states/sti_radial_return.h",
    "content": "namespace sm_dance_bot\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialReturn : smacc::SmaccState<StiRadialReturn, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiRadialLoopStart, SUCCESS>,\n  Transition<EvCbFailure<CbUndoPathBackwards, OrNavigation>, StiRadialEndPoint, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void onExit()\n  {\n      ClMoveBaseZ* moveBase;\n      this->requiresClient(moveBase);\n\n      auto odomTracker = moveBase->getComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n      odomTracker->clearPath();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/radial_motion_states/sti_radial_rotate.h",
    "content": "namespace sm_dance_bot\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialRotate : smacc::SmaccState<StiRadialRotate, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiRadialEndPoint, SUCCESS>,\n  Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiRadialLoopStart, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto cbAbsRotate = this->getOrthogonal<OrNavigation>()\n                           ->getClientBehavior<CbAbsoluteRotate>();\n\n    auto &superstate = this->context<SS>();\n    cbAbsRotate->absoluteGoalAngleDegree = superstate.iteration_count * SS::ray_angle_increment_degree();\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_forward_1.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward1 : public smacc::SmaccState<StiSPatternForward1, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate2>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate1>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_forward_2.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward2 : public smacc::SmaccState<StiSPatternForward2, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate3>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate2>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n\n    this->configure<OrNavigation, CbNavigateForward>(SS::pitch2_lenght_meters());\n    this->configure<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_forward_3.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward3 : public smacc::SmaccState<StiSPatternForward3, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate4>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate3>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_forward_4.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward4 : public smacc::SmaccState<StiSPatternForward4, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternLoopStart>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate4>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n\n    this->configure<OrNavigation, CbNavigateForward>(SS::pitch2_lenght_meters());\n    this->configure<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_loop_start.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternLoopStart : smacc::SmaccState<StiSPatternLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopContinue<StiSPatternLoopStart>, StiSPatternRotate1, CONTINUELOOP>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    auto &superstate = this->context<SS>();\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    checkWhileLoopConditionAndThrowEvent(&StiSPatternLoopStart::loopCondition);\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_1.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate1 : smacc::SmaccState<StiSPatternRotate1, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward1>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternLoopStart>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n\n        // float angle = 0;\n        // if (superstate.direction() == TDirection::LEFT)\n        //     angle = 90;\n        // else\n        //     angle = -90;\n        //this->configure<OrNavigation, CbRotate>(angle);\n\n        float offset = 7;\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            // - offset because we are looking to the north and we have to turn clockwise\n            this->configure<OrNavigation, CbAbsoluteRotate>(0 - offset);\n        }\n        else\n        {\n            // - offset because we are looking to the south and we have to turn counter-clockwise\n            this->configure<OrNavigation, CbAbsoluteRotate>(180 + offset);\n        }\n\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_2.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate2 : smacc::SmaccState<StiSPatternRotate2, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward2>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward1>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        float offset = 7;\n        float angle = 0;\n        if (SS::direction() == TDirection::LEFT)\n            angle = 90 + offset ;\n        else\n            angle = -90 - offset;\n\n        configure_orthogonal<OrNavigation, CbRotate>(angle);\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_3.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate3 : smacc::SmaccState<StiSPatternRotate3, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward3>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward2>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 7;\n        float angle = 0;\n        if (superstate.direction() == TDirection::LEFT)\n            angle = -90 - offset;\n        else\n            angle = +90 + offset;\n\n        this->configure<OrNavigation, CbRotate>(angle);\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_4.h",
    "content": "namespace sm_dance_bot\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate4 : smacc::SmaccState<StiSPatternRotate4, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward4>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward3>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[SsrSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 7;\n        float angle = 0;\n        if (superstate.direction() == TDirection::LEFT)\n            angle = -90 - offset;\n        else\n            angle = 90 + offset;\n\n        this->configure<OrNavigation, CbRotate>(angle);\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_acquire_sensors.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n\nusing namespace smacc::default_events;\n\n// STATE DECLARATION\nstruct StAcquireSensors : smacc::SmaccState<StAcquireSensors, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n   // DECLARE CUSTOM OBJECT TAGS\n   struct ON_SENSORS_AVAILABLE : SUCCESS\n   {\n   };\n   struct SrAcquireSensors;\n\n   // TRANSITION TABLE\n   typedef mpl::list<\n\n       Transition<EvAllGo<SrAllEventsGo, SrAcquireSensors>, StEventCountDown, ON_SENSORS_AVAILABLE>,\n       Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n       >\n       reactions;\n\n   // STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n      configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n      configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n      configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n      configure_orthogonal<OrUpdatablePublisher, cl_ros_publisher::CbDefaultPublishLoop>();\n\n      // Create State Reactor\n      auto srAllSensorsReady = static_createStateReactor<SrAllEventsGo,\n                                                         smacc::state_reactors::EvAllGo<SrAllEventsGo, SrAcquireSensors>,\n                                                         mpl::list<\n                                                                   EvTopicMessage<CbLidarSensor, OrObstaclePerception>,\n                                                                   EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>\n                                                                  >>();\n\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbLidarSensor, OrObstaclePerception>>();\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>>();\n\n      //srAllSensorsReady->setOutputEvent<smacc::state_reactors::EvAllGo<SrAllEventsGo, SrAcquireSensors>>();\n      // srAllSensorsReady->setOutputEvent<EvAllGo<SrAllEventsGo, SrAcquireSensors>>();\n   }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_event_count_down.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StEventCountDown : smacc::SmaccState<StEventCountDown, MsDanceBotRunMode>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCountdownEnd<SrEventCountdown>, StNavigateToWaypointsX>,\n    Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //   configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n        //   configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n        //   configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n        //   configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n\n        // Create State Reactor\n\n        //auto srCountdown = static_createStateReactor<SrEventCountdown>(5);\n        //srCountdown->addInputEvent<EvTimer<ClRosTimer, OrTimer>>();\n        //srCountdown->setOutputEvent<EvCountdownEnd<SrEventCountdown>>();\n\n        auto srCountdown = static_createStateReactor<SrEventCountdown,\n                                                         EvCountdownEnd<SrEventCountdown>,\n                                                         mpl::list<\n                                                                  EvTimer<ClRosTimer, OrTimer>\n                                                                  >>(5);\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_forward_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateForward1 : smacc::SmaccState<StNavigateForward1, MsDanceBotRunMode>\n{\nusing SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StRotateDegrees2>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StNavigateToWaypointsX, ABORT>,\n  Transition<EvActionPreempted<ClMoveBaseZ, OrNavigation>, StNavigateToWaypointsX, PREEMPT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(1);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n\n  void runtimeConfigure()\n  {\n    ClMoveBaseZ *move_base_action_client;\n    this->requiresClient(move_base_action_client);\n\n    // we careful with the lifetime of the callbac, us a scoped connection if is not forever\n    move_base_action_client->onSucceeded(&StNavigateForward1::onActionClientSucceeded, this);\n  }\n\n  void onActionClientSucceeded(ClMoveBaseZ::ResultConstPtr &msg)\n  {\n    ROS_INFO_STREAM(\" [Callback SmaccSignal] Success Detected from StAquireSensors (connected to client signal), result data: \" << *msg);\n  }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_forward_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateForward2 : smacc::SmaccState<StNavigateForward2, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StRotateDegrees5>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(1);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_reverse_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateReverse1 : smacc::SmaccState<StNavigateReverse1, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StRotateDegrees3>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_reverse_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateReverse2 : smacc::SmaccState<StNavigateReverse2, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_reverse_3.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateReverse3 : smacc::SmaccState<StNavigateReverse3, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StNavigateToWaypoint1>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_to_waypoint_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateToWaypoint1 : smacc::SmaccState<StNavigateToWaypoint1, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateGlobalPosition, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbNavigateGlobalPosition, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateGlobalPosition>(0, 0, 0);\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"All Done!\");\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_navigate_to_waypoints_x.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StNavigateToWaypointsX : smacc::SmaccState<StNavigateToWaypointsX, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// CUSTOM TRANSITION TAGS\n  struct TRANSITION_1 : SUCCESS{};\n  struct TRANSITION_2 : SUCCESS{};\n  struct TRANSITION_3 : SUCCESS{};\n  struct TRANSITION_4 : SUCCESS{};\n  struct TRANSITION_5 : SUCCESS{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvWaypoint0<ClMoveBaseZ, OrNavigation>, SS1::SsRadialPattern1, TRANSITION_1>,\n  Transition<EvWaypoint1<ClMoveBaseZ, OrNavigation>, SS2::SsRadialPattern2, TRANSITION_2>,\n  Transition<EvWaypoint2<ClMoveBaseZ, OrNavigation>, SS3::SsRadialPattern3, TRANSITION_3>,\n  Transition<EvWaypoint3<ClMoveBaseZ, OrNavigation>, SS4::SsFPattern1, TRANSITION_4>,\n  Transition<EvWaypoint4<ClMoveBaseZ, OrNavigation>, SS5::SsSPattern1, TRANSITION_5>,\n  Transition<EvCbFailure<ClMoveBaseZ, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    configure_orthogonal<OrNavigation, CbNavigateNextWaypoint>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees1 : smacc::SmaccState<StRotateDegrees1, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateForward1>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ 90);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees2 : smacc::SmaccState<StRotateDegrees2, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -90);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_3.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees3 : smacc::SmaccState<StRotateDegrees3, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ 180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_4.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees4 : smacc::SmaccState<StRotateDegrees4, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateReverse2>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_5.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees5 : smacc::SmaccState<StRotateDegrees5, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/states/st_rotate_degrees_6.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot\n{\n// STATE DECLARATION\nstruct StRotateDegrees6 : smacc::SmaccState<StRotateDegrees6, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateReverse3>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/superstates/ss_f_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot {\nnamespace f_pattern_states {\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\n// FORWARD DECLARATIONS OF INNER STATES\ntemplate <typename SS> class StiFPatternRotate1;\ntemplate <typename SS> class StiFPatternForward1;\ntemplate <typename SS> class StiFPatternReturn1;\ntemplate <typename SS> class StiFPatternRotate2;\ntemplate <typename SS> class StiFPatternForward2;\ntemplate <typename SS> class StiFPatternStartLoop;\n} // namespace f_pattern_states\n} // namespace sm_dance_bot\nnamespace sm_dance_bot {\nnamespace SS4 {\nusing namespace f_pattern_states;\n\n// STATE DECLARATION\nstruct SsFPattern1 : smacc::SmaccState<SsFPattern1, MsDanceBotRunMode, StiFPatternStartLoop<SsFPattern1>>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiFPatternStartLoop<SsFPattern1>>, StNavigateForward2, ENDLOOP> //,\n\n    >reactions;\n\n// STATE VARIABLES\n    // superstate parameters\n    static constexpr float ray_lenght_meters() { return 3.25; }\n    static constexpr float pitch_lenght_meters() { return 0.75; }\n    static constexpr int total_iterations() { return 10; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n\n    // superstate state variables\n    int iteration_count;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n        iteration_count = 0;\n    }\n}; // namespace SS4\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\n\n} // namespace SS4\n} // namespace sm_dance_bot\n\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_rotate_1.h>\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_forward_1.h>\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_return_1.h>\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_rotate_2.h>\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_forward_2.h>\n#include <sm_dance_bot/states/f_pattern_states/sti_fpattern_loop_start.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/superstates/ss_radial_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot {\nnamespace SS1 {\nnamespace sm_dance_bot {\nnamespace radial_motion_states {\n\n//FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\nusing namespace sm_dance_bot::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern1 : smacc::SmaccState<SsRadialPattern1, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StRotateDegrees1, ENDLOOP>\n\n    >reactions;\n\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 4; }\n\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern1;\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS1\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/superstates/ss_radial_pattern_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot {\nnamespace SS2 {\nnamespace sm_dance_bot {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATIONS OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\nusing namespace sm_dance_bot::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern2 : smacc::SmaccState<SsRadialPattern2, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateReverse1, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    int iteration_count = 0;\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 5; }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern2;\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS2\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/superstates/ss_radial_pattern_3.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot {\nnamespace SS3 {\nnamespace sm_dance_bot {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot\nusing namespace sm_dance_bot::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern3 : smacc::SmaccState<SsRadialPattern3, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StRotateDegrees4, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    int iteration_count;\n\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 4; }\n\n    void runtimeConfigure()\n    {\n        iteration_count = 0;\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern3;\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS3\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/include/sm_dance_bot/superstates/ss_s_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot {\nnamespace SS5 {\nnamespace sm_dance_bot {\nnamespace s_pattern_states {\n\n// FORWARD DECLARATIONS OF INNER STATES\nclass StiSPatternRotate1;\nclass StiSPatternForward1;\nclass StiSPatternRotate2;\nclass StiSPatternForward2;\nclass StiSPatternRotate3;\nclass StiSPatternForward3;\nclass StiSPatternRotate4;\nclass StiSPatternForward4;\nclass StiSPatternLoopStart;\n} // namespace s_pattern_states\n} // namespace sm_dance_bot\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\nusing namespace sm_dance_bot::s_pattern_states;\n\n// STATE DECLARATION\nstruct SsSPattern1 : smacc::SmaccState<SsSPattern1, MsDanceBotRunMode, StiSPatternLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiSPatternLoopStart>, StRotateDegrees6, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    static constexpr float pitch1_lenght_meters() { return 0.75; }\n    static constexpr float pitch2_lenght_meters() { return 1.45; }\n    static constexpr int total_iterations() { return 11; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n\n    int iteration_count;\n\n    void runtimeConfigure()\n    {\n        this->iteration_count = 0;\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsSPattern1;\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_1.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_forward_1.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_2.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_forward_2.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_3.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_forward_3.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_rotate_4.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_forward_4.h>\n#include <sm_dance_bot/states/s_pattern_states/sti_spattern_loop_start.h>\n} // namespace SS5\n} // namespace sm_dance_bot\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/launch/readme.md",
    "content": "# Dance Bot State Machine\n## Setup and requirements\n\nMake sure that you have installed all the dependencies. For example this demo depends on rigeback robot simulation.\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nAfter that you have to build the smacc ros workspace using catkin_make.\n\n```\ncatkin_make\n```\n\nAfter you build, remember to source the proper devel folder.\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\n## Default demo launching\nBelow is the default launch command to launch this demo:\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch\n```\n\n## Lightweight demo launching\n\nWe use this launch command to start the process hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/launch/ridgeback_simulation.launch",
    "content": "<launch>\n    <arg name=\"show_gz_client\" default=\"true\"/>\n\n    <include file=\"$(find ridgeback_gazebo)/launch/ridgeback_world.launch\">\n        <arg name=\"gui\" value=\"$(arg show_gz_client)\"/>\n    </include>\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"true\" name=\"move_base\" launch-prefix=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e \">\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/local_costmap_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/local_costmap_params.yaml\" command=\"load\" />\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/base_local_planner_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/base_local_planner_params.yaml\" command=\"load\" />\n\n        <rosparam file=\"$(find ridgeback_navigation)/params/move_base_params.yaml\" command=\"load\" />\n\n        <param name=\"base_global_planner\" type=\"string\" value=\"navfn/NavfnROS\" />\n        <param name=\"base_local_planner\" value=\"base_local_planner/TrajectoryPlannerROS\"/>\n\n        <remap from=\"odom\" to=\"odometry/filtered\" />\n    </node>\n\n    <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find ridgeback_navigation)/maps/ridgeback_race.yaml\" output=\"screen\"/>\n    <!--- Run AMCL -->\n    <include file=\"$(find ridgeback_navigation)/launch/include/amcl.launch\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/launch/sm_dance_bot.launch",
    "content": "<launch>\n\n    <!--========= LAUNCH FILE ARGUMENTS ======================================================-->\n    <!-- defines the xterm parameters for the clients, set to empty to skip using xterm window-->\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <!-- defines the xterm parameters for the state machine, set to empty to skip using xterm window-->\n    <arg name=\"sm_xterm\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e\" />\n\n    <!-- if true, gazebo client is shown -->\n    <arg name=\"show_gz_client\" default=\"true\" />\n\n    <!-- if true, smacc_viewer is shown -->\n    <arg name=\"show_smacc_viewer\" default=\"true\" />\n\n    <!-- if true, rviz is shown -->\n    <arg name=\"show_rviz\" default=\"true\" />\n\n    <!-- It does not start the sm node in order to start it from your standalone process with debugger-->\n    <arg name=\"debug\" default=\"false\" />\n\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_dance_bot)/config/rosconsole.config\" />\n\n    <!--================================================================================-->\n    <!-- load the navigation environment simulated in gazebo-->\n    <include file=\"$(find sm_dance_bot)/launch/ridgeback_simulation.launch\">\n        <arg name=\"show_gz_client\" value=\"$(arg show_gz_client)\" />\n    </include>\n\n    <!--  setup smacc planners configuration  -->\n    <group ns=\"move_base\">\n        <!-- backward local planner -->\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/backward_local_planner.yaml\" command=\"load\" />\n        <!-- forward local planner -->\n        <rosparam file=\"$(find sm_dance_bot)/config/move_base_client/forward_local_planner.yaml\" command=\"load\" />\n    </group>\n\n    <!-- load state machine parameters -->\n    <rosparam command=\"load\" file=\"$(find sm_dance_bot)/config/sm_dance_bot_config.yaml\" />\n\n    <group ns=\"sm_dance_bot\">\n        <!-- set run mode -->\n        <param name=\"run_mode\" value=\"debug\" />\n        <!-- load flight plan -->\n        <param name=\"waypoints_plan\" value=\"$(find sm_dance_bot)/config/move_base_client/waypoints_plan.yaml\" />\n    </group>\n\n    <!-- state machine node -->\n    <node pkg=\"sm_dance_bot\" type=\"sm_dance_bot\" name=\"sm_dance_bot\" launch-prefix=\"$(arg sm_xterm)\" unless=\"$(arg debug)\">\n        <remap from=\"/odom\" to=\"/odometry/filtered\" />\n        <remap from=\"/sm_dance_bot/odom_tracker/odom_tracker_path\" to=\"/odom_tracker_path\"/>\n        <remap from=\"/sm_dance_bot/odom_tracker/odom_tracker_stacked_path\" to=\"/odom_tracker_path_stacked\"/>\n    </node>\n\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find sm_dance_bot)/config/navigation.rviz\" if=\"$(arg show_rviz)\">\n        <remap from=\"/remap_smacc_status\" to=\"/SmDanceBot/smacc/status\" />\n    </node>\n\n    <node pkg=\"sm_dance_bot\" type=\"led_action_server_node\" name=\"led_action_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot\" type=\"temperature_sensor_node\" name=\"temperature_sensor_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot\" type=\"service_node_3.py\" name=\"service_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <!-- <node pkg=\"smacc_viewer\" type=\"smacc_viewer_node.py\" name=\"smacc_viewer\" if=\"$(arg show_smacc_viewer)\"/> -->\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_dance_bot</name>\n    <version>1.4.16</version>\n  <description>The dance_bot package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/dance_bot</url> -->\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>actionlib</depend>\n  <depend>actionlib_msgs</depend>\n  <depend>move_base_z_client_plugin</depend>\n  <depend>xterm</depend>\n\n  <depend>ros_publisher_client</depend>\n  <depend>multirole_sensor_client</depend>\n\n  <depend>sr_all_events_go</depend>\n  <depend>sr_event_countdown</depend>\n  <depend>sr_conditional</depend>\n  <depend>ros_timer_client</depend>\n\n  <depend>ridgeback_gazebo</depend>\n  <depend>ridgeback_navigation</depend>\n\n  <depend>tf</depend>\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/action_server_node_3/src/action_server_node_3.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/led_action_server/action/LEDControl.action",
    "content": "uint8 command\n\n# Possible command values\nuint8 CMD_ON = 0\nuint8 CMD_OFF = 1\n---\nuint8 state\n\n# Possible feeedback values (tool states)\nuint8 STATE_UNKNOWN = 0\nuint8 STATE_RUNNING = 1\nuint8 STATE_IDLE = 2\n---\nuint8 result\n\n# Possible result values\nuint8 RESULT_SUCCESS = 0\nuint8 RESULT_ERROR = 1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/led_action_server/src/led_action_server_node.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <actionlib/server/simple_action_server.h>\n#include <std_msgs/UInt8.h>\n#include <functional>\n#include <dynamic_reconfigure/DoubleParameter.h>\n#include <dynamic_reconfigure/Reconfigure.h>\n#include <dynamic_reconfigure/Config.h>\n#include <sm_dance_bot/LEDControlAction.h>\n#include <sm_dance_bot/LEDControlActionResult.h>\n#include <sm_dance_bot/LEDControlResult.h>\n#include <memory>\n#include <visualization_msgs/MarkerArray.h>\n\ntypedef actionlib::SimpleActionServer<sm_dance_bot::LEDControlAction> Server;\n\n// This class describes a preemptable-on/off tool action server to be used from smacc\n// shows in rviz a sphere whose color describe the current state (unknown, running, idle)\nclass LEDActionServer\n{\npublic:\n  std::shared_ptr<Server> as_ ;\n\n  ros::Publisher stateMarkerPublisher_;\n\n  sm_dance_bot::LEDControlGoal cmd;\n\n  uint8_t currentState_;\n\n/**\n******************************************************************************************************************\n* constructor()\n******************************************************************************************************************\n*/\n  LEDActionServer()\n  {\n    currentState_ =  sm_dance_bot::LEDControlResult::STATE_UNKNOWN;\n  }\n\n/**\n******************************************************************************************************************\n* publishFeedback()\n******************************************************************************************************************\n*/\nvoid publishFeedback()  // Note: \"Action\" is not appended to DoDishes here\n{\n    sm_dance_bot::LEDControlFeedback feedback_msg;\n\n    as_->publishFeedback(feedback_msg);\n}\n\n/**\n******************************************************************************************************************\n* execute()\n******************************************************************************************************************\n*/\nvoid execute(const sm_dance_bot::LEDControlGoalConstPtr& goal)  // Note: \"Action\" is not appended to DoDishes here\n{\n  ROS_INFO_STREAM(\"Tool action server request: \"<< *goal);\n  cmd = *goal;\n\n  if(goal->command == sm_dance_bot::LEDControlGoal::CMD_ON)\n  {\n    currentState_ =  sm_dance_bot::LEDControlResult::STATE_RUNNING;\n  }\n  else  if (goal->command == sm_dance_bot::LEDControlGoal::CMD_OFF)\n  {\n    currentState_ =  sm_dance_bot::LEDControlResult::STATE_IDLE;\n  }\n\n  // 10Hz internal loop\n  ros::Rate rate(20);\n\n  while(ros::ok())\n  {\n    if(as_->isPreemptRequested())\n    {\n       // a new request is being executed, we will stop this one\n       ROS_WARN(\"LEDActionServer request preempted. Forgetting older request.\");\n       as_->setPreempted();\n       return;\n    }\n\n    publishFeedback();\n    publishStateMarker();\n    rate.sleep();\n  }\n\n   // never reach succeeded because were are interested in keeping the feedback alive\n   as_->setSucceeded();\n}\n\n/**\n******************************************************************************************************************\n* run()\n******************************************************************************************************************\n*/\nvoid run()\n{\n  ros::NodeHandle n;\n  ROS_INFO(\"Creating tool action server\");\n\n  as_ = std::make_shared<Server>(n, \"led_action_server\", boost::bind(&LEDActionServer::execute, this,  _1), false);\n  ROS_INFO(\"Starting Tool Action Server\");\n\n  stateMarkerPublisher_ = n.advertise<visualization_msgs::MarkerArray>(\"tool_markers\", 1);\n\n  as_->start();\n\n  ros::spin();\n}\n\n/**\n******************************************************************************************************************\n* publishStateMarker()\n******************************************************************************************************************\n*/\nvoid publishStateMarker()\n{\n    visualization_msgs::Marker marker;\n    marker.header.frame_id = \"base_link\";\n    marker.header.stamp = ros::Time::now ();\n\n    marker.ns = \"tool_namespace\";\n    marker.id = 0;\n    marker.type = visualization_msgs::Marker::SPHERE;\n    marker.action = visualization_msgs::Marker::ADD;\n\n    marker.scale.x = 0.2;\n    marker.scale.y = 0.2;\n    marker.scale.z = 0.2;\n\n    marker.color.a = 1;\n\n    if(currentState_ == sm_dance_bot::LEDControlResult::STATE_RUNNING)\n    {\n      // show green ball\n      marker.color.r = 0;\n      marker.color.g = 1;\n      marker.color.b = 0;\n    }\n    else if (currentState_ == sm_dance_bot::LEDControlResult::STATE_IDLE)\n    {\n      // show gray ball\n      marker.color.r = 0.7;\n      marker.color.g = 0.7;\n      marker.color.b = 0.7;\n    }\n    else\n    {\n      // show black ball\n      marker.color.r = 0;\n      marker.color.g = 0;\n      marker.color.b = 0;\n    }\n\n    marker.pose.orientation.w=1;\n    marker.pose.position.x=0;\n    marker.pose.position.y=0;\n    marker.pose.position.z=1;\n\n    visualization_msgs::MarkerArray ma;\n    ma.markers.push_back(marker);\n\n    stateMarkerPublisher_.publish(ma);\n}\n};\n\n/**\n******************************************************************************************************************\n* main()\n******************************************************************************************************************\n*/\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"led_action_server_node\");\n  LEDActionServer LEDActionServer;\n  LEDActionServer.run();\n\n  return 0;\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/lidar_node/src/lidar_node.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/service_node_3/__init__.py",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/service_node_3/src/service_node_3.py",
    "content": "#!/usr/bin/env python\n\n\nimport rospy\nimport std_srvs\n\n\nif __name__ == \"__main__\":\n\n    def set_bool_service(req):\n        rospy.loginfo(\"RECEIVING SET BOOL SERVICE REQUEST: value=\" + str(req.data))\n\n        response = std_srvs.srv.SetBoolResponse()\n        response.message = \"OK, value set\"\n        response.success = True\n        return response\n\n    rospy.init_node(\"service_node3\")\n    s = rospy.Service(\"service_node3\", std_srvs.srv.SetBool, set_bool_service)\n    rospy.spin()\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/servers/temperature_sensor_node/src/temperature_sensor_node.cpp",
    "content": "#include <ros/ros.h>\n#include <sensor_msgs/Temperature.h>\n\nint main(int argc, char** argv)\n{\n    ros::init(argc,argv, \"temperature_sensor_node\");\n\n    ros::NodeHandle nh;\n    auto pub = nh.advertise<sensor_msgs::Temperature>(\"/temperature\",1);\n\n    ros::Rate r(10);\n\n    while(ros::ok())\n    {\n        sensor_msgs::Temperature msg;\n        pub.publish(msg);\n\n        r.sleep();\n        ros::spinOnce();\n    }\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/src/clients/cl_led/cl_led.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <sm_dance_bot/clients/cl_led/cl_led.h>\n//#include <pluginlib/class_list_macros.h>\n\nnamespace sm_dance_bot\n{\nnamespace cl_led\n{\n\nClLED::ClLED(std::string actionServerName) : Base(actionServerName)\n{\n}\n\nstd::string ClLED::getName() const\n{\n    return \"TOOL ACTION CLIENT\";\n}\n\nClLED::~ClLED()\n{\n}\n} // namespace cl_led\n\n//PLUGINLIB_EXPORT_CLASS(cl_led::ClLED, smacc::ISmaccComponent)\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/src/sm_dance_bot.cpp",
    "content": "#include <sm_dance_bot/sm_dance_bot.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"dance_bot\");\n    ros::NodeHandle nh;\n\n    ros::Duration(5).sleep();\n    smacc::run<SmDanceBot>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot/urdf/empty.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_dance_bot\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco, brett2@robosoft-ai.com, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_dance_bot_2)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin multirole_sensor_client tf sr_all_events_go sr_event_countdown ros_timer_client sr_conditional ros_publisher_client actionlib actionlib_msgs)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\nadd_action_files(\n   DIRECTORY\n   servers/led_action_server/action/\n\n   FILES\n   LEDControl.action\n)\n\ngenerate_messages(\n   DEPENDENCIES\n   actionlib_msgs\n )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES sm_dance_bot_2\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}\n              src/sm_dance_bot_2.cpp\n              src/clients/cl_led/cl_led.cpp)\n\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n\n add_executable(temperature_sensor_node_${PROJECT_NAME} servers/temperature_sensor_node/src/temperature_sensor_node.cpp)\n set_target_properties(temperature_sensor_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"temperature_sensor_node\")\n\n target_link_libraries(temperature_sensor_node_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n add_executable(led_action_server_node_${PROJECT_NAME} servers/led_action_server/src/led_action_server_node.cpp)\n set_target_properties(led_action_server_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"led_action_server_node\")\n target_link_libraries(\n   led_action_server_node_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n)\n\nadd_dependencies(led_action_server_node_${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\ninstall(PROGRAMS\n   servers/service_node_3/src/service_node_3.py\n   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS\n  ${PROJECT_NAME}\n   temperature_sensor_node_${PROJECT_NAME}\n   led_action_server_node_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME} temperature_sensor_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(DIRECTORY\n    launch/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\ninstall(DIRECTORY\n    urdf/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf\n)\n\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_dance_bot.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_dance_bot/docs/smacc_state_machine_20200222-125058.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> A full-featured state machine example, that highlights the capabilities of SMACC & the ROS Navigation Stack via the MoveBaseZ Client.<br></br>\n\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__dance__bot.html\">Doxygen Namespace & Class Reference</a>\n\nTo see a video of this state machine in action click <a href=\"https://www.youtube.com/watch?v=9iyX_x05d3Q&t=7s\">here</a>.\n\n<h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file for the full gazebo demo...\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch\n```\n\nOr, you can run the lightweight demo...\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n\nThis launch command starts the process by hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/backward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nBackwardLocalPlanner:\n    k_rho: -1.4 # linear distance to the goal gain, default = -1.0 (related with carrot distance)\n    k_alpha: -0.1\n    k_betta: -1.0\n    carrot_distance: 0.3 #meters default 0.5\n    carrot_angular_distance: 0.3 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.003 # 3 mm\n    yaw_goal_tolerance: 0.3\n    pure_spinning_straight_line_mode: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.157\n  xy_goal_tolerance: 0.15\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/costmap_common_params.yaml",
    "content": "\nmap_type: costmap\norigin_z: 0.0\nz_resolution: 1\nz_voxels: 2\n\nobstacle_range: 12.5\nraytrace_range: 3.0\n\npublish_voxel_map: false\ntransform_tolerance: 0.5\nmeter_scoring: true\n\nfootprint: [[0.48, -0.40], [0.48, 0.40], [-0.48, 0.40], [-0.48, -0.40]]\nfootprint_padding: 0.3\n\nplugins:\n- {name: obstacles_layer, type: \"costmap_2d::ObstacleLayer\"}\n- {name: inflater_layer, type: \"costmap_2d::InflationLayer\"}\n\nobstacles_layer:\n  observation_sources: scan\n  scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 10.5, raytrace_range: 3.0}\n\ninflater_layer:\n inflation_radius: 0.2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/forward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nForwardLocalPlanner:\n    k_rho: 2.0\n    k_alpha: -0.4\n    k_betta: -1.0\n    carrot_distance: 0.2 #meters\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.04\n    yaw_goal_tolerance: 0.01\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/global_costmap_params.yaml",
    "content": "global_costmap:\n  global_frame: odom\n  robot_base_frame: base_link\n  update_frequency: 20\n  publish_frequency: 5\n  width: 40.0\n  height: 40.0\n  resolution: 0.05\n  origin_x: -20.0\n  origin_y: -20.0\n  static_map: true\n  rolling_window: false\n  inflater_layer:\n    inflation_radius: 0.6\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: odom\n   robot_base_frame: base_link\n   update_frequency: 20.0\n   publish_frequency: 5.0\n   width: 10.0\n   height: 10.0\n   resolution: 0.05\n   static_map: false\n   rolling_window: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/move_base_client/waypoints_plan.yaml",
    "content": "waypoints:\n  # POINT 0\n  - position:\n      x: 3.0\n      y: -2.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 1\n  - position:\n      x: -5.75\n      y: 3.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 2\n  - position:\n      x: -10.25\n      y: -4.25\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 3\n  - position:\n      x: 2.0\n      y: -8.58 # north west corner of the room\n      #y: -12.35 # south west corner of the room\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n    # POINT 4\n  - position:\n      x: -10\n      y: 13.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 4\n  - position:\n      x: -0.0\n      y: 0.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  #POINT 5\n  - position:\n      x: 6.0\n      y: 8.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/navigation.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 83\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Odometry1/Shape1\n        - /TF1/Frames1\n        - /SmaccRvizDisplay1\n      Splitter Ratio: 0.3861111104488373\n    Tree Height: 723\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nPreferences:\n  PromptSaveOnExit: true\nToolbars:\n  toolButtonStyle: 2\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 209; 209; 214\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 40\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.4000000059604645\n      Class: rviz/RobotModel\n      Collision Enabled: false\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        axle_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        chassis_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        mid_mount:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        rear_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        top_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.25\n      Name: Axes\n      Radius: 0.05000000074505806\n      Reference Frame: odom\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.05000000074505806\n      Style: Flat Squares\n      Topic: front/scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: true\n      Enabled: false\n      Name: Costmaps\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Alpha: 1\n      Axes Length: 1\n      Axes Radius: 0.10000000149011612\n      Class: rviz/Pose\n      Color: 255; 0; 255\n      Enabled: true\n      Head Length: 0.20000000298023224\n      Head Radius: 0.10000000149011612\n      Name: MoveBase Goal\n      Shaft Length: 0.5\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow\n      Topic: /move_base/current_goal\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 85; 255\n      Enabled: true\n      Name: Polygon\n      Topic: /move_base/local_costmap/obstacles_layer_footprint/footprint_stamped\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 85; 170; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path_stacked\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 255; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: FW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 255; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/ForwardGlobalPlanner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 170; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: BW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 170; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /backward_planner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Global Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/NavfnROS/plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Local Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/TrajectoryPlannerROS/local_plan\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/ForwardLocalPlanner/goal_marker\n      Name: FW Goal\n      Namespaces:\n        my_namespace2: true\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/BackwardLocalPlanner/goal_marker\n      Name: BW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/backward_planner/markers\n      Name: BackwardMotionPlanner\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Angle Tolerance: 0.10000000149011612\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.30000001192092896\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 15000\n      Name: Odometry\n      Position Tolerance: 0.10000000149011612\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.10000000149011612\n        Color: 255; 25; 0\n        Head Length: 0.003000000026077032\n        Head Radius: 0\n        Shaft Length: 0.05000000074505806\n        Shaft Radius: 0.019999999552965164\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        axle_link:\n          Value: false\n        base_link:\n          Value: true\n        chassis_link:\n          Value: false\n        front_cover_link:\n          Value: false\n        front_laser:\n          Value: false\n        front_left_wheel_link:\n          Value: false\n        front_lights_link:\n          Value: false\n        front_right_wheel_link:\n          Value: false\n        front_rocker_link:\n          Value: false\n        imu_link:\n          Value: false\n        left_side_cover_link:\n          Value: false\n        map:\n          Value: true\n        mid_mount:\n          Value: false\n        odom:\n          Value: true\n        rear_cover_link:\n          Value: false\n        rear_left_wheel_link:\n          Value: false\n        rear_lights_link:\n          Value: false\n        rear_right_wheel_link:\n          Value: false\n        rear_rocker_link:\n          Value: false\n        right_side_cover_link:\n          Value: false\n        top_link:\n          Value: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: false\n      Show Axes: true\n      Show Names: true\n      Tree:\n        map:\n          odom:\n            base_link:\n              chassis_link:\n                axle_link:\n                  front_rocker_link:\n                    front_left_wheel_link:\n                      {}\n                    front_right_wheel_link:\n                      {}\n                  rear_rocker_link:\n                    rear_left_wheel_link:\n                      {}\n                    rear_right_wheel_link:\n                      {}\n                front_cover_link:\n                  {}\n                front_laser:\n                  {}\n                front_lights_link:\n                  {}\n                imu_link:\n                  {}\n                left_side_cover_link:\n                  {}\n                rear_cover_link:\n                  {}\n                rear_lights_link:\n                  {}\n                right_side_cover_link:\n                  {}\n                top_link:\n                  {}\n              mid_mount:\n                {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 25; 255; 0\n      Enabled: true\n      Name: GridCells\n      Topic: \"\"\n      Value: true\n    - Alpha: 1\n      Arrow Length: 0.05000000074505806\n      Axes Length: 0.30000001192092896\n      Axes Radius: 0.009999999776482582\n      Class: rviz/PoseArray\n      Color: 255; 25; 0\n      Enabled: true\n      Head Length: 0.07000000029802322\n      Head Radius: 0.029999999329447746\n      Name: Pose Estimation\n      Shaft Length: 0.23000000417232513\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow (Flat)\n      Topic: /particlecloud\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /tool_markers\n      Name: MarkerArray\n      Namespaces:\n        tool_namespace: true\n      Queue Size: 1\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: Global Planner Costmap\n      Topic: /move_base/global_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: false\n      Name: LocalPlanner Costmap\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Class: smacc_rviz_plugin/SmaccRvizDisplay\n      CurrentState: \"\"\n      Enabled: true\n      Name: SmaccRvizDisplay\n      Topic: /remap_smacc_status\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: odom\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Theta std deviation: 0.2617993950843811\n      Topic: /initialpose\n      X std deviation: 0.5\n      Y std deviation: 0.5\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: -0.004999920725822449\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Scale: 60.632442474365234\n      Target Frame: base_link\n      Value: TopDownOrtho (rviz)\n      X: 5.9219889640808105\n      Y: -5.189697265625\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1025\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001b500000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005820000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1853\n  X: 67\n  Y: 27\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.undo_path_global_planner=DEBUG\nlog4j.logger.ros.backward_local_planner=DEBUG\nlog4j.logger.ros.move_base=DEBUG\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/config/sm_dance_bot_2_config.yaml",
    "content": "SmDanceBot2:\n   signal_detector_loop_freq: 20\n\n# RadialMotionStateMachine:\n#     NavigateToRadialStart:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 start_position_x: 3\n#                 start_position_y: 0\n#     RotateDegress:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 initial_orientation_index: 0 # the initial index of the linear motion (factor of angle_increment_degrees)\n#                 angle_increment_degree: 15    # the increment of angle between to linear motions\n#                 linear_trajectories_count: 12  # the number of linear trajectories of the radial motion\n#     NavigateToEndPoint:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 straight_motion_distance: 3.5\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/docs/Global Transition Rules.txt",
    "content": "GLOBAL TRANSITION RULES\n---------------------------------\n\nFor all states, superstates, If any sensor is lost, transition back to st_acquire_sensors.\n\nFor all states, If the Navigation Orthogonal is aborted, transition to st_navigate_to_waypoints_x.\n\n\nFor all states, superstates, but not ssrs, If Keyboard Orthogonal = N, transition to next success state.\n\nFor all states, superstates, but not ssrs, If Keyboard Orthogonal = P, transition to previous state.\n\nFor all states, If Navigation Orthogonal is prempted, transition to previous state.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_led/cl_led.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_action_client_base.h>\n#include <sm_dance_bot_2/LEDControlAction.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_led\n{\nclass ClLED : public smacc::client_bases::SmaccActionClientBase<sm_dance_bot_2::LEDControlAction>\n{\n\npublic:\n    SMACC_ACTION_CLIENT_DEFINITION(sm_dance_bot_2::LEDControlAction);\n\n    ClLED(std::string actionServerName);\n    virtual std::string getName() const override;\n    virtual ~ClLED();\n};\n} // namespace cl_led\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_led/client_behaviors/cb_led_off.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot_2/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_led\n{\nclass CbLEDOff : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_OFF;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_led/client_behaviors/cb_led_on.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot_2/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_led\n{\nclass CbLEDOn : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_ON;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_lidar/cl_lidar.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/LaserScan.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_lidar\n{\n\nclass ClLidarSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::LaserScan>\n{\npublic:\n    ClLidarSensor()\n    {\n    }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n#include <sensor_msgs/LaserScan.h>\n#include <sm_dance_bot_2/clients/cl_lidar/cl_lidar.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_lidar\n{\nstruct CbLidarSensor : cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClLidarSensor>\n{\npublic:\n  CbLidarSensor()\n  {\n    ROS_INFO(\"CbLidarSensor Constructor\");\n  }\n\n  virtual void onEntry() override\n  {\n    ROS_INFO(\"CbLidarSensor onEntry\");\n    cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClLidarSensor>::onEntry();\n  }\n\n  virtual void onMessageCallback(const sensor_msgs::LaserScan &msg) override\n  {\n  }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_service3/cl_service3.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_service_client.h>\n#include <std_srvs/SetBool.h>\nnamespace sm_dance_bot_2\n{\nnamespace cl_service3\n{\nclass ClService3 : public smacc::client_bases::SmaccServiceClient<std_srvs::SetBool>\n{\npublic:\n  ClService3()\n  {\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_service3/client_behaviors/cb_service3.h",
    "content": "#include <smacc/smacc_client_behavior.h>\n#include <sm_dance_bot_2/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_service3\n{\nenum class Service3Command\n{\n  SERVICE3_ON,\n  SERVICE3_OFF\n};\n\nclass CbService3 : public smacc::SmaccClientBehavior\n{\nprivate:\n  ClService3 *serviceClient_;\n  Service3Command value_;\n\npublic:\n  CbService3(Service3Command value)\n  {\n    value_ = value;\n  }\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(serviceClient_);\n\n    std_srvs::SetBool req;\n    if (value_ == Service3Command::SERVICE3_ON)\n      req.request.data = true;\n    else\n      req.request.data = false;\n\n    serviceClient_->call(req);\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_string_publisher/cl_string_publisher.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_publisher_client.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_string_publisher\n{\nclass ClStringPublisher : public smacc::client_bases::SmaccPublisherClient\n{\npublic:\n    ClStringPublisher(std::string topicName)\n        : smacc::client_bases::SmaccPublisherClient()\n    {\n        this->configure<std_msgs::String>(topicName);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_2/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_client_behavior.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_string_publisher\n{\nclass CbStringPublisher : public smacc::SmaccClientBehavior\n{\npublic:\n    ClStringPublisher *publisherClient_;\n    std::string msg_;\n\n    CbStringPublisher(std::string msg)\n    {\n        ROS_INFO_STREAM(\"Creating CbStringPublisher behavior with stored message: \" << msg);\n        msg_ = msg;\n    }\n\n    virtual void onEntry()\n    {\n        this->requiresClient(publisherClient_);\n    }\n\n    virtual void onExit() override\n    {\n        std_msgs::String rosmsg;\n        rosmsg.data = msg_;\n        publisherClient_->publish(rosmsg);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_temperature_sensor/cl_temperature_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/Temperature.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_temperature_sensor\n{\nclass ClTemperatureSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::Temperature>\n{\npublic:\n    ClTemperatureSensor()\n    {\n    }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h",
    "content": "\n#pragma once\n#include <sensor_msgs/Temperature.h>\n#include <sm_dance_bot_2/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_temperature_sensor\n{\nstruct EvCustomTemperatureAlert : sc::event<EvCustomTemperatureAlert>\n{\n};\n\n//--------------------------------------------------------------------------------------\nclass CbConditionTemperatureSensor : public cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClTemperatureSensor>\n{\npublic:\n  CbConditionTemperatureSensor()\n  {\n  }\n  virtual void onMessageCallback(const sensor_msgs::Temperature &msg) override\n  {\n    if (msg.temperature > 40)\n    {\n      auto ev = new EvCustomTemperatureAlert();\n      this->postEvent(ev);\n    }\n  }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_led.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot_2/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrLED : public smacc::Orthogonal<OrLED>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_led::ClLED>(\"led_action_server\");\n        actionclient->initialize();\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_navigation.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace sm_dance_bot_2\n{\nusing namespace cl_move_base_z;\n\nclass OrNavigation : public smacc::Orthogonal<OrNavigation>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto movebaseClient = this->createClient<ClMoveBaseZ>();\n        movebaseClient->initialize();\n\n        // create planner switcher\n        movebaseClient->createComponent<PlannerSwitcher>();\n\n        movebaseClient->createComponent<cl_move_base_z::Pose>();\n\n        // create odom tracker\n        movebaseClient->createComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n\n        // create waypoints navigator component\n        auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();\n        loadWaypointsFromYaml(waypointsNavigator);\n\n        // change this to skip some points of the yaml file, default = 0\n        waypointsNavigator->currentWaypoint_ = 0;\n    }\n\n    void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)\n    {\n        // if it is the first time and the waypoints navigator is not configured\n\n        std::string planfilepath;\n        ros::NodeHandle nh(\"~\");\n        if (nh.getParam(\"/sm_dance_bot_2/waypoints_plan\", planfilepath))\n        {\n            waypointsNavigator->loadWayPointsFromFile(planfilepath);\n        }\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_obstacle_perception.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_2/clients/cl_lidar/cl_lidar.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrObstaclePerception : public smacc::Orthogonal<OrObstaclePerception>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto lidarClient = this->createClient<ClLidarSensor>();\n\n        lidarClient->topicName = \"/front/scan\";\n        //lidarClient->queueSize = \"/front/scan\";\n        lidarClient->timeout_ = ros::Duration(10);\n\n        lidarClient->initialize();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_service3.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot_2/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrService3 : public smacc::Orthogonal<OrService3>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto serviceClient = this->createClient<ClService3>();\n        serviceClient->serviceName_ = \"/service_node3\";\n        serviceClient->initialize();\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_2/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_dance_bot_2\n{\nclass OrStringPublisher : public smacc::Orthogonal<OrStringPublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        this->createClient<ClStringPublisher>(\"/string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_temperature_sensor.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sensor_msgs/Temperature.h>\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <sm_dance_bot_2/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrTemperatureSensor : public smacc::Orthogonal<OrTemperatureSensor>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clTemperatureSensor = this->createClient<ClTemperatureSensor>();\n\n        clTemperatureSensor->topicName = \"/temperature\";\n        //ClTemperatureSensor->queueSize = \"/front/scan\";\n        clTemperatureSensor->timeout_ = ros::Duration(10);\n\n        clTemperatureSensor->initialize();\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_timer.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot_2\n{\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto publisherClient_ = this->createClient<cl_ros_publisher::ClRosPublisher>();\n        publisherClient_->configure<std_msgs::String>(\"/updatable_string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/sm_dance_bot_2.h",
    "content": "#include <smacc/smacc.h>\n\n#include <sensor_msgs/LaserScan.h>\n\n// CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/client_behaviors.h>\n\nusing namespace cl_move_base_z;\n\n#include <sm_dance_bot_2/clients/cl_led/client_behaviors/cb_led_on.h>\n#include <sm_dance_bot_2/clients/cl_led/client_behaviors/cb_led_off.h>\n\n#include <sm_dance_bot_2/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h>\n#include <sm_dance_bot_2/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h>\n\n#include <sm_dance_bot_2/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h>\n#include <sm_dance_bot_2/clients/cl_service3/client_behaviors/cb_service3.h>\n\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nusing namespace sm_dance_bot_2::cl_lidar;\nusing namespace sm_dance_bot_2::cl_service3;\nusing namespace sm_dance_bot_2::cl_string_publisher;\nusing namespace sm_dance_bot_2::cl_temperature_sensor;\nusing namespace sm_dance_bot_2::cl_led;\n//using namespace sm_dance_bot_2::cl_move_base_z;\n//using namespace sm_dance_bot_2::cl_updatable_publisher;\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n#include <sr_event_countdown/sr_event_countdown.h>\n#include <sr_conditional/sr_conditional.h>\n\nusing namespace smacc::state_reactors;\n\n// ORTHOGONALS\n#include <sm_dance_bot_2/orthogonals/or_navigation.h>\n#include <sm_dance_bot_2/orthogonals/or_obstacle_perception.h>\n#include <sm_dance_bot_2/orthogonals/or_led.h>\n#include <sm_dance_bot_2/orthogonals/or_temperature_sensor.h>\n#include <sm_dance_bot_2/orthogonals/or_string_publisher.h>\n#include <sm_dance_bot_2/orthogonals/or_service3.h>\n#include <sm_dance_bot_2/orthogonals/or_timer.h>\n#include <sm_dance_bot_2/orthogonals/or_updatable_publisher.h>\n\nnamespace sm_dance_bot_2\n{\n//STATE FORWARD DECLARATIONS\nclass StAcquireSensors;\nclass StEventCountDown;\nclass StRotateDegrees4;\nclass StNavigateForward1;\nclass StNavigateToWaypoint1;\nclass StNavigateToWaypointsX;\nclass StRotateDegrees2;\nclass StRotateDegrees1;\nclass StNavigateReverse2;\nclass StRotateDegrees3;\nclass StNavigateReverse1;\nclass StNavigateForward2;\nclass StRotateDegrees5;\nclass StNavigateReverse3;\nclass StRotateDegrees6;\nclass StNavigateReverse3;\n\n//SUPERSTATE FORWARD DECLARATIONS\n\n//MODE STATES FORWARD DECLARATIONS\nclass MsDanceBotRunMode;\nclass MsDanceBotRecoveryMode;\n\nnamespace SS1\n{\nclass SsRadialPattern1;\n}\n\nnamespace SS2\n{\nclass SsRadialPattern2;\n}\n\nnamespace SS3\n{\nclass SsRadialPattern3;\n}\n\nnamespace SS4\n{\nclass SsFPattern1;\n}\n\nnamespace SS5\n{\nclass SsSPattern1;\n}\n\n// custom smd_dance_bot event\nstruct EvGlobalError : sc::event<EvGlobalError>\n{\n};\n\n} // namespace sm_dance_bot_2\n\nusing namespace sm_dance_bot_2;\nusing namespace cl_ros_timer;\nusing namespace smacc;\n\n\nnamespace sm_dance_bot_2\n{\n/// \\brief Advanced example of state machine with smacc that shows multiple techniques\n///  for the development of state machines\nstruct SmDanceBot2\n    : public smacc::SmaccStateMachineBase<SmDanceBot2, MsDanceBotRunMode>\n{\n    int counter_1;\n    bool rt_ready_flag;\n\n    typedef mpl::bool_<false> shallow_history;\n    typedef mpl::bool_<false> deep_history;\n    typedef mpl::bool_<false> inherited_deep_history;\n\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->setGlobalSMData(\"counter_1\", counter_1);\n        this->setGlobalSMData(\"rt_ready_flag\", rt_ready_flag);\n\n        this->createOrthogonal<OrNavigation>();\n        this->createOrthogonal<OrObstaclePerception>();\n        this->createOrthogonal<OrLED>();\n        this->createOrthogonal<OrTemperatureSensor>();\n        this->createOrthogonal<OrStringPublisher>();\n        this->createOrthogonal<OrService3>();\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n    }\n};\n\n} // namespace sm_dance_bot_2\n\n//MODE STATES\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/ms_dance_bot_run_mode.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_recovery_mode/ms_dance_bot_recovery_mode.h>\n\n//SUPERSTATES\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_2.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_3.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/ss_f_pattern_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/ss_s_pattern_1.h>\n\n//STATES\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_acquire_sensors.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_event_count_down.h>\n\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_to_waypoints_x.h>\n\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_6.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_5.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_forward_2.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_4.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_forward_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_to_waypoint_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_2.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_2.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_3.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_1.h>\n#include <sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_3.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_recovery_mode/ms_dance_bot_recovery_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nclass MsDanceBotRecoveryMode : public smacc::SmaccState<MsDanceBotRecoveryMode, SmDanceBot2>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, sc::deep_history<MsDanceBotRunMode::LastDeepState>>\n\n   >reactions;\n   // typedef Transition<EvGlobalError, MsDanceBotRunMode> reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/ss_f_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_2 {\nnamespace f_pattern_states {\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\n// FORWARD DECLARATIONS OF INNER STATES\ntemplate <typename SS> class StiFPatternRotate1;\ntemplate <typename SS> class StiFPatternForward1;\ntemplate <typename SS> class StiFPatternReturn1;\ntemplate <typename SS> class StiFPatternRotate2;\ntemplate <typename SS> class StiFPatternForward2;\ntemplate <typename SS> class StiFPatternStartLoop;\n} // namespace f_pattern_states\n} // namespace sm_dance_bot_2\nnamespace sm_dance_bot_2 {\nnamespace SS4 {\nusing namespace f_pattern_states;\n\n// STATE DECLARATION\nstruct SsFPattern1 : smacc::SmaccState<SsFPattern1, MsDanceBotRunMode, StiFPatternStartLoop<SsFPattern1>>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiFPatternStartLoop<SsFPattern1>>, StNavigateForward2, ENDLOOP> //,\n\n    >reactions;\n\n// STATE VARIABLES\n    // superstate parameters\n    static constexpr float ray_lenght_meters() { return 3.25; }\n    static constexpr float pitch_lenght_meters() { return 0.75; }\n    static constexpr int total_iterations() { return 10; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n\n    // superstate state variables\n    int iteration_count;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n        iteration_count = 0;\n    }\n}; // namespace SS4\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\n\n} // namespace SS4\n} // namespace sm_dance_bot_2\n\n#include \"sti_fpattern_rotate_1.h\"\n#include \"sti_fpattern_forward_1.h\"\n#include \"sti_fpattern_return_1.h\"\n#include \"sti_fpattern_rotate_2.h\"\n#include \"sti_fpattern_forward_2.h\"\n#include \"sti_fpattern_loop_start.h\"\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_forward_1.h",
    "content": "\nnamespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward1 : public smacc::SmaccState<StiFPatternForward1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternReturn1<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n     TSti::template configure_orthogonal<OrNavigation, CbNavigateForward>(SS::ray_lenght_meters());\n     TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n    ROS_INFO(\"[SsrFpattern] Fpattern rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_forward_2.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward2 : smacc::SmaccState<StiFPatternForward2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward2<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternStartLoop<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n    ROS_INFO(\"[SsrFpattern] Fpattern rotate: SS current iteration: %d/%d\", superstate.iteration_count, superstate.total_iterations());\n\n    TSti::template configure<OrNavigation, CbNavigateForward>(SS::pitch_lenght_meters());\n    TSti::template configure<OrLED, CbLEDOff>();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_loop_start.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternStartLoop : smacc::SmaccState<StiFPatternStartLoop<SS>, SS>\n{\n  typedef SmaccState<StiFPatternStartLoop<SS>, SS> TSti;\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiFPatternStartLoop<SS>>, StiFPatternRotate1<SS>, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    auto &superstate = TSti::template context<SS>();\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    TSti::checkWhileLoopConditionAndThrowEvent(&StiFPatternStartLoop<SS>::loopCondition);\n  }\n};\n} // namespace f_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_return_1.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternReturn1 : smacc::SmaccState<StiFPatternReturn1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternReturn1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiFPatternRotate2<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    TSti::template configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_rotate_1.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate1 : smacc::SmaccState<StiFPatternRotate1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternForward1<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    float angle = 0;\n    double offset = 7; // for a better behaving\n\n    if (SS::direction() == TDirection::LEFT)\n      angle = 90 + offset;\n    else\n      angle = -90 - offset;\n\n     //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n     TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(angle); // absolute aligned to the y-axis\n     TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/f_pattern_states/sti_fpattern_rotate_2.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate2 : smacc::SmaccState<StiFPatternRotate2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate2<SS>, SS> TSti;\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternForward2<SS>>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    double offset = 7; // for a better behaving\n    float angle = 0;\n    if (SS::direction() == TDirection::LEFT)\n      angle = -90 - offset;\n    else\n      angle = 90 + offset;\n\n    //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n    TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(0 + offset); // absolute horizontal\n    TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace f_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/ms_dance_bot_run_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nclass MsDanceBotRunMode : public smacc::SmaccState<MsDanceBotRunMode, SmDanceBot2, StAcquireSensors>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n   >reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_2 {\nnamespace SS1 {\nnamespace sm_dance_bot_2 {\nnamespace radial_motion_states {\n\n//FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\nusing namespace sm_dance_bot_2::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern1 : smacc::SmaccState<SsRadialPattern1, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n        using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateReverse1, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    int iteration_count = 0;\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 5; }\n};\n\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern1;\n#include \"sti_radial_end_point.h\"\n#include \"sti_radial_return.h\"\n#include \"sti_radial_rotate.h\"\n#include \"sti_radial_loop_start.h\"\n} // namespace SS1\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_2 {\nnamespace SS2 {\nnamespace sm_dance_bot_2 {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATIONS OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\nusing namespace sm_dance_bot_2::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern2 : smacc::SmaccState<SsRadialPattern2, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n        using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateReverse1, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    int iteration_count = 0;\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 5; }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern2;\n#include \"sti_radial_end_point.h\"\n#include \"sti_radial_return.h\"\n#include \"sti_radial_rotate.h\"\n#include \"sti_radial_loop_start.h\"\n} // namespace SS2\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/ss_radial_pattern_3.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_2 {\nnamespace SS3 {\nnamespace sm_dance_bot_2 {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\nusing namespace sm_dance_bot_2::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern3 : smacc::SmaccState<SsRadialPattern3, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StRotateDegrees4, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    int iteration_count;\n\n    static constexpr int total_iterations() { return 16; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 4; }\n\n    void runtimeConfigure()\n    {\n        iteration_count = 0;\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern3;\n#include \"sti_radial_end_point.h\"\n#include \"sti_radial_return.h\"\n#include \"sti_radial_rotate.h\"\n#include \"sti_radial_loop_start.h\"\n} // namespace SS3\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/sti_radial_end_point.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialEndPoint : smacc::SmaccState<StiRadialEndPoint, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiRadialReturn, SUCCESS>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiRadialRotate, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    ROS_INFO(\"ssr radial end point, distance in meters: %lf\", SS::ray_length_meters());\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::ray_length_meters());\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/sti_radial_loop_start.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialLoopStart : smacc::SmaccState<StiRadialLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiRadialLoopStart>, StiRadialRotate, CONTINUELOOP>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiRadialLoopStart::loopWhileCondition);\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/sti_radial_return.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialReturn : smacc::SmaccState<StiRadialReturn, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiRadialLoopStart, SUCCESS>,\n  Transition<EvCbFailure<CbUndoPathBackwards, OrNavigation>, StiRadialEndPoint, ABORT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/radial_motion_states/sti_radial_rotate.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialRotate : smacc::SmaccState<StiRadialRotate, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiRadialEndPoint, SUCCESS>,\n  Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiRadialLoopStart, ABORT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto cbAbsRotate = this->getOrthogonal<OrNavigation>()\n                           ->getClientBehavior<CbAbsoluteRotate>();\n\n    auto &superstate = this->context<SS>();\n    cbAbsRotate->absoluteGoalAngleDegree = superstate.iteration_count * SS::ray_angle_increment_degree();\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/ss_s_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_2 {\nnamespace SS5 {\nnamespace sm_dance_bot_2 {\nnamespace s_pattern_states {\n\n// FORWARD DECLARATIONS OF INNER STATES\nclass StiSPatternRotate1;\nclass StiSPatternForward1;\nclass StiSPatternRotate2;\nclass StiSPatternForward2;\nclass StiSPatternRotate3;\nclass StiSPatternForward3;\nclass StiSPatternRotate4;\nclass StiSPatternForward4;\nclass StiSPatternLoopStart;\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\nusing namespace sm_dance_bot_2::s_pattern_states;\n\n// STATE DECLARATION\nstruct SsSPattern1 : smacc::SmaccState<SsSPattern1, MsDanceBotRunMode, StiSPatternLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiSPatternLoopStart>, StRotateDegrees6, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    static constexpr float pitch1_lenght_meters() { return 0.75; }\n    static constexpr float pitch2_lenght_meters() { return 1.45; }\n    static constexpr int total_iterations() { return 11; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n\n    int iteration_count;\n\n    void runtimeConfigure()\n    {\n        this->iteration_count = 0;\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsSPattern1;\n#include \"sti_spattern_rotate_1.h\"\n#include \"sti_spattern_forward_1.h\"\n#include \"sti_spattern_rotate_2.h\"\n#include \"sti_spattern_forward_2.h\"\n#include \"sti_spattern_rotate_3.h\"\n#include \"sti_spattern_forward_3.h\"\n#include \"sti_spattern_rotate_4.h\"\n#include \"sti_spattern_forward_4.h\"\n#include \"sti_spattern_loop_start.h\"\n} // namespace SS5\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_forward_1.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward1 : public smacc::SmaccState<StiSPatternForward1, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate2>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate1>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_forward_2.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward2 : public smacc::SmaccState<StiSPatternForward2, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate3>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate2>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n\n    this->configure<OrNavigation, CbNavigateForward>(SS::pitch2_lenght_meters());\n    this->configure<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_forward_3.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward3 : public smacc::SmaccState<StiSPatternForward3, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate4>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate3>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_forward_4.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward4 : public smacc::SmaccState<StiSPatternForward4, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternLoopStart>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate4>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n\n    this->configure<OrNavigation, CbNavigateForward>(SS::pitch2_lenght_meters());\n    this->configure<OrLED, CbLEDOn>();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_loop_start.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternLoopStart : smacc::SmaccState<StiSPatternLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopContinue<StiSPatternLoopStart>, StiSPatternRotate1, CONTINUELOOP>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    auto &superstate = this->context<SS>();\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    checkWhileLoopConditionAndThrowEvent(&StiSPatternLoopStart::loopCondition);\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_rotate_1.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate1 : smacc::SmaccState<StiSPatternRotate1, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward1>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternLoopStart>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n\n        // float angle = 0;\n        // if (superstate.direction() == TDirection::LEFT)\n        //     angle = 90;\n        // else\n        //     angle = -90;\n        //this->configure<OrNavigation, CbRotate>(angle);\n\n        float offset = 7;\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            // - offset because we are looking to the north and we have to turn clockwise\n            this->configure<OrNavigation, CbAbsoluteRotate>(0 - offset);\n        }\n        else\n        {\n            // - offset because we are looking to the south and we have to turn counter-clockwise\n            this->configure<OrNavigation, CbAbsoluteRotate>(180 + offset);\n        }\n\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_rotate_2.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate2 : smacc::SmaccState<StiSPatternRotate2, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward2>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward1>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        float offset = 7;\n        float angle = 0;\n        if (SS::direction() == TDirection::LEFT)\n            angle = 90 + offset ;\n        else\n            angle = -90 - offset;\n\n        configure_orthogonal<OrNavigation, CbRotate>(angle);\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_rotate_3.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate3 : smacc::SmaccState<StiSPatternRotate3, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward3>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward2>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 7;\n        float angle = 0;\n        if (superstate.direction() == TDirection::LEFT)\n            angle = -90 - offset;\n        else\n            angle = +90 + offset;\n\n        this->configure<OrNavigation, CbRotate>(angle);\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/s_pattern_states/sti_spattern_rotate_4.h",
    "content": "namespace sm_dance_bot_2\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate4 : smacc::SmaccState<StiSPatternRotate4, SS>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCbSuccess<CbRotate, OrNavigation>, StiSPatternForward4>,\n    Transition<EvCbFailure<CbRotate, OrNavigation>, StiSPatternForward3>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[SsrSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 7;\n        float angle = 0;\n        if (superstate.direction() == TDirection::LEFT)\n            angle = -90 - offset;\n        else\n            angle = 90 + offset;\n\n        this->configure<OrNavigation, CbRotate>(angle);\n        this->configure<OrLED, CbLEDOff>();\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_acquire_sensors.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n\nusing namespace smacc::default_events;\n\n// STATE DECLARATION\nstruct StAcquireSensors : smacc::SmaccState<StAcquireSensors, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n   // DECLARE CUSTOM OBJECT TAGS\n   struct ON_SENSORS_AVAILABLE : SUCCESS\n   {\n   };\n   struct SrAcquireSensors;\n\n   // TRANSITION TABLE\n   typedef mpl::list<\n\n       Transition<EvAllGo<SrAllEventsGo, SrAcquireSensors>, StEventCountDown, ON_SENSORS_AVAILABLE>,\n       Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n       >\n       reactions;\n\n   // STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n      configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n      configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n      configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n      configure_orthogonal<OrUpdatablePublisher, cl_ros_publisher::CbDefaultPublishLoop>();\n\n      // Create State Reactor\n      // auto srAllSensorsReady = static_createStateReactor<SrAllEventsGo>();\n\n      auto srAllSensorsReady = static_createStateReactor<SrAllEventsGo,\n                                                   EvAllGo<SrAllEventsGo, SrAcquireSensors>,\n                                                   mpl::list<\n                                                               EvTopicMessage<CbLidarSensor, OrObstaclePerception>,\n                                                               EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>\n                                                            >>();\n\n\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbLidarSensor, OrObstaclePerception>>();\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>>();\n\n      //srAllSensorsReady->setOutputEvent<smacc::state_reactors::EvAllGo<SrAllEventsGo, SrAcquireSensors>>();\n   }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_event_count_down.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StEventCountDown : smacc::SmaccState<StEventCountDown, MsDanceBotRunMode>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCountdownEnd<SrEventCountdown>, StNavigateToWaypointsX>,\n    Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //   configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n        //   configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n        //   configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n        //   configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n\n        // Create State Reactor\n        // auto srCountdown = static_createStateReactor<SrEventCountdown>(5);\n        // srCountdown->addInputEvent<EvTimer<ClRosTimer, OrTimer>>();\n        // srCountdown->setOutputEvent<EvCountdownEnd<SrEventCountdown>>();\n\n        auto srCountdown = static_createStateReactor<SrEventCountdown,\n                                                    EvCountdownEnd<SrEventCountdown>,\n                                                    mpl::list<\n                                                            EvTimer<ClRosTimer, OrTimer>\n                                                            >>(5);\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_forward_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateForward1 : smacc::SmaccState<StNavigateForward1, MsDanceBotRunMode>\n{\nusing SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StRotateDegrees2>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StNavigateToWaypointsX, ABORT>,\n  Transition<EvActionPreempted<CbNavigateForward, OrNavigation>, StNavigateToWaypointsX, PREEMPT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(1);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n\n  void runtimeConfigure()\n  {\n    ClMoveBaseZ *move_base_action_client;\n    this->requiresClient(move_base_action_client);\n\n    // we careful with the lifetime of the callbac, us a scoped connection if is not forever\n    move_base_action_client->onSucceeded(&StNavigateForward1::onActionClientSucceeded, this);\n  }\n\n  void onActionClientSucceeded(ClMoveBaseZ::ResultConstPtr &msg)\n  {\n    ROS_INFO_STREAM(\" [Callback SmaccSignal] Success Detected from StAquireSensors (connected to client signal), result data: \" << *msg);\n  }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_forward_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateForward2 : smacc::SmaccState<StNavigateForward2, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StRotateDegrees5>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(1);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateReverse1 : smacc::SmaccState<StNavigateReverse1, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StRotateDegrees3>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateReverse2 : smacc::SmaccState<StNavigateReverse2, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_reverse_3.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateReverse3 : smacc::SmaccState<StNavigateReverse3, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvCbSuccess<CbNavigateBackwards, OrNavigation>, StNavigateToWaypoint1>,\n   Transition<EvCbFailure<CbNavigateBackwards, OrNavigation>, StNavigateToWaypointsX>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrNavigation, CbNavigateBackwards>(2);\n      configure_orthogonal<OrLED, CbLEDOff>();\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n   }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_to_waypoint_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateToWaypoint1 : smacc::SmaccState<StNavigateToWaypoint1, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateGlobalPosition, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbNavigateGlobalPosition, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateGlobalPosition>(0, 0, 0);\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"All Done!\");\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_navigate_to_waypoints_x.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StNavigateToWaypointsX : smacc::SmaccState<StNavigateToWaypointsX, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// CUSTOM TRANSITION TAGS\n  struct TRANSITION_1 : SUCCESS{};\n  struct TRANSITION_2 : SUCCESS{};\n  struct TRANSITION_3 : SUCCESS{};\n  struct TRANSITION_4 : SUCCESS{};\n  struct TRANSITION_5 : SUCCESS{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvWaypoint0<ClMoveBaseZ, OrNavigation>, SS1::SsRadialPattern1, TRANSITION_1>,\n  Transition<EvWaypoint1<ClMoveBaseZ, OrNavigation>, SS2::SsRadialPattern2, TRANSITION_2>,\n  Transition<EvWaypoint2<ClMoveBaseZ, OrNavigation>, SS3::SsRadialPattern3, TRANSITION_3>,\n  Transition<EvWaypoint3<ClMoveBaseZ, OrNavigation>, SS4::SsFPattern1, TRANSITION_4>,\n  Transition<EvWaypoint4<ClMoveBaseZ, OrNavigation>, SS5::SsSPattern1, TRANSITION_5>,\n  Transition<EvCbFailure<ClMoveBaseZ, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    configure_orthogonal<OrNavigation, CbNavigateNextWaypoint>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_1.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees1 : smacc::SmaccState<StRotateDegrees1, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateForward1>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ 90);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_2.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees2 : smacc::SmaccState<StRotateDegrees2, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -90);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_3.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees3 : smacc::SmaccState<StRotateDegrees3, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ 180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_4.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees4 : smacc::SmaccState<StRotateDegrees4, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateReverse2>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_5.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees5 : smacc::SmaccState<StRotateDegrees5, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateToWaypointsX>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/include/sm_dance_bot_2/states/ms_dance_bot_run_mode/st_rotate_degrees_6.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_2\n{\n// STATE DECLARATION\nstruct StRotateDegrees6 : smacc::SmaccState<StRotateDegrees6, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbRotate, OrNavigation>, StNavigateReverse3>,\n  Transition<EvCbFailure<CbRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbRotate>(/*30*/ -180);\n    configure_orthogonal<OrLED, CbLEDOff>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/launch/readme.md",
    "content": "# Dance Bot State Machine\n## Setup and requirements\n\nMake sure that you have installed all the dependencies. For example this demo depends on rigeback robot simulation.\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nAfter that you have to build the smacc ros workspace using catkin_make.\n\n```\ncatkin_make\n```\n\nAfter you build, remember to source the proper devel folder.\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\n## Default demo launching\nBelow is the default launch command to launch this demo:\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch\n```\n\n## Lightweight demo launching\n\nWe use this launch command to start the process hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n```\nroslaunch sm_dance_bot sm_dance_bot.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/launch/ridgeback_simulation.launch",
    "content": "<launch>\n    <arg name=\"show_gz_client\" default=\"true\"/>\n\n    <include file=\"$(find ridgeback_gazebo)/launch/ridgeback_world.launch\">\n        <arg name=\"gui\" value=\"$(arg show_gz_client)\"/>\n    </include>\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"true\" name=\"move_base\" launch-prefix=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e \">\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/local_costmap_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/local_costmap_params.yaml\" command=\"load\" />\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/base_local_planner_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/base_local_planner_params.yaml\" command=\"load\" />\n\n        <rosparam file=\"$(find ridgeback_navigation)/params/move_base_params.yaml\" command=\"load\" />\n\n        <param name=\"base_global_planner\" type=\"string\" value=\"navfn/NavfnROS\" />\n        <param name=\"base_local_planner\" value=\"base_local_planner/TrajectoryPlannerROS\"/>\n\n        <remap from=\"odom\" to=\"odometry/filtered\" />\n    </node>\n\n    <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find ridgeback_navigation)/maps/ridgeback_race.yaml\" output=\"screen\"/>\n    <!--- Run AMCL -->\n    <include file=\"$(find ridgeback_navigation)/launch/include/amcl.launch\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/launch/sm_dance_bot_2.launch",
    "content": "<launch>\n\n    <!--========= LAUNCH FILE ARGUMENTS ======================================================-->\n    <!-- defines the xterm parameters for the clients, set to empty to skip using xterm window-->\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <!-- defines the xterm parameters for the state machine, set to empty to skip using xterm window-->\n    <arg name=\"sm_xterm\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e\" />\n\n    <!-- if true, gazebo client is shown -->\n    <arg name=\"show_gz_client\" default=\"true\" />\n\n    <!-- if true, smacc_viewer is shown -->\n    <arg name=\"show_smacc_viewer\" default=\"true\" />\n\n    <!-- if true, rviz is shown -->\n    <arg name=\"show_rviz\" default=\"true\" />\n\n    <!-- It does not start the sm node in order to start it from your standalone process with debugger-->\n    <arg name=\"debug\" default=\"false\" />\n\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_dance_bot_2)/config/rosconsole.config\" />\n\n    <!--================================================================================-->\n    <!-- load the navigation environment simulated in gazebo-->\n    <include file=\"$(find sm_dance_bot_2)/launch/ridgeback_simulation.launch\">\n        <arg name=\"show_gz_client\" value=\"$(arg show_gz_client)\" />\n    </include>\n\n    <!--  setup smacc planners configuration  -->\n    <group ns=\"move_base\">\n        <!-- backward local planner -->\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/backward_local_planner.yaml\" command=\"load\" />\n        <!-- forward local planner -->\n        <rosparam file=\"$(find sm_dance_bot_2)/config/move_base_client/forward_local_planner.yaml\" command=\"load\" />\n    </group>\n\n    <!-- load state machine parameters -->\n    <rosparam command=\"load\" file=\"$(find sm_dance_bot_2)/config/sm_dance_bot_2_config.yaml\" />\n\n    <group ns=\"sm_dance_bot_2\">\n        <!-- set run mode -->\n        <param name=\"run_mode\" value=\"debug\" />\n        <!-- load flight plan -->\n        <param name=\"waypoints_plan\" value=\"$(find sm_dance_bot_2)/config/move_base_client/waypoints_plan.yaml\" />\n    </group>\n\n    <!-- state machine node -->\n    <node pkg=\"sm_dance_bot_2\" type=\"sm_dance_bot_2\" name=\"sm_dance_bot_2\" launch-prefix=\"$(arg sm_xterm)\" unless=\"$(arg debug)\">\n        <remap from=\"/odom\" to=\"/odometry/filtered\" />\n        <remap from=\"/sm_dance_bot_2/odom_tracker/odom_tracker_path\" to=\"/odom_tracker_path\"/>\n        <remap from=\"/sm_dance_bot_2/odom_tracker/odom_tracker_stacked_path\" to=\"/odom_tracker_path_stacked\"/>\n    </node>\n\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find sm_dance_bot_2)/config/navigation.rviz\" if=\"$(arg show_rviz)\">\n        <remap from=\"/remap_smacc_status\" to=\"/SmDanceBot/smacc/status\" />\n    </node>\n\n    <node pkg=\"sm_dance_bot_2\" type=\"led_action_server_node\" name=\"led_action_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot_2\" type=\"temperature_sensor_node\" name=\"temperature_sensor_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot_2\" type=\"service_node_3.py\" name=\"service_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <!-- <node pkg=\"smacc_viewer\" type=\"smacc_viewer_node.py\" name=\"smacc_viewer\" if=\"$(arg show_smacc_viewer)\"/> -->\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_dance_bot_2</name>\n    <version>1.4.16</version>\n  <description>The dance_bot package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag -->\n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>BSDv3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/dance_bot</url> -->\n\n\n  <!-- Author tags are optional, multiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintainers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->\n  <!--   <depend>roscpp</depend> -->\n  <!--   Note that this is equivalent to the following: -->\n  <!--   <build_depend>roscpp</build_depend> -->\n  <!--   <exec_depend>roscpp</exec_depend> -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use build_export_depend for packages you need in order to build against this package: -->\n  <!--   <build_export_depend>message_generation</build_export_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use exec_depend for packages you need at runtime: -->\n  <!--   <exec_depend>message_runtime</exec_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <!-- Use doc_depend for packages you need only for building documentation: -->\n  <!--   <doc_depend>doxygen</doc_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>actionlib</depend>\n  <depend>actionlib_msgs</depend>\n  <depend>move_base_z_client_plugin</depend>\n  <depend>xterm</depend>\n\n\n\n\n  <depend>ros_publisher_client</depend>\n  <depend>multirole_sensor_client</depend>\n\n  <depend>sr_all_events_go</depend>\n  <depend>sr_event_countdown</depend>\n  <depend>sr_conditional</depend>\n  <depend>ros_timer_client</depend>\n\n  <depend>ridgeback_gazebo</depend>\n  <depend>ridgeback_navigation</depend>\n\n  <depend>tf</depend>¡\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/action_server_node_3/src/action_server_node_3.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/led_action_server/action/LEDControl.action",
    "content": "uint8 command\n\n# Possible command values\nuint8 CMD_ON = 0\nuint8 CMD_OFF = 1\n---\nuint8 state\n\n# Possible feeedback values (tool states)\nuint8 STATE_UNKNOWN = 0\nuint8 STATE_RUNNING = 1\nuint8 STATE_IDLE = 2\n---\nuint8 result\n\n# Possible result values\nuint8 RESULT_SUCCESS = 0\nuint8 RESULT_ERROR = 1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/led_action_server/src/led_action_server_node.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <actionlib/server/simple_action_server.h>\n#include <std_msgs/UInt8.h>\n#include <functional>\n#include <dynamic_reconfigure/DoubleParameter.h>\n#include <dynamic_reconfigure/Reconfigure.h>\n#include <dynamic_reconfigure/Config.h>\n#include <sm_dance_bot_2/LEDControlAction.h>\n#include <sm_dance_bot_2/LEDControlActionResult.h>\n#include <sm_dance_bot_2/LEDControlResult.h>\n#include <memory>\n#include <visualization_msgs/MarkerArray.h>\n\ntypedef actionlib::SimpleActionServer<sm_dance_bot_2::LEDControlAction> Server;\n\n// This class describes a preemptable-on/off tool action server to be used from smacc\n// shows in rviz a sphere whose color describe the current state (unknown, running, idle)\nclass LEDActionServer\n{\npublic:\n  std::shared_ptr<Server> as_ ;\n\n  ros::Publisher stateMarkerPublisher_;\n\n  sm_dance_bot_2::LEDControlGoal cmd;\n\n  uint8_t currentState_;\n\n/**\n******************************************************************************************************************\n* constructor()\n******************************************************************************************************************\n*/\n  LEDActionServer()\n  {\n    currentState_ =  sm_dance_bot_2::LEDControlResult::STATE_UNKNOWN;\n  }\n\n/**\n******************************************************************************************************************\n* publishFeedback()\n******************************************************************************************************************\n*/\nvoid publishFeedback()  // Note: \"Action\" is not appended to DoDishes here\n{\n    sm_dance_bot_2::LEDControlFeedback feedback_msg;\n\n    as_->publishFeedback(feedback_msg);\n}\n\n/**\n******************************************************************************************************************\n* execute()\n******************************************************************************************************************\n*/\nvoid execute(const sm_dance_bot_2::LEDControlGoalConstPtr& goal)  // Note: \"Action\" is not appended to DoDishes here\n{\n  ROS_INFO_STREAM(\"Tool action server request: \"<< *goal);\n  cmd = *goal;\n\n  if(goal->command == sm_dance_bot_2::LEDControlGoal::CMD_ON)\n  {\n    currentState_ =  sm_dance_bot_2::LEDControlResult::STATE_RUNNING;\n  }\n  else  if (goal->command == sm_dance_bot_2::LEDControlGoal::CMD_OFF)\n  {\n    currentState_ =  sm_dance_bot_2::LEDControlResult::STATE_IDLE;\n  }\n\n  // 10Hz internal loop\n  ros::Rate rate(20);\n\n  while(ros::ok())\n  {\n    if(as_->isPreemptRequested())\n    {\n       // a new request is being executed, we will stop this one\n       ROS_WARN(\"LEDActionServer request preempted. Forgetting older request.\");\n       as_->setPreempted();\n       return;\n    }\n\n    publishFeedback();\n    publishStateMarker();\n    rate.sleep();\n  }\n\n   // never reach succeeded because were are interested in keeping the feedback alive\n   as_->setSucceeded();\n}\n\n/**\n******************************************************************************************************************\n* run()\n******************************************************************************************************************\n*/\nvoid run()\n{\n  ros::NodeHandle n;\n  ROS_INFO(\"Creating tool action server\");\n\n  as_ = std::make_shared<Server>(n, \"led_action_server\", boost::bind(&LEDActionServer::execute, this,  _1), false);\n  ROS_INFO(\"Starting Tool Action Server\");\n\n  stateMarkerPublisher_ = n.advertise<visualization_msgs::MarkerArray>(\"tool_markers\", 1);\n\n  as_->start();\n\n  ros::spin();\n}\n\n/**\n******************************************************************************************************************\n* publishStateMarker()\n******************************************************************************************************************\n*/\nvoid publishStateMarker()\n{\n    visualization_msgs::Marker marker;\n    marker.header.frame_id = \"base_link\";\n    marker.header.stamp = ros::Time::now ();\n\n    marker.ns = \"tool_namespace\";\n    marker.id = 0;\n    marker.type = visualization_msgs::Marker::SPHERE;\n    marker.action = visualization_msgs::Marker::ADD;\n\n    marker.scale.x = 0.2;\n    marker.scale.y = 0.2;\n    marker.scale.z = 0.2;\n\n    marker.color.a = 1;\n\n    if(currentState_ == sm_dance_bot_2::LEDControlResult::STATE_RUNNING)\n    {\n      // show green ball\n      marker.color.r = 0;\n      marker.color.g = 1;\n      marker.color.b = 0;\n    }\n    else if (currentState_ == sm_dance_bot_2::LEDControlResult::STATE_IDLE)\n    {\n      // show gray ball\n      marker.color.r = 0.7;\n      marker.color.g = 0.7;\n      marker.color.b = 0.7;\n    }\n    else\n    {\n      // show black ball\n      marker.color.r = 0;\n      marker.color.g = 0;\n      marker.color.b = 0;\n    }\n\n    marker.pose.orientation.w=1;\n    marker.pose.position.x=0;\n    marker.pose.position.y=0;\n    marker.pose.position.z=1;\n\n    visualization_msgs::MarkerArray ma;\n    ma.markers.push_back(marker);\n\n    stateMarkerPublisher_.publish(ma);\n}\n};\n\n/**\n******************************************************************************************************************\n* main()\n******************************************************************************************************************\n*/\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"led_action_server_node\");\n  LEDActionServer LEDActionServer;\n  LEDActionServer.run();\n\n  return 0;\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/lidar_node/src/lidar_node.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/service_node_3/__init__.py",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/service_node_3/src/service_node_3.py",
    "content": "#!/usr/bin/env python\n\n\nimport rospy\nimport std_srvs\n\nif __name__ == \"__main__\":\n\n    def set_bool_service(req):\n        rospy.loginfo(\"RECEIVING SET BOOL SERVICE REQUEST: value=\" + str(req.data))\n\n        response = std_srvs.srv.SetBoolResponse()\n        response.message = \"OK, value set\"\n        response.success = True\n        return response\n\n    rospy.init_node(\"service_node3\")\n    s = rospy.Service(\"service_node3\", std_srvs.srv.SetBool, set_bool_service)\n    rospy.spin()\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/servers/temperature_sensor_node/src/temperature_sensor_node.cpp",
    "content": "#include <ros/ros.h>\n#include <sensor_msgs/Temperature.h>\n\nint main(int argc, char** argv)\n{\n    ros::init(argc,argv, \"temperature_sensor_node\");\n\n    ros::NodeHandle nh;\n    auto pub = nh.advertise<sensor_msgs::Temperature>(\"/temperature\",1);\n\n    ros::Rate r(10);\n\n    while(ros::ok())\n    {\n        sensor_msgs::Temperature msg;\n        pub.publish(msg);\n\n        r.sleep();\n        ros::spinOnce();\n    }\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/src/clients/cl_led/cl_led.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <sm_dance_bot_2/clients/cl_led/cl_led.h>\n//#include <pluginlib/class_list_macros.h>\n\nnamespace sm_dance_bot_2\n{\nnamespace cl_led\n{\n\nClLED::ClLED(std::string actionServerName) : Base(actionServerName)\n{\n}\n\nstd::string ClLED::getName() const\n{\n    return \"TOOL ACTION CLIENT\";\n}\n\nClLED::~ClLED()\n{\n}\n} // namespace cl_led\n\n//PLUGINLIB_EXPORT_CLASS(cl_led::ClLED, smacc::ISmaccComponent)\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/src/sm_dance_bot_2.cpp",
    "content": "#include <sm_dance_bot_2/sm_dance_bot_2.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"dance_bot\");\n    ros::NodeHandle nh;\n\n    ros::Duration(5).sleep();\n    smacc::run<SmDanceBot2>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_2/urdf/empty.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_dance_bot_strikes_back\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco, brett2@robosoft-ai.com, robosoft-ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_dance_bot_strikes_back)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin multirole_sensor_client tf sr_all_events_go sr_event_countdown ros_timer_client sr_conditional ros_publisher_client actionlib actionlib_msgs angles)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\nadd_action_files(\n   DIRECTORY\n   servers/led_action_server/action/\n\n   FILES\n   LEDControl.action\n)\n\ngenerate_messages(\n   DEPENDENCIES\n   actionlib_msgs\n )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES sm_dance_bot_strikes_back\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}\n              src/sm_dance_bot_strikes_back.cpp\n              src/clients/cl_led/cl_led.cpp)\n\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n\n add_executable(temperature_sensor_node_smdbsb_${PROJECT_NAME} servers/temperature_sensor_node/src/temperature_sensor_node.cpp)\n  set_target_properties(temperature_sensor_node_smdbsb_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"temperature_sensor_node\")\n set_target_properties(temperature_sensor_node_smdbsb_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"temperature_sensor_node\")\n\n target_link_libraries(temperature_sensor_node_smdbsb_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\nadd_executable(led_action_server_node_smdbsb_${PROJECT_NAME} servers/led_action_server/src/led_action_server_node.cpp)\nset_target_properties(led_action_server_node_smdbsb_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"led_action_server_node\")\n\n target_link_libraries(\n   led_action_server_node_smdbsb_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n)\n\nadd_dependencies(led_action_server_node_smdbsb_${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp)\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\ninstall(PROGRAMS\n   servers/service_node_3/src/service_node_3.py\n   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS\n  ${PROJECT_NAME}\n   temperature_sensor_node_smdbsb_${PROJECT_NAME}\n   led_action_server_node_smdbsb_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\ninstall(DIRECTORY\n    launch/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\ninstall(DIRECTORY\n    urdf/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf\n)\n\n\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_dance_bot.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img  src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_dance_bot_strikes_back/docs/smacc_state_machine_20200222-122229.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> A full-featured state machine example, that highlights the capabilities of SMACC & the ROS Navigation Stack via the MoveBaseZ Client. In the original sm_dance_bot state machine, the variables that controlled the movements of the robot were entirely static, but in this example we made them dynamic, in that the robot uses a lidar sensor to find the range of the wall in front of it, then moves forward that value minus some margin. This also shows the \"Orthogonal Read-Write Cycle\" where we are reading data from one orthogonal (in this case the lidar client, \"cl_lidar\" is inside the obstacle perception orthogonal \"or_obstacle_perception\" and writes via the client \"cl_move_base_z\" in the navigation orthogonal \"or_navigation\".<br></br>\n\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__dance__bot__strikes__back.html\">Doxygen Namespace & Class Reference</a>\n\nTo see a video of this state machine in action click <a href=\"https://www.youtube.com/watch?v=ucMr5Dg6UpU\">here</a>.\n<br></br>\n\n<p align=\"center\">\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_dance_bot_strikes_back/docs/sm_dance_bot_strikes_back.JPG\" width=\"800\"/>\n </p>\n <br></br>\n\n<h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file for the full gazebo demo...\n\n```\nroslaunch sm_dance_bot_strikes_back sm_dance_bot_strikes_back.launch\n```\n\nOr, you can run the lightweight demo...\n\n```\nroslaunch sm_dance_bot_strikes_back sm_dance_bot_strikes_back.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n\nThis launch command starts the process by hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/backward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nBackwardLocalPlanner:\n    k_rho: -1.4 # linear distance to the goal gain, default = -1.0 (related with carrot distance)\n    k_alpha: -0.1\n    k_betta: -1.0\n    carrot_distance: 0.3 #meters default 0.5\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.015 # 0.025\n    yaw_goal_tolerance: 0.3\n    pure_spinning_straight_line_mode: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.057\n  xy_goal_tolerance: 0.15\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/costmap_common_params.yaml",
    "content": "\nmap_type: costmap\norigin_z: 0.0\nz_resolution: 1\nz_voxels: 2\n\nobstacle_range: 12.5\nraytrace_range: 3.0\n\npublish_voxel_map: false\ntransform_tolerance: 0.5\nmeter_scoring: true\n\nfootprint: [[0.48, -0.40], [0.48, 0.40], [-0.48, 0.40], [-0.48, -0.40]]\nfootprint_padding: 0.3\n\nplugins:\n- {name: obstacles_layer, type: \"costmap_2d::ObstacleLayer\"}\n- {name: inflater_layer, type: \"costmap_2d::InflationLayer\"}\n\nobstacles_layer:\n  observation_sources: scan\n  scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 10.5, raytrace_range: 3.0}\n\ninflater_layer:\n inflation_radius: 0.2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/forward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nForwardLocalPlanner:\n    k_rho: 1.0\n    k_alpha: -0.4\n    k_betta: -1.0\n    carrot_distance: 1.5 #meters\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.04\n    yaw_goal_tolerance: 0.01\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/global_costmap_params.yaml",
    "content": "global_costmap:\n  global_frame: odom\n  robot_base_frame: base_link\n  update_frequency: 20\n  publish_frequency: 5\n  width: 40.0\n  height: 40.0\n  resolution: 0.05\n  origin_x: -20.0\n  origin_y: -20.0\n  static_map: true\n  rolling_window: false\n  inflater_layer:\n    inflation_radius: 0.6\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: odom\n   robot_base_frame: base_link\n   update_frequency: 20.0\n   publish_frequency: 5.0\n   width: 10.0\n   height: 10.0\n   resolution: 0.05\n   static_map: false\n   rolling_window: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/move_base_client/waypoints_plan.yaml",
    "content": "waypoints:\n  # POINT 0\n  - position:\n      x: 3.0\n      y: -2.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 1\n  - position:\n      x: -5.75\n      y: 3.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 2\n  - position:\n      x: -10.25\n      y: -4.25\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  # POINT 3\n  - position:\n      x: 1.0\n      y: -8.5\n      #y: -12.35\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n\n    #orientation:\n    #  x: 0.0\n    #  y: 0.0\n    #  z: -0.3007058\n    #  w: 0.953717\n    # POINT 4\n  - position:\n      x: -9.5\n      y: 15.5\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n    # 15degress[ 0, 0, 0.1305262, 0.9914449 ]\n    #orientation:\n    #  x: 0.0\n    #  y: 0.0\n    #  z: 0.1305262\n    #  w: 0.9914449\n  # POINT 5\n  - position:\n      x: -0.0\n      y: 0.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n  #POINT 6\n  - position:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.0\n      w: 1.0\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/config/sm_dancebot_strikes_back_config.yaml",
    "content": "SmDanceBotStrikesBack:\n   signal_detector_loop_freq: 20\n\n# RadialMotionStateMachine:\n#     NavigateToRadialStart:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 start_position_x: 3\n#                 start_position_y: 0\n#     RotateDegress:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 initial_orientation_index: 0 # the initial index of the linear motion (factor of angle_increment_degrees)\n#                 angle_increment_degree: 15    # the increment of angle between to linear motions\n#                 linear_trajectories_count: 12  # the number of linear trajectories of the radial motion\n#     NavigateToEndPoint:\n#         NavigationOrthogonalLine:\n#             Navigate:\n#                 straight_motion_distance: 3.5\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_led/cl_led.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_action_client_base.h>\n#include <sm_dance_bot_strikes_back/LEDControlAction.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_led\n{\nclass ClLED : public smacc::client_bases::SmaccActionClientBase<sm_dance_bot_strikes_back::LEDControlAction>\n{\npublic:\n    SMACC_ACTION_CLIENT_DEFINITION(sm_dance_bot_strikes_back::LEDControlAction);\n\n    ClLED(std::string actionServerName);\n    virtual std::string getName() const override;\n    virtual ~ClLED();\n};\n} // namespace cl_led\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_led/client_behaviors/cb_led_off.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot_strikes_back/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_led\n{\nclass CbLEDOff : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_OFF;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_led/client_behaviors/cb_led_on.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n#include <sm_dance_bot_strikes_back/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_led\n{\nclass CbLEDOn : public smacc::SmaccClientBehavior\n{\npublic:\n  cl_led::ClLED *ledActionClient_;\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(ledActionClient_);\n\n    cl_led::ClLED::Goal goal;\n    goal.command = cl_led::ClLED::Goal::CMD_ON;\n    ledActionClient_->sendGoal(goal);\n  }\n\n  virtual void onExit() override\n  {\n    //ROS_INFO(\"Entering ToolClientBehavior\");\n  }\n};\n} // namespace cl_led\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_lidar/cl_lidar.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/LaserScan.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_lidar\n{\n\nclass ClLidarSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::LaserScan>\n{\npublic:\n    ClLidarSensor(std::string topicname, ros::Duration timeout)\n    {\n\n        this->topicName = topicname;\n        this->timeout_ = timeout;\n    }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n#include <sensor_msgs/LaserScan.h>\n#include <sm_dance_bot_strikes_back/clients/cl_lidar/cl_lidar.h>\n\nnamespace sm_dance_bot_strikes_back\n{\n  namespace cl_lidar\n  {\n    struct CbLidarSensor : cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<sm_dance_bot_strikes_back::cl_lidar::ClLidarSensor>\n    {\n    public:\n      CbLidarSensor()\n      {\n        ROS_INFO(\"CbLidarSensor Constructor\");\n      }\n\n      virtual void onEntry() override\n      {\n        ROS_INFO(\"CbLidarSensor onEntry\");\n        cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClLidarSensor>::onEntry();\n      }\n\n      virtual void onMessageCallback(const sensor_msgs::LaserScan &msg) override\n      {\n      }\n    };\n  } // namespace cl_lidar\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_lidar/components/cp_lidar_data.h",
    "content": "\n#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_lidar\n{\nclass CpLidarSensorData : public smacc::ISmaccComponent\n{\npublic:\n  sensor_msgs::LaserScan lastMessage_;\n  float forwardObstacleDistance;\n\n  const float SECURITY_DISTANCE =  1; //meters\n\n  virtual void onInitialize() override\n  {\n    auto client_ = dynamic_cast<smacc::client_bases::SmaccSubscriberClient<sensor_msgs::LaserScan> *>(owner_);\n    client_->onMessageReceived(&CpLidarSensorData::MessageCallbackStoreDistanceToWall, this);\n  }\n\n  void MessageCallbackStoreDistanceToWall(const sensor_msgs::LaserScan &scanmsg)\n  {\n    this->lastMessage_ = scanmsg;\n    auto fwdist = scanmsg.ranges[scanmsg.ranges.size() / 2] /*meter*/;\n\n    /*if the distance is infinity or nan, use max range distance*/\n    if (fwdist == std::numeric_limits<float>::infinity() || fwdist != fwdist)\n    {\n      this->forwardObstacleDistance = scanmsg.range_max - SECURITY_DISTANCE /*meters*/;\n      ROS_INFO_THROTTLE(1.0, \"[CpLidarSensorData] Distance to forward obstacle is not a number, setting default value to: %lf\", scanmsg.range_max);\n    }\n    else\n    {\n      this->forwardObstacleDistance = std::max(fwdist - SECURITY_DISTANCE, 0.0F);\n    }\n  }\n};\n} // namespace cl_lidar\n} // namespace sm_dance_bot_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_service3/cl_service3.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_service_client.h>\n#include <std_srvs/SetBool.h>\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_service3\n{\nclass ClService3 : public smacc::client_bases::SmaccServiceClient<std_srvs::SetBool>\n{\npublic:\n  ClService3()\n  {\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_service3/client_behaviors/cb_service3.h",
    "content": "#include <smacc/smacc_client_behavior.h>\n#include <sm_dance_bot_strikes_back/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_service3\n{\nenum class Service3Command\n{\n  SERVICE3_ON,\n  SERVICE3_OFF\n};\n\nclass CbService3 : public smacc::SmaccClientBehavior\n{\nprivate:\n  ClService3 *serviceClient_;\n  Service3Command value_;\n\npublic:\n  CbService3(Service3Command value)\n  {\n    value_ = value;\n  }\n\n  virtual void onEntry() override\n  {\n    this->requiresClient(serviceClient_);\n\n    std_srvs::SetBool req;\n    if (value_ == Service3Command::SERVICE3_ON)\n      req.request.data = true;\n    else\n      req.request.data = false;\n\n    serviceClient_->call(req);\n  }\n};\n} // namespace cl_service3\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_string_publisher/cl_string_publisher.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_publisher_client.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_string_publisher\n{\nclass ClStringPublisher : public smacc::client_bases::SmaccPublisherClient\n{\npublic:\n    ClStringPublisher(std::string topicName)\n        : smacc::client_bases::SmaccPublisherClient()\n    {\n        this->configure<std_msgs::String>(topicName);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_strikes_back/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_client_behavior.h>\n#include <std_msgs/String.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_string_publisher\n{\nclass CbStringPublisher : public smacc::SmaccClientBehavior\n{\npublic:\n    ClStringPublisher *publisherClient_;\n    std::string msg_;\n\n    CbStringPublisher(std::string msg)\n    {\n        ROS_INFO_STREAM(\"Creating CbStringPublisher behavior with stored message: \" << msg);\n        msg_ = msg;\n    }\n\n    virtual void onEntry()\n    {\n        this->requiresClient(publisherClient_);\n    }\n\n    virtual void onExit() override\n    {\n        std_msgs::String rosmsg;\n        rosmsg.data = msg_;\n        publisherClient_->publish(rosmsg);\n    }\n};\n} // namespace cl_string_publisher\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_temperature_sensor/cl_temperature_sensor.h",
    "content": "#pragma once\n\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <std_msgs/String.h>\n#include <sensor_msgs/Temperature.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_temperature_sensor\n{\nclass ClTemperatureSensor : public cl_multirole_sensor::ClMultiroleSensor<sensor_msgs::Temperature>\n{\npublic:\n    ClTemperatureSensor()\n    {\n    }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h",
    "content": "\n#pragma once\n#include <sensor_msgs/Temperature.h>\n#include <sm_dance_bot_strikes_back/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_temperature_sensor\n{\nstruct EvCustomTemperatureAlert : sc::event<EvCustomTemperatureAlert>\n{\n};\n\n//--------------------------------------------------------------------------------------\nclass CbConditionTemperatureSensor : public cl_multirole_sensor::CbDefaultMultiRoleSensorBehavior<ClTemperatureSensor>\n{\npublic:\n  CbConditionTemperatureSensor()\n  {\n  }\n  virtual void onMessageCallback(const sensor_msgs::Temperature &msg) override\n  {\n    if (msg.temperature > 40)\n    {\n      auto ev = new EvCustomTemperatureAlert();\n      this->postEvent(ev);\n    }\n  }\n};\n} // namespace cl_temperature_sensor\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/modestates/ms_dance_bot_recovery_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nclass MsDanceBotRecoveryMode : public smacc::SmaccState<MsDanceBotRecoveryMode, SmDanceBotStrikesBack>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, sc::deep_history<MsDanceBotRunMode::LastDeepState>>\n\n   >reactions;\n   // typedef Transition<EvGlobalError, MsDanceBotRunMode> reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/modestates/ms_dance_bot_run_mode.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nclass MsDanceBotRunMode : public smacc::SmaccState<MsDanceBotRunMode, SmDanceBotStrikesBack, StAcquireSensors>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n   >reactions;\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_led.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot_strikes_back/clients/cl_led/cl_led.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrLED : public smacc::Orthogonal<OrLED>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_led::ClLED>(\"led_action_server\");\n        actionclient->initialize();\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_navigation.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nusing namespace cl_move_base_z;\n\nclass OrNavigation : public smacc::Orthogonal<OrNavigation>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto movebaseClient = this->createClient<ClMoveBaseZ>();\n        movebaseClient->initialize();\n\n        movebaseClient->createComponent<Pose>();\n\n        // create planner switcher\n        movebaseClient->createComponent<PlannerSwitcher>();\n\n        // create odom tracker\n        movebaseClient->createComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n\n        // create waypoints navigator component\n        auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();\n        loadWaypointsFromYaml(waypointsNavigator);\n\n        // change this to skip some points of the yaml file, default = 0\n        waypointsNavigator->currentWaypoint_ = 0;\n    }\n\n    void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)\n    {\n        // if it is the first time and the waypoints navigator is not configured\n\n        std::string planfilepath;\n        ros::NodeHandle nh(\"~\");\n        if (nh.getParam(\"/sm_dance_bot_strikes_back/waypoints_plan\", planfilepath))\n        {\n            waypointsNavigator->loadWayPointsFromFile(planfilepath);\n        }\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_obstacle_perception.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_strikes_back/clients/cl_lidar/cl_lidar.h>\n#include <sm_dance_bot_strikes_back/clients/cl_lidar/components/cp_lidar_data.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrObstaclePerception : public smacc::Orthogonal<OrObstaclePerception>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto lidarClient =\n            this->createClient<ClLidarSensor>(\"/front/scan\", ros::Duration(10));\n\n        lidarClient->initialize();\n\n        lidarClient->createComponent<CpLidarSensorData>();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_service3.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sm_dance_bot_strikes_back/clients/cl_service3/cl_service3.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrService3 : public smacc::Orthogonal<OrService3>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto serviceClient = this->createClient<ClService3>();\n        serviceClient->serviceName_ = \"/service_node3\";\n        serviceClient->initialize();\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_string_publisher.h",
    "content": "#pragma once\n\n#include <sm_dance_bot_strikes_back/clients/cl_string_publisher/cl_string_publisher.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_dance_bot_strikes_back\n{\nclass OrStringPublisher : public smacc::Orthogonal<OrStringPublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        this->createClient<ClStringPublisher>(\"/string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_temperature_sensor.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <sensor_msgs/Temperature.h>\n#include <multirole_sensor_client/cl_multirole_sensor.h>\n#include <sm_dance_bot_strikes_back/clients/cl_temperature_sensor/cl_temperature_sensor.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrTemperatureSensor : public smacc::Orthogonal<OrTemperatureSensor>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clTemperatureSensor = this->createClient<ClTemperatureSensor>();\n\n        clTemperatureSensor->topicName = \"/temperature\";\n        //ClTemperatureSensor->queueSize = \"/front/scan\";\n        clTemperatureSensor->timeout_ = ros::Duration(10);\n\n        clTemperatureSensor->initialize();\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_timer.h",
    "content": "#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto publisherClient_ = this->createClient<cl_ros_publisher::ClRosPublisher>();\n        publisherClient_->configure<std_msgs::String>(\"/updatable_string_publisher_out\");\n    }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/sm_dance_bot_strikes_back.h",
    "content": "#include <smacc/smacc.h>\n\n#include <sensor_msgs/LaserScan.h>\n\n// CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n\n#include <multirole_sensor_client/client_behaviors/cb_default_multirole_sensor_behavior.h>\n\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/client_behaviors.h>\n\nusing namespace cl_move_base_z;\n\n#include <sm_dance_bot_strikes_back/clients/cl_led/client_behaviors/cb_led_on.h>\n#include <sm_dance_bot_strikes_back/clients/cl_led/client_behaviors/cb_led_off.h>\n\n#include <sm_dance_bot_strikes_back/clients/cl_lidar/client_behaviors/cb_lidar_sensor.h>\n#include <sm_dance_bot_strikes_back/clients/cl_temperature_sensor/client_behaviors/cb_custom_condition_temperature_sensor.h>\n\n#include <sm_dance_bot_strikes_back/clients/cl_string_publisher/client_behaviors/cb_string_publisher.h>\n#include <sm_dance_bot_strikes_back/clients/cl_service3/client_behaviors/cb_service3.h>\n\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n\nusing namespace sm_dance_bot_strikes_back::cl_lidar;\nusing namespace sm_dance_bot_strikes_back::cl_service3;\nusing namespace sm_dance_bot_strikes_back::cl_string_publisher;\nusing namespace sm_dance_bot_strikes_back::cl_temperature_sensor;\nusing namespace sm_dance_bot_strikes_back::cl_led;\n//using namespace sm_dance_bot_strikes_back::cl_move_base_z;\n//using namespace sm_dance_bot_strikes_back::cl_updatable_publisher;\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n#include <sr_event_countdown/sr_event_countdown.h>\n#include <sr_conditional/sr_conditional.h>\n\nusing namespace smacc::state_reactors;\n\n// ORTHOGONALS\n#include <sm_dance_bot_strikes_back/orthogonals/or_navigation.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_obstacle_perception.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_led.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_temperature_sensor.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_string_publisher.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_service3.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_timer.h>\n#include <sm_dance_bot_strikes_back/orthogonals/or_updatable_publisher.h>\n\nnamespace sm_dance_bot_strikes_back\n{\n//STATE FORWARD DECLARATIONS\nclass StAcquireSensors;\nclass StEventCountDown;\nclass StNavigateToWaypointsX;\nclass StFpatternPrealignment;\nclass StSpatternPrealignment;\n\n//SUPERSTATE FORWARD DECLARATIONS\n\n// MODE STATES FORWARD DECLARATIONS\nclass MsDanceBotRunMode;\nclass MsDanceBotRecoveryMode;\n\nnamespace SS1\n{\nclass SsRadialPattern1;\n}\n\nnamespace SS2\n{\nclass SsRadialPattern2;\n}\n\nnamespace SS3\n{\nclass SsRadialPattern3;\n}\n\nnamespace SS4\n{\nclass SsFPattern1;\n}\n\nnamespace SS5\n{\nclass SsSPattern1;\n}\n\n// custom smd_dance_bot event\nstruct EvGlobalError : sc::event<EvGlobalError>\n{\n};\n\n} // namespace sm_dance_bot_strikes_back\n\nusing namespace sm_dance_bot_strikes_back;\nusing namespace cl_ros_timer;\nusing namespace smacc;\n\nnamespace sm_dance_bot_strikes_back\n{\n/// \\brief Advanced example of state machine with smacc that shows multiple techniques\n///  for the development of state machines\nstruct SmDanceBotStrikesBack\n    : public smacc::SmaccStateMachineBase<SmDanceBotStrikesBack, MsDanceBotRunMode>\n{\n    int counter_1;\n    bool rt_ready_flag;\n\n    typedef mpl::bool_<false> shallow_history;\n    typedef mpl::bool_<false> deep_history;\n    typedef mpl::bool_<false> inherited_deep_history;\n\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->setGlobalSMData(\"counter_1\", counter_1);\n        this->setGlobalSMData(\"rt_ready_flag\", rt_ready_flag);\n\n        this->createOrthogonal<OrNavigation>();\n        this->createOrthogonal<OrObstaclePerception>();\n        this->createOrthogonal<OrLED>();\n        this->createOrthogonal<OrTemperatureSensor>();\n        this->createOrthogonal<OrStringPublisher>();\n        this->createOrthogonal<OrService3>();\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n    }\n};\n\n} // namespace sm_dance_bot_strikes_back\n\n//MODE STATES\n#include <sm_dance_bot_strikes_back/modestates/ms_dance_bot_run_mode.h>\n#include <sm_dance_bot_strikes_back/modestates/ms_dance_bot_recovery_mode.h>\n\n//SUPERSTATES\n#include <sm_dance_bot_strikes_back/superstates/ss_radial_pattern_1.h>\n#include <sm_dance_bot_strikes_back/superstates/ss_radial_pattern_2.h>\n#include <sm_dance_bot_strikes_back/superstates/ss_radial_pattern_3.h>\n#include <sm_dance_bot_strikes_back/superstates/ss_f_pattern_1.h>\n#include <sm_dance_bot_strikes_back/superstates/ss_s_pattern_1.h>\n\n//STATES\n#include <sm_dance_bot_strikes_back/states/st_acquire_sensors.h>\n#include <sm_dance_bot_strikes_back/states/st_event_count_down.h>\n#include <sm_dance_bot_strikes_back/states/st_fpattern_prealignment.h>\n#include <sm_dance_bot_strikes_back/states/st_spattern_prealignment.h>\n\n#include <sm_dance_bot_strikes_back/states/st_navigate_to_waypoints_x.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_forward_1.h",
    "content": "\nnamespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward1 : public smacc::SmaccState<StiFPatternForward1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n  using TSti::configure_orthogonal;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternReturn1<SS>>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    TSti::template configure_orthogonal<OrNavigation, CbNavigateForward>();\n    TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    cl_lidar::ClLidarSensor *lidarClient;\n    this->requiresClient(lidarClient);\n\n    auto lidarData = lidarClient->getComponent<CpLidarSensorData>();\n\n    auto forwardBehavior = TSti::template getOrthogonal<OrNavigation>()\n                               ->template getClientBehavior<CbNavigateForward>();\n\n    forwardBehavior->forwardDistance = lidarData->forwardObstacleDistance;\n    ROS_INFO(\"Going forward in F pattern, distance to wall: %lf\", *(forwardBehavior->forwardDistance));\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_forward_2.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternForward2 : smacc::SmaccState<StiFPatternForward2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternForward2<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiFPatternRotate2<SS>>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n\n    TSti::template configure<OrNavigation, CbNavigateForward>(SS::pitch_lenght_meters());\n    TSti::template configure<OrLED, CbLEDOff>();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_loop_start.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternStartLoop : smacc::SmaccState<StiFPatternStartLoop<SS>, SS>\n{\n  typedef SmaccState<StiFPatternStartLoop<SS>, SS> TSti;\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n      Transition<EvLoopContinue<StiFPatternStartLoop<SS>>, StiFPatternForward2<SS>, CONTINUELOOP>>\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    cl_lidar::ClLidarSensor *lidarClient;\n    this->requiresClient(lidarClient);\n\n    auto lidarData = lidarClient->getComponent<CpLidarSensorData>();\n\n    auto horizontalDistance = lidarData->forwardObstacleDistance;\n\n    return horizontalDistance > 0.5 /*meters*/; // go ahead until 1.5m before the wall\n  }\n\n  void onEntry()\n  {\n    TSti::checkWhileLoopConditionAndThrowEvent(&StiFPatternStartLoop<SS>::loopCondition);\n  }\n};\n} // namespace f_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_return_1.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternReturn1 : smacc::SmaccState<StiFPatternReturn1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternReturn1<SS>, SS> TSti;\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiFPatternRotate1<SS>>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    TSti::template configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    TSti::template configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_rotate_1.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate1 : smacc::SmaccState<StiFPatternRotate1<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate1<SS>, SS> TSti;\n  using TSti::context;\n  using TSti::getOrthogonal;\n\n  using TSti::SmaccState;\n  using TSti::context_type;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternStartLoop<SS>>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n    TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(); // absolute aligned to the y-axis\n    TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void\n  runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n\n    auto initialStateAngle = superstate.initialStateAngle;\n\n    float angle = 0;\n    double offset = 9; // for a better behaving\n\n    if (SS::direction() == TDirection::LEFT)\n      angle = -offset;\n    else\n      angle = +offset;\n\n    auto absoluteRotateBehavior = TSti::template getOrthogonal<OrNavigation>()->template getClientBehavior<CbAbsoluteRotate>();\n\n    absoluteRotateBehavior->absoluteGoalAngleDegree = initialStateAngle + angle;\n    ROS_INFO(\"Fpattern, rotate to: %lf\", *(absoluteRotateBehavior->absoluteGoalAngleDegree));\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_rotate_2.h",
    "content": "#include <angles/angles.h>\nnamespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n// STATE DECLARATION\ntemplate <typename SS>\nstruct StiFPatternRotate2 : smacc::SmaccState<StiFPatternRotate2<SS>, SS>\n{\n  typedef SmaccState<StiFPatternRotate2<SS>, SS> TSti;\n  using TSti::context;\n  using TSti::getOrthogonal;\n\n  using TSti::context_type;\n  using TSti::SmaccState;\n\n// TRANSITION TABLE\n\n      typedef mpl::list<\n      Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiFPatternForward1<SS>>\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    //TSti::template configure_orthogonal<OrNavigation, CbRotate>(angle);\n    TSti::template configure_orthogonal<OrNavigation, CbAbsoluteRotate>(); // absolute horizontal\n    TSti::template configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = TSti::template context<SS>();\n\n    auto initialStateAngle = 0;//superstate.initialStateAngle;\n    double offset = superstate.offset; // for a better behaving\n    float angle = 0;\n    if (SS::direction() == TDirection::LEFT)\n      angle = 90 + offset;\n    else\n      angle = -90 - offset;\n\n\n    auto absoluteRotateBehavior = TSti::template getOrthogonal<OrNavigation>()->template getClientBehavior<CbAbsoluteRotate>();\n\n    auto targetAngle =  angles::to_degrees(angles::normalize_angle(angles::from_degrees(initialStateAngle + angle)));\n\n    absoluteRotateBehavior->absoluteGoalAngleDegree = targetAngle;\n    ROS_INFO(\"Fpattern, rotate to: %lf\", *(absoluteRotateBehavior->absoluteGoalAngleDegree));\n  }\n};\n} // namespace f_pattern_states\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_end_point.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialEndPoint : smacc::SmaccState<StiRadialEndPoint, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiRadialReturn, SUCCESS>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiRadialLoopStart, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>();\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    cl_lidar::ClLidarSensor *lidarClient;\n    this->requiresClient(lidarClient);\n\n    auto lidarData = lidarClient->getComponent<CpLidarSensorData>();\n\n    auto forwardBehavior = this->getOrthogonal<OrNavigation>()\n                               ->getClientBehavior<CbNavigateForward>();\n\n    forwardBehavior->forwardDistance = lidarData->forwardObstacleDistance;\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_loop_start.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialLoopStart : smacc::SmaccState<StiRadialLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiRadialLoopStart>, StiRadialRotate, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiRadialLoopStart::loopWhileCondition);\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_return.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialReturn : smacc::SmaccState<StiRadialReturn, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbUndoPathBackwards, OrNavigation>, StiRadialLoopStart, SUCCESS>,\n  Transition<EvCbFailure<CbUndoPathBackwards, OrNavigation>, StiRadialEndPoint, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbUndoPathBackwards>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_rotate.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace radial_motion_states\n{\n// STATE DECLARATION\nstruct StiRadialRotate : smacc::SmaccState<StiRadialRotate, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiRadialEndPoint, SUCCESS>,\n  Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiRadialLoopStart, ABORT>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto cbAbsRotate = this->getOrthogonal<OrNavigation>()\n                           ->getClientBehavior<CbAbsoluteRotate>();\n\n    auto &superstate = this->context<SS>();\n    cbAbsRotate->absoluteGoalAngleDegree = superstate.iteration_count * SS::ray_angle_increment_degree();\n  }\n};\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_1.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward1 : public smacc::SmaccState<StiSPatternForward1, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate2>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate1>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n  }\n\n  void runtimeConfiguration()\n  {\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_2.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward2 : public smacc::SmaccState<StiSPatternForward2, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate3>,\n      Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate2>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>();\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n\n    double extrasecurityMargin = 0.2;\n\n    auto forwardBehavior = this->getOrthogonal<OrNavigation>()\n                               ->getClientBehavior<CbNavigateForward>();\n\n    cl_lidar::ClLidarSensor *lidarClient;\n    this->requiresClient(lidarClient);\n    auto lidarData = lidarClient->getComponent<CpLidarSensorData>();\n\n    if (!std::isnan(lidarData->forwardObstacleDistance))\n      forwardBehavior->forwardDistance = lidarData->forwardObstacleDistance - extrasecurityMargin; /*extra security margin for easy dynamic implementation of dynamic-smotion*/\n\n    else\n      forwardBehavior->forwardDistance = superstate.pitch2_lenght_meters();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_3.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward3 : public smacc::SmaccState<StiSPatternForward3, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternRotate4>,\n  Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate3>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>(SS::pitch1_lenght_meters());\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_4.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternForward4 : public smacc::SmaccState<StiSPatternForward4, SS>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvCbSuccess<CbNavigateForward, OrNavigation>, StiSPatternLoopStart>,\n      Transition<EvCbFailure<CbNavigateForward, OrNavigation>, StiSPatternRotate4>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbNavigateForward>();\n    configure_orthogonal<OrLED, CbLEDOn>();\n  }\n\n  void runtimeConfigure()\n  {\n    auto &superstate = this->context<SS>();\n    double extrasecurityMargin = 0.2;\n\n    auto forwardBehavior = this->getOrthogonal<OrNavigation>()\n                               ->getClientBehavior<CbNavigateForward>();\n\n    cl_lidar::ClLidarSensor *lidarClient;\n    this->requiresClient(lidarClient);\n    auto lidarData = lidarClient->getComponent<CpLidarSensorData>();\n\n    if (!std::isnan(lidarData->forwardObstacleDistance))\n      forwardBehavior->forwardDistance = lidarData->forwardObstacleDistance - extrasecurityMargin; /*extra security margin for easy dynamic implementation of dynamic-smotion*/\n\n    else\n      forwardBehavior->forwardDistance = superstate.pitch2_lenght_meters();\n  }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_loop_start.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternLoopStart : smacc::SmaccState<StiSPatternLoopStart, SS>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiSPatternLoopStart>, StiSPatternRotate1, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopCondition()\n  {\n    auto &superstate = this->context<SS>();\n    if(superstate.iteration_count++ < superstate.total_iterations())\n    {\n      ROS_INFO(\"Spattern iteration finished, going to next iteration (%d)\", superstate.iteration_count);\n      return true;\n    }\n    else\n    {\n      ROS_INFO(\"Spattern iteration finished, All iterations finished (%d)\", superstate.iteration_count - 1);\n      return false;\n    }\n\n  }\n\n  void onEntry()\n  {\n    checkWhileLoopConditionAndThrowEvent(&StiSPatternLoopStart::loopCondition);\n  }\n};\n\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_1.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate1 : smacc::SmaccState<StiSPatternRotate1, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward1>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternLoopStart>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        double offset;\n        // if (superstate.iteration_count == 1)\n        // {\n            offset = 0;\n        // }\n        // else\n        // {\n        //     offset = 13.5;\n        // }\n\n        auto absoluteRotateBehavior = this->getOrthogonal<OrNavigation>()\n                                          ->getClientBehavior<CbAbsoluteRotate>();\n\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            // - offset because we are looking to the north and we have to turn clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle - offset;\n        }\n        else\n        {\n            // - offset because we are looking to the south and we have to turn counter-clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle + offset;\n        }\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_2.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate2 : smacc::SmaccState<StiSPatternRotate2, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward2>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternForward1>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 0;\n        auto absoluteRotateBehavior = this->getOrthogonal<OrNavigation>()->template getClientBehavior<CbAbsoluteRotate>();\n\n\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle - 90 - offset;\n        }\n        else\n        {\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle + 90 + offset;\n        }\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_3.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate3 : smacc::SmaccState<StiSPatternRotate3, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward3>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternForward2>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset = 0;\n        auto absoluteRotateBehavior = this->getOrthogonal<OrNavigation>()->template getClientBehavior<CbAbsoluteRotate>();\n\n\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            // - offset because we are looking to the north and we have to turn clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle + offset;\n        }\n        else\n        {\n            // - offset because we are looking to the south and we have to turn counter-clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle - offset;\n        }\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_4.h",
    "content": "namespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n// STATE DECLARATION\nstruct StiSPatternRotate4 : smacc::SmaccState<StiSPatternRotate4, SS>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, StiSPatternForward4>,\n        Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StiSPatternForward3>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrNavigation, CbAbsoluteRotate>();\n        configure_orthogonal<OrLED, CbLEDOff>();\n    }\n\n    void runtimeConfigure()\n    {\n        auto &superstate = this->context<SS>();\n        ROS_INFO(\"[StiSPatternRotate] SpatternRotate rotate: SS current iteration: %d/%d\", superstate.iteration_count, SS::total_iterations());\n\n        float offset= 0;\n\n        auto absoluteRotateBehavior = this->getOrthogonal<OrNavigation>()->template getClientBehavior<CbAbsoluteRotate>();\n\n        if (superstate.direction() == TDirection::RIGHT)\n        {\n            // - offset because we are looking to the south and we have to turn counter-clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle + 90 + offset;\n        }\n        else\n        {\n            // - offset because we are looking to the north and we have to turn clockwise\n            absoluteRotateBehavior->absoluteGoalAngleDegree = superstate.initialStateAngle - 90 - offset;\n\n        }\n    }\n};\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/st_acquire_sensors.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nstruct StAcquireSensors : smacc::SmaccState<StAcquireSensors, MsDanceBotRunMode>\n{\n   using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n   struct ON_SENSORS_AVAILABLE : SUCCESS{};\n   struct SrAcquireSensors;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvAllGo<SrAllEventsGo, SrAcquireSensors>, StEventCountDown, ON_SENSORS_AVAILABLE>,\n   Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n   >reactions;\n\n// STATE FUNCTIONS\n   static void staticConfigure()\n   {\n      configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n      configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n      configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n      configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n      configure_orthogonal<OrUpdatablePublisher, cl_ros_publisher::CbDefaultPublishLoop>();\n\n      // Create State Reactor\n      //auto srAllSensorsReady = static_createStateReactor<SrAllEventsGo>();\n\n      auto srAllSensorsReady = static_createStateReactor<SrAllEventsGo,\n                                                         EvAllGo<SrAllEventsGo, SrAcquireSensors>,\n                                                         mpl::list<\n                                                                     EvTopicMessage<CbLidarSensor, OrObstaclePerception>,\n                                                                     EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>\n                                                                  >>();\n\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbLidarSensor, OrObstaclePerception>>();\n      //srAllSensorsReady->addInputEvent<EvTopicMessage<CbConditionTemperatureSensor, OrTemperatureSensor>>();\n      //srAllSensorsReady->setOutputEvent<EvAllGo<SrAllEventsGo, SrAcquireSensors>>();\n   }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/st_event_count_down.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nstruct StEventCountDown : smacc::SmaccState<StEventCountDown, MsDanceBotRunMode>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvCountdownEnd<SrEventCountdown>, StNavigateToWaypointsX>,\n    Transition<EvGlobalError, MsDanceBotRecoveryMode>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //   configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n        //   configure_orthogonal<OrStringPublisher, CbStringPublisher>(\"Hello World!\");\n        //   configure_orthogonal<OrTemperatureSensor, CbConditionTemperatureSensor>();\n        //   configure_orthogonal<OrService3, CbService3>(Service3Command::SERVICE3_ON);\n\n        // Create State Reactor\n        // auto srCountdown = static_createStateReactor<SrEventCountdown>(5);\n        // srCountdown->addInputEvent<EvTimer<ClRosTimer, OrTimer>>();\n        // srCountdown->setOutputEvent<EvCountdownEnd<SrEventCountdown>>();\n\n        auto srCountdown = static_createStateReactor<SrEventCountdown,\n                                                    EvCountdownEnd<SrEventCountdown>,\n                                                    mpl::list<\n                                                            EvTimer<ClRosTimer, OrTimer>\n                                                            >>(5);\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/st_fpattern_prealignment.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nstruct StFpatternPrealignment : smacc::SmaccState<StFpatternPrealignment, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, SS4::SsFPattern1>,\n  Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbAbsoluteRotate>(0);\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/st_navigate_to_waypoints_x.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nstruct StNavigateToWaypointsX : smacc::SmaccState<StNavigateToWaypointsX, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TRANSITION_1 : SUCCESS{};\n  struct TRANSITION_2 : SUCCESS{};\n  struct TRANSITION_3 : SUCCESS{};\n  struct TRANSITION_4 : SUCCESS{};\n  struct TRANSITION_5 : SUCCESS{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvWaypoint0<ClMoveBaseZ, OrNavigation>, SS1::SsRadialPattern1, TRANSITION_1>,\n  Transition<EvWaypoint1<ClMoveBaseZ, OrNavigation>, SS2::SsRadialPattern2, TRANSITION_2>,\n  Transition<EvWaypoint2<ClMoveBaseZ, OrNavigation>, SS3::SsRadialPattern3, TRANSITION_3>,\n  Transition<EvWaypoint3<ClMoveBaseZ, OrNavigation>, StFpatternPrealignment, TRANSITION_4>,\n  Transition<EvWaypoint4<ClMoveBaseZ, OrNavigation>, StSpatternPrealignment, TRANSITION_5>,\n  Transition<EvCbFailure<ClMoveBaseZ, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrLED, CbLEDOn>();\n    configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    configure_orthogonal<OrNavigation, CbNavigateNextWaypoint>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/states/st_spattern_prealignment.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_dance_bot_strikes_back\n{\n// STATE DECLARATION\nstruct StSpatternPrealignment : smacc::SmaccState<StSpatternPrealignment, MsDanceBotRunMode>\n{\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvCbSuccess<CbAbsoluteRotate, OrNavigation>, SS5::SsSPattern1>,\n  Transition<EvCbFailure<CbAbsoluteRotate, OrNavigation>, StNavigateToWaypointsX>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrNavigation, CbAbsoluteRotate>(60.5);\n    configure_orthogonal<OrLED, CbLEDOff>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/superstates/ss_f_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n#include <tf/transform_datatypes.h>\n#include <angles/angles.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace f_pattern_states\n{\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\n// FORWARD DECLARATIONS OF INNER STATES\ntemplate <typename SS>\nclass StiFPatternRotate1;\ntemplate <typename SS>\nclass StiFPatternForward1;\ntemplate <typename SS>\nclass StiFPatternReturn1;\ntemplate <typename SS>\nclass StiFPatternRotate2;\ntemplate <typename SS>\nclass StiFPatternForward2;\ntemplate <typename SS>\nclass StiFPatternStartLoop;\n} // namespace f_pattern_states\n} // namespace sm_dance_bot_strikes_back\nnamespace sm_dance_bot_strikes_back\n{\nnamespace SS4\n{\nusing namespace f_pattern_states;\n\n// STATE DECLARATION\nstruct SsFPattern1 : smacc::SmaccState<SsFPattern1, MsDanceBotRunMode, StiFPatternStartLoop<SsFPattern1>>\n{\npublic:\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n        Transition<EvLoopEnd<StiFPatternStartLoop<SsFPattern1>>, StNavigateToWaypointsX, ENDLOOP>>\n        reactions;\n\n    // STATE VARIABLES\n    // superstate parameters\n    static constexpr float ray_lenght_meters() { return 4; }\n    static constexpr float pitch_lenght_meters() { return 0.6; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n\n    double initialStateAngle = 0;\n    double offset;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n        this->offset = 0;//13.5;\n        cl_move_base_z::ClMoveBaseZ *robot;\n        this->requiresClient(robot);\n\n        if (robot != nullptr)\n        {\n            auto pose = robot->getComponent<cl_move_base_z::Pose>()->toPoseMsg();\n            this->initialStateAngle = angles::to_degrees(angles::normalize_angle(tf::getYaw(pose.orientation)));\n            ROS_INFO(\"Initial angle for F pattern: %lf degrees\", initialStateAngle);\n        }\n        else\n        {\n            ROS_ERROR(\"robot pose not found to plan the FPattern motion\");\n        }\n    }\n}; // namespace SS4\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\n} // namespace SS4\n} // namespace sm_dance_bot_strikes_back\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_rotate_1.h>\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_forward_1.h>\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_return_1.h>\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_rotate_2.h>\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_forward_2.h>\n#include <sm_dance_bot_strikes_back/states/f_pattern_states/sti_fpattern_loop_start.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/superstates/ss_radial_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_strikes_back {\nnamespace SS1 {\nnamespace sm_dance_bot_strikes_back {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\nusing namespace sm_dance_bot_strikes_back::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern1 : smacc::SmaccState<SsRadialPattern1, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateToWaypointsX, ENDLOOP>\n\n    >reactions;\n\n    static constexpr int total_iterations() { return 32; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 4; }\n\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern1;\n\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS1\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/superstates/ss_radial_pattern_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_strikes_back {\nnamespace SS2 {\nnamespace sm_dance_bot_strikes_back {\nnamespace radial_motion_states {\n\n//FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\nusing namespace sm_dance_bot_strikes_back::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern2 : smacc::SmaccState<SsRadialPattern2, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateToWaypointsX, ENDLOOP> //,\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    int iteration_count = 0;\n    static constexpr int total_iterations() { return 32; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 5; }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern2;\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS2\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/superstates/ss_radial_pattern_3.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_strikes_back {\nnamespace SS3 {\nnamespace sm_dance_bot_strikes_back {\nnamespace radial_motion_states {\n\n// FORWARD DECLARATION OF INNER STATES\nclass StiRadialRotate;\nclass StiRadialReturn;\nclass StiRadialEndPoint;\nclass StiRadialLoopStart;\n} // namespace radial_motion_states\n} // namespace sm_dance_bot_strikes_back\nusing namespace sm_dance_bot_strikes_back::radial_motion_states;\n\n// STATE DECLARATION\nstruct SsRadialPattern3 : smacc::SmaccState<SsRadialPattern3, MsDanceBotRunMode, StiRadialLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiRadialLoopStart>, StNavigateToWaypointsX, ENDLOOP>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    int iteration_count;\n\n    static constexpr int total_iterations() { return 32; }\n    static constexpr float ray_angle_increment_degree() { return 360.0 / total_iterations(); }\n    static constexpr float ray_length_meters() { return 4; }\n\n    void runtimeConfigure()\n    {\n        iteration_count = 0;\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsRadialPattern3;\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_end_point.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_return.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_rotate.h>\n#include <sm_dance_bot_strikes_back/states/radial_motion_states/sti_radial_loop_start.h>\n} // namespace SS3\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/include/sm_dance_bot_strikes_back/superstates/ss_s_pattern_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace SS5\n{\nnamespace sm_dance_bot_strikes_back\n{\nnamespace s_pattern_states\n{\n\n// FORWARD DECLARATION OF INNER STATES\nclass StiSPatternRotate1;\nclass StiSPatternForward1;\nclass StiSPatternRotate2;\nclass StiSPatternForward2;\nclass StiSPatternRotate3;\nclass StiSPatternForward3;\nclass StiSPatternRotate4;\nclass StiSPatternForward4;\nclass StiSPatternLoopStart;\n} // namespace s_pattern_states\n} // namespace sm_dance_bot_strikes_back\n\nenum class TDirection\n{\n    LEFT,\n    RIGHT\n};\n\nusing namespace sm_dance_bot_strikes_back::s_pattern_states;\n\n// STATE DECLARATION\nstruct SsSPattern1 : smacc::SmaccState<SsSPattern1, MsDanceBotRunMode, StiSPatternLoopStart>\n{\npublic:\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<EvLoopEnd<StiSPatternLoopStart>, StNavigateToWaypointsX, ENDLOOP>\n\n        >\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n    }\n\n    static constexpr float pitch1_lenght_meters() { return 0.6; }\n    static constexpr float pitch2_lenght_meters() { return 1.75; }\n    static constexpr int total_iterations() { return 12; }\n    static constexpr TDirection direction() { return TDirection::RIGHT; }\n    double initialStateAngle;\n\n    int iteration_count;\n\n    void runtimeConfigure()\n    {\n\n        this->iteration_count = 0;\n\n        cl_move_base_z::ClMoveBaseZ *robot;\n        this->requiresClient(robot);\n\n        if (robot != nullptr)\n        {\n            auto pose = robot->getComponent<cl_move_base_z::Pose>()->toPoseMsg();\n            this->initialStateAngle = angles::to_degrees(angles::normalize_angle(tf::getYaw(pose.orientation)));\n            ROS_INFO(\"Initial angle for F pattern: %lf\", initialStateAngle);\n        }\n        else\n        {\n            ROS_ERROR(\"robot pose not found to plan the FPattern motion\");\n        }\n    }\n};\n\n// FORWARD DECLARATION FOR THE SUPERSTATE\nusing SS = SsSPattern1;\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_1.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_1.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_2.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_2.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_3.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_3.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_rotate_4.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_forward_4.h>\n#include <sm_dance_bot_strikes_back/states/s_pattern_states/sti_spattern_loop_start.h>\n\n} // namespace SS5\n} // namespace sm_dance_bot_strikes_back\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/launch/readme.md",
    "content": "# Dance Bot State Machine\n## Setup and requirements\n\nMake sure that you have installed all the dependencies. For example this demo depends on rigeback robot simulation.\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nAfter that you have to build the smacc ros workspace using catkin_make.\n\n```\ncatkin_make\n```\n\nAfter you build, remember to source the proper devel folder.\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\n## Default demo launching\nBelow is the default launch command to launch this demo:\n\n```\nroslaunch sm_dance_bot_strikes_back sm_dance_bot_strikes_back.launch\n```\n\n## Lightweight demo launching\n\nWe use this launch command to start the process hiding the xterminals for all the servers, the state machine, the smacc_viewer and the gazebo client.\n\n```\nroslaunch sm_dance_bot_strikes_back sm_dance_bot_strikes_back.launch sm_xterm:=nice server_nodes_xterms:=nice show_gz_client:=false show_smacc_viewer:=false\n```\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/launch/ridgeback_simulation.launch",
    "content": "<launch>\n    <arg name=\"show_gz_client\" default=\"true\"/>\n\n    <include file=\"$(find ridgeback_gazebo)/launch/ridgeback_world.launch\">\n        <arg name=\"gui\" value=\"$(arg show_gz_client)\"/>\n    </include>\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"true\" name=\"move_base\" launch-prefix=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e \">\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/local_costmap_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/local_costmap_params.yaml\" command=\"load\" />\n\n\n        <!-- <rosparam file=\"$(find ridgeback_navigation)/params/base_local_planner_params.yaml\" command=\"load\" /> -->\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/base_local_planner_params.yaml\" command=\"load\" />\n\n\n        <rosparam file=\"$(find ridgeback_navigation)/params/move_base_params.yaml\" command=\"load\" />\n\n        <param name=\"base_global_planner\" type=\"string\" value=\"navfn/NavfnROS\" />\n        <param name=\"base_local_planner\" value=\"base_local_planner/TrajectoryPlannerROS\"/>\n\n        <remap from=\"odom\" to=\"odometry/filtered\" />\n    </node>\n\n    <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find ridgeback_navigation)/maps/ridgeback_race.yaml\" output=\"screen\"/>\n\n    <!--- Run AMCL -->\n    <include file=\"$(find ridgeback_navigation)/launch/include/amcl.launch\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/launch/sm_dance_bot_strikes_back.launch",
    "content": "<launch>\n\n    <!--========= LAUNCH FILE ARGUMENTS ======================================================-->\n    <!-- defines the xterm parameters for the clients, set to empty to skip using xterm window-->\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <!-- defines the xterm parameters for the state machine, set to empty to skip using xterm window-->\n    <arg name=\"sm_xterm\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e\" />\n\n    <!-- if true, gazebo client is shown -->\n    <arg name=\"show_gz_client\" default=\"true\" />\n\n    <!-- if true, smacc_viewer is shown -->\n    <arg name=\"show_smacc_viewer\" default=\"true\" />\n\n    <!-- if true, rviz is shown -->\n    <arg name=\"show_rviz\" default=\"true\" />\n\n    <!-- It does not start the sm node in order to start it from your standalone process with debugger-->\n    <arg name=\"debug\" default=\"false\" />\n\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_dance_bot_strikes_back)/config/rosconsole.config\" />\n\n    <!--================================================================================-->\n    <!-- load the navigation environment simulated in gazebo-->\n    <include file=\"$(find sm_dance_bot_strikes_back)/launch/ridgeback_simulation.launch\">\n        <arg name=\"show_gz_client\" value=\"$(arg show_gz_client)\" />\n    </include>\n\n    <!--  setup smacc planners configuration  -->\n    <group ns=\"move_base\">\n        <!-- backward local planner -->\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/backward_local_planner.yaml\" command=\"load\" />\n        <!-- forward local planner -->\n        <rosparam file=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/forward_local_planner.yaml\" command=\"load\" />\n    </group>\n\n    <!-- load state machine parameters -->\n    <rosparam command=\"load\" file=\"$(find sm_dance_bot_strikes_back)/config/sm_dancebot_strikes_back_config.yaml\" />\n\n    <group ns=\"sm_dance_bot_strikes_back\">\n        <!-- set run mode -->\n        <param name=\"run_mode\" value=\"debug\" />\n        <!-- load flight plan -->\n        <param name=\"waypoints_plan\" value=\"$(find sm_dance_bot_strikes_back)/config/move_base_client/waypoints_plan.yaml\" />\n    </group>\n\n    <!-- state machine node -->\n    <node pkg=\"sm_dance_bot_strikes_back\" type=\"sm_dance_bot_strikes_back\" name=\"sm_dance_bot_strikes_back\" launch-prefix=\"$(arg sm_xterm)\" unless=\"$(arg debug)\">\n        <remap from=\"/odom\" to=\"/odometry/filtered\" />\n        <remap from=\"/sm_dance_bot_strikes_back/odom_tracker/odom_tracker_path\" to=\"/odom_tracker_path\"/>\n        <remap from=\"/sm_dance_bot_strikes_back/odom_tracker/odom_tracker_stacked_path\" to=\"/odom_tracker_path_stacked\"/>\n    </node>\n\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find sm_dance_bot)/config/navigation.rviz\" if=\"$(arg show_rviz)\">\n        <remap from=\"/remap_smacc_status\" to=\"/SmDanceBotStrikesBack/smacc/status\" />\n    </node>\n\n    <node pkg=\"sm_dance_bot_strikes_back\" type=\"led_action_server_node\" name=\"led_action_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot_strikes_back\" type=\"temperature_sensor_node\" name=\"temperature_sensor_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n    <node pkg=\"sm_dance_bot_strikes_back\" type=\"service_node_3.py\" name=\"service_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <!-- <node pkg=\"smacc_viewer\" type=\"smacc_viewer_node.py\" name=\"smacc_viewer\" if=\"$(arg show_smacc_viewer)\"/> -->\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_dance_bot_strikes_back</name>\n    <version>1.4.16</version>\n  <description>The dance_bot_strikes_back package</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n  <license>BSD-3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>actionlib</depend>\n  <depend>actionlib_msgs</depend>\n  <depend>sm_dance_bot</depend>\n\n  <depend>move_base_z_client_plugin</depend>\n  <depend>angles</depend>\n\n  <depend>ros_publisher_client</depend>\n  <depend>multirole_sensor_client</depend>\n\n  <depend>sr_all_events_go</depend>\n  <depend>sr_event_countdown</depend>\n  <depend>sr_conditional</depend>\n  <depend>ros_timer_client</depend>\n\n  <depend>ridgeback_gazebo</depend>\n  <depend>ridgeback_navigation</depend>\n  <depend>xterm</depend>\n  <depend>tf</depend>¡\n\n  <export>\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/action_server_node_3/src/action_server_node_3.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/led_action_server/action/LEDControl.action",
    "content": "uint8 command\n\n# Possible command values\nuint8 CMD_ON = 0\nuint8 CMD_OFF = 1\n---\nuint8 state\n\n# Possible feeedback values (tool states)\nuint8 STATE_UNKNOWN = 0\nuint8 STATE_RUNNING = 1\nuint8 STATE_IDLE = 2\n---\nuint8 result\n\n# Possible result values\nuint8 RESULT_SUCCESS = 0\nuint8 RESULT_ERROR = 1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/led_action_server/src/led_action_server_node.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <actionlib/server/simple_action_server.h>\n#include <std_msgs/UInt8.h>\n#include <functional>\n#include <dynamic_reconfigure/DoubleParameter.h>\n#include <dynamic_reconfigure/Reconfigure.h>\n#include <dynamic_reconfigure/Config.h>\n#include <sm_dance_bot_strikes_back/LEDControlAction.h>\n#include <sm_dance_bot_strikes_back/LEDControlActionResult.h>\n#include <sm_dance_bot_strikes_back/LEDControlResult.h>\n#include <memory>\n#include <visualization_msgs/MarkerArray.h>\n\ntypedef actionlib::SimpleActionServer<sm_dance_bot_strikes_back::LEDControlAction> Server;\n\n// This class describes a preemptable-on/off tool action server to be used from smacc\n// shows in rviz a sphere whose color describe the current state (unknown, running, idle)\nclass LEDActionServer\n{\npublic:\n  std::shared_ptr<Server> as_ ;\n\n  ros::Publisher stateMarkerPublisher_;\n\n  sm_dance_bot_strikes_back::LEDControlGoal cmd;\n\n  uint8_t currentState_;\n\n/**\n******************************************************************************************************************\n* constructor()\n******************************************************************************************************************\n*/\n  LEDActionServer()\n  {\n    currentState_ =  sm_dance_bot_strikes_back::LEDControlResult::STATE_UNKNOWN;\n  }\n\n/**\n******************************************************************************************************************\n* publishFeedback()\n******************************************************************************************************************\n*/\nvoid publishFeedback()  // Note: \"Action\" is not appended to DoDishes here\n{\n    sm_dance_bot_strikes_back::LEDControlFeedback feedback_msg;\n\n    as_->publishFeedback(feedback_msg);\n}\n\n/**\n******************************************************************************************************************\n* execute()\n******************************************************************************************************************\n*/\nvoid execute(const sm_dance_bot_strikes_back::LEDControlGoalConstPtr& goal)  // Note: \"Action\" is not appended to DoDishes here\n{\n  ROS_INFO_STREAM(\"Tool action server request: \"<< *goal);\n  cmd = *goal;\n\n  if(goal->command == sm_dance_bot_strikes_back::LEDControlGoal::CMD_ON)\n  {\n    currentState_ =  sm_dance_bot_strikes_back::LEDControlResult::STATE_RUNNING;\n  }\n  else  if (goal->command == sm_dance_bot_strikes_back::LEDControlGoal::CMD_OFF)\n  {\n    currentState_ =  sm_dance_bot_strikes_back::LEDControlResult::STATE_IDLE;\n  }\n\n  // 10Hz internal loop\n  ros::Rate rate(20);\n\n  while(ros::ok())\n  {\n    if(as_->isPreemptRequested())\n    {\n       // a new request is being executed, we will stop this one\n       ROS_WARN(\"LEDActionServer request preempted. Forgetting older request.\");\n       as_->setPreempted();\n       return;\n    }\n\n    publishFeedback();\n    publishStateMarker();\n    rate.sleep();\n  }\n\n   // never reach succeeded because were are interested in keeping the feedback alive\n   as_->setSucceeded();\n}\n\n/**\n******************************************************************************************************************\n* run()\n******************************************************************************************************************\n*/\nvoid run()\n{\n  ros::NodeHandle n;\n  ROS_INFO(\"Creating tool action server\");\n\n  as_ = std::make_shared<Server>(n, \"led_action_server\", boost::bind(&LEDActionServer::execute, this,  _1), false);\n  ROS_INFO(\"Starting Tool Action Server\");\n\n  stateMarkerPublisher_ = n.advertise<visualization_msgs::MarkerArray>(\"tool_markers\", 1);\n\n  as_->start();\n\n  ros::spin();\n}\n\n/**\n******************************************************************************************************************\n* publishStateMarker()\n******************************************************************************************************************\n*/\nvoid publishStateMarker()\n{\n    visualization_msgs::Marker marker;\n    marker.header.frame_id = \"base_link\";\n    marker.header.stamp = ros::Time::now ();\n\n    marker.ns = \"tool_namespace\";\n    marker.id = 0;\n    marker.type = visualization_msgs::Marker::SPHERE;\n    marker.action = visualization_msgs::Marker::ADD;\n\n    marker.scale.x = 0.2;\n    marker.scale.y = 0.2;\n    marker.scale.z = 0.2;\n\n    marker.color.a = 1;\n\n    if(currentState_ == sm_dance_bot_strikes_back::LEDControlResult::STATE_RUNNING)\n    {\n      // show green ball\n      marker.color.r = 0;\n      marker.color.g = 1;\n      marker.color.b = 0;\n    }\n    else if (currentState_ == sm_dance_bot_strikes_back::LEDControlResult::STATE_IDLE)\n    {\n      // show gray ball\n      marker.color.r = 0.7;\n      marker.color.g = 0.7;\n      marker.color.b = 0.7;\n    }\n    else\n    {\n      // show black ball\n      marker.color.r = 0;\n      marker.color.g = 0;\n      marker.color.b = 0;\n    }\n\n    marker.pose.orientation.w=1;\n    marker.pose.position.x=0;\n    marker.pose.position.y=0;\n    marker.pose.position.z=1;\n\n    visualization_msgs::MarkerArray ma;\n    ma.markers.push_back(marker);\n\n    stateMarkerPublisher_.publish(ma);\n}\n};\n\n/**\n******************************************************************************************************************\n* main()\n******************************************************************************************************************\n*/\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"led_action_server_node\");\n  LEDActionServer LEDActionServer;\n  LEDActionServer.run();\n\n  return 0;\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/lidar_node/src/lidar_node.cpp",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/service_node_3/__init__.py",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/service_node_3/src/service_node_3.py",
    "content": "#!/usr/bin/env python\n\n\nimport rospy\nimport std_srvs\n\nif __name__ == \"__main__\":\n\n    def set_bool_service(req):\n        rospy.loginfo(\"RECEIVING SET BOOL SERVICE REQUEST: value=\" + str(req.data))\n\n        response = std_srvs.srv.SetBoolResponse()\n        response.message = \"OK, value set\"\n        response.success = True\n        return response\n\n    rospy.init_node(\"service_node3\")\n    s = rospy.Service(\"service_node3\", std_srvs.srv.SetBool, set_bool_service)\n    rospy.spin()\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/servers/temperature_sensor_node/src/temperature_sensor_node.cpp",
    "content": "#include <ros/ros.h>\n#include <sensor_msgs/Temperature.h>\n\nint main(int argc, char** argv)\n{\n    ros::init(argc,argv, \"temperature_sensor_node\");\n\n    ros::NodeHandle nh;\n    auto pub = nh.advertise<sensor_msgs::Temperature>(\"/temperature\",1);\n\n    ros::Rate r(10);\n\n    while(ros::ok())\n    {\n        sensor_msgs::Temperature msg;\n        pub.publish(msg);\n\n        r.sleep();\n        ros::spinOnce();\n    }\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/src/clients/cl_led/cl_led.cpp",
    "content": "/*****************************************************************************************************************\n * ReelRobotix Inc. - Software License Agreement      Copyright (c) 2018\n * \t Authors: Pablo Inigo Blasco, Brett Aldrich\n *\n ******************************************************************************************************************/\n#include <sm_dance_bot_strikes_back/clients/cl_led/cl_led.h>\n//#include <pluginlib/class_list_macros.h>\n\nnamespace sm_dance_bot_strikes_back\n{\nnamespace cl_led\n{\n\nClLED::ClLED(std::string actionServerName) : Base(actionServerName)\n{\n}\n\nstd::string ClLED::getName() const\n{\n    return \"TOOL ACTION CLIENT\";\n}\n\nClLED::~ClLED()\n{\n}\n} // namespace cl_led\n\n//PLUGINLIB_EXPORT_CLASS(cl_led::ClLED, smacc::ISmaccComponent)\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/src/sm_dance_bot_strikes_back.cpp",
    "content": "#include <sm_dance_bot_strikes_back/sm_dance_bot_strikes_back.h>\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"dance_bot_strikes_back\");\n    ros::NodeHandle nh;\n\n    ros::Duration(5).sleep();\n    smacc::run<SmDanceBotStrikesBack>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_dance_bot_strikes_back/urdf/empty.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_ferrari\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_ferrari)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client eg_conditional_generator)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_ferrari_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_ferrari_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n add_executable(temperature_sensor_node_${PROJECT_NAME} servers/temperature_sensor_node/src/temperature_sensor_node.cpp)\n set_target_properties(temperature_sensor_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"temperature_sensor_node\")\n\n target_link_libraries(temperature_sensor_node_${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node temperature_sensor_node_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_ferrari.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\n install(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_ferrari/docs/smacc_state_machine_20200923-204005.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A simple, but complete state machine example. We highly recommend using this example as a starting point for users state machine projects.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__three__some.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_ferrari sm_ferrari.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/config/sm_three_some_config.yaml",
    "content": "SmFerrari:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/Float32.h>\n\nnamespace sm_ferrari\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::Float32>\n{\n    public:\n    ClSubscriber(std::string topicname):\n        smacc::client_bases::SmaccSubscriberClient<std_msgs::Float32>(topicname)\n    {\n    }\n};\n} // namespace client_1\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/clients/cl_subscriber/client_behaviors/cb_my_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_ferrari/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_ferrari\n{\nnamespace cl_subscriber\n{\n\ntemplate <typename TSource, typename TOrthogonal>\nstruct EvMyBehavior: sc::event<EvMyBehavior<TSource, TOrthogonal>>\n{\n\n};\n\nclass CbMySubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    void onEntry()\n    {\n        ClSubscriber* client;\n        this->requiresClient(client);\n\n        client->onMessageReceived(&CbMySubscriberBehavior::onMessageReceived, this);\n    }\n\n    template <typename TOrthogonal, typename TSourceObject>\n    void onOrthogonalAllocation()\n    {\n        postMyEvent_ = [=]{this->postEvent<EvMyBehavior<TSourceObject, TOrthogonal>>();};\n    }\n\n    void onMessageReceived(const std_msgs::Float32& msg)\n    {\n        if(msg.data > 30)\n        {\n            ROS_INFO(\"[CbMySubscriberBehavior] received message from topic with value > 30. Posting event!\");\n            this->postMyEvent_();\n        }\n    }\n\n    std::function<void()> postMyEvent_;\n};\n} // namespace cl_subscriber\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/mode_states/ms_recover.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ferrari\n{\n// STATE DECLARATION\nclass MsRecover : public smacc::SmaccState<MsRecover, SmFerrari>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvToDeep, sc::deep_history<MsRun::LastDeepState>, SUCCESS>\n\n   >reactions;\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/mode_states/ms_run.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ferrari\n{\n// STATE DECLARATION\nclass MsRun : public smacc::SmaccState<MsRun, SmFerrari, StState1>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_ferrari\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/orthogonals/or_subscriber.h",
    "content": "#pragma once\n\n#include <sm_ferrari/clients/cl_subscriber/cl_subscriber.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_ferrari\n{\nusing namespace sm_ferrari::cl_subscriber;\n\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto subscriber_client = this->createClient<ClSubscriber>(\"/temperature\");\n        subscriber_client->initialize();\n    }\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_ferrari\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n#include <std_msgs/String.h>\n\nnamespace sm_ferrari\n{\nusing namespace cl_ros_publisher;\n\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto ros_publisher_client = this->createClient<ClRosPublisher>();\n        ros_publisher_client->initialize();\n    }\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/sm_ferrari.h",
    "content": "#pragma once\n\n#include <smacc/smacc.h>\n\n// CLIENTS\n//#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n//#include \"orthogonals/or_timer.h\"\n//#include \"orthogonals/or_updatable_publisher.h\"\n#include \"orthogonals/or_subscriber.h\"\n#include \"orthogonals/or_keyboard.h\"\n\n//using namespace cl_ros_timer;\n//using namespace cl_ros_publisher;\nusing namespace cl_keyboard;\n\nusing namespace sm_ferrari::cl_subscriber;\n\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n#include \"clients/cl_subscriber/client_behaviors/cb_my_subscriber_behavior.h\"\n\n//#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n//#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\n//STATE REACTORS\n//#include <sr_all_events_go/sr_all_events_go.h>\n#include <eg_conditional_generator/eg_conditional_generator.h>\n\nusing namespace smacc;\nusing namespace smacc::state_reactors;\nusing namespace smacc::default_events;\nusing namespace smacc::event_generators;\n\nnamespace sm_ferrari\n{\n//SUPERSTATES\nnamespace SS1\n{\nclass Ss1;\n} // namespace SS1\n\n//SUPERSTATES\nnamespace SS2\n{\nclass Ss2;\n} // namespace SS1\n\n\n//STATES\nclass StState1; // first state specially needs a forward declaration\nclass StState2;\nclass StState3;\nclass StState4;\n\nclass MsRun;\nclass MsRecover;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\n// STATE MACHINE\nstruct SmFerrari\n    : public smacc::SmaccStateMachineBase<SmFerrari, MsRun>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        //this->createOrthogonal<OrTimer>();\n        //this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_ferrari\n\n// MODE STATES\n#include <sm_ferrari/mode_states/ms_run.h>\n#include <sm_ferrari/mode_states/ms_recover.h>\n\n//STATES\n#include <sm_ferrari/states/st_state_1.h>\n#include <sm_ferrari/states/st_state_2.h>\n#include <sm_ferrari/states/st_state_3.h>\n#include <sm_ferrari/states/st_state_4.h>\n\n#include <sm_ferrari/superstates/ss_superstate_1.h>\n#include <sm_ferrari/superstates/ss_superstate_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/inner_states/sti_state_1.h",
    "content": "namespace sm_ferrari\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState1 : smacc::SmaccState<StiState1, SS>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiState1>, StiState2, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiState1::loopWhileCondition);\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/inner_states/sti_state_2.h",
    "content": "namespace sm_ferrari\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState2 : smacc::SmaccState<StiState2, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  //Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiState3, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiState3, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiState1, PREVIOUS>,\n  Transition<EvMyBehavior<CbMySubscriberBehavior, OrSubscriber>, StiState3, NEXT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    // configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    // configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrSubscriber, CbMySubscriberBehavior>();\n    // configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n     configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/inner_states/sti_state_3.h",
    "content": "namespace sm_ferrari\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState3 : smacc::SmaccState<StiState3, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  //Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiState1, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiState2, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiState1, NEXT>,\n  Transition<EvMyBehavior<CbMySubscriberBehavior, OrSubscriber>, StiState1, NEXT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    //configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    //configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrSubscriber, CbMySubscriberBehavior>();\n    //configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/st_state_1.h",
    "content": "namespace sm_ferrari\n{\n// STATE DECLARATION\nstruct StState1 : smacc::SmaccState<StState1, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    //Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StState2, TIMEOUT>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1, PREVIOUS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StState2, NEXT>,\n    Transition<EvMyBehavior<CbMySubscriberBehavior, OrSubscriber>, StState2, NEXT>\n    //, Transition<EvFail, MsRecover, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        //configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        //configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrSubscriber, CbMySubscriberBehavior>();\n        //configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/st_state_2.h",
    "content": "namespace sm_ferrari\n{\n    // STATE DECLARATION\n    struct StState2 : smacc::SmaccState<StState2, MsRun>, smacc::ISmaccUpdatable\n    {\n        using SmaccState::SmaccState;\n\n        // DECLARE CUSTOM OBJECT TAGS\n        struct TIMEOUT : SUCCESS\n        {\n        };\n        struct NEXT : SUCCESS\n        {\n        };\n        struct PREVIOUS : ABORT\n        {\n        };\n\n        // TRANSITION TABLE\n        typedef mpl::list<\n\n            //Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StState3, TIMEOUT>,\n            //Transition<EvAllGo<SrAllEventsGo>, StState3>,\n            // Keyboard events\n            Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StState1, PREVIOUS>,\n            Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StState3, NEXT>,\n            Transition<EvMyBehavior<CbMySubscriberBehavior, OrSubscriber>, StState3, NEXT>,\n            Transition<EvTrue<EgConditionalGenerator, StState2>, StState3, NEXT>\n\n            >\n            reactions;\n\n        static int k;\n\n        // STATE FUNCTIONS\n        static void staticConfigure()\n        {\n            //configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n            //configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n            configure_orthogonal<OrSubscriber, CbMySubscriberBehavior>();\n            //configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n            configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n\n            // Create State Reactor\n            //auto sbAll = static_createStateReactor<SrAllEventsGo>();\n            //sbAll->addInputEvent<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>>();\n            //sbAll->addInputEvent<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>>();\n            //sbAll->addInputEvent<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>>();\n            //sbAll->setOutputEvent<EvAllGo<SrAllEventsGo>>();\n\n            static_createEventGenerator<EgConditionalGenerator>(ConditionalGeneratorMode::ON_UPDATE);\n        }\n\n        void runtimeConfigure()\n        {\n            k = 0;\n\n            auto eg = this->getEventGenerator<EgConditionalGenerator>();\n            eg->setPredicateFunction([=] { return this->eventGeneratorPredicate(); });\n        }\n\n        static bool eventGeneratorPredicate()\n        {\n            auto res = k > 300;\n            ROS_INFO(\"[State2] checking k: %d  > 300 == %d\", k, res);\n            ros::Duration(0.01).sleep();\n            return res;\n        }\n\n        virtual void update() override\n        {\n            k++;\n            ROS_INFO(\"[State2] internally updating k: %d\", k);\n        }\n\n        void onEntry()\n        {\n            ROS_INFO(\"On Entry!\");\n        }\n\n        void onExit()\n        {\n            ROS_INFO(\"On Exit!\");\n        }\n    };\n\n    int StState2::k = 0;\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/st_state_3.h",
    "content": "namespace sm_ferrari\n{\n// STATE DECLARATION\nstruct StState3 : smacc::SmaccState<StState3, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    //Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SS1::Ss1, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SS1::Ss1>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StState2, PREVIOUS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1, NEXT>,\n    Transition<EvMyBehavior<CbMySubscriberBehavior, OrSubscriber>, SS1::Ss1, NEXT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        // configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        // configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrSubscriber, CbMySubscriberBehavior>();\n\n        // configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/states/st_state_4.h",
    "content": "namespace sm_ferrari\n{\n// STATE DECLARATION\nstruct StState4 : smacc::SmaccState<StState4, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/superstates/ss_superstate_1.h",
    "content": "namespace sm_ferrari\n{\nnamespace SS1\n{\nnamespace sm_ferrari\n{\nnamespace inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiState1;\nclass StiState2;\nclass StiState3;\n} // namespace ss1_states\n} // namespace sm_ferrari\n\nusing namespace sm_ferrari::inner_states;\n\n// STATE DECLARATION\nstruct Ss1 : smacc::SmaccState<Ss1, MsRun, StiState1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiState1>, SS2::Ss2>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS1::Ss1;\n\n#include <sm_ferrari/states/inner_states/sti_state_1.h>\n#include <sm_ferrari/states/inner_states/sti_state_2.h>\n#include <sm_ferrari/states/inner_states/sti_state_3.h>\n\n} // namespace SS1\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/include/sm_ferrari/superstates/ss_superstate_2.h",
    "content": "namespace sm_ferrari\n{\nnamespace SS2\n{\nnamespace sm_ferrari\n{\nnamespace inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiState1;\nclass StiState2;\nclass StiState3;\n} // namespace ss1_states\n} // namespace sm_ferrari\n\nusing namespace sm_ferrari::inner_states;\n\n// STATE DECLARATION\nstruct Ss2 : smacc::SmaccState<Ss2, MsRun, StiState1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiState1>, StState4>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS2::Ss2;\n\n#include <sm_ferrari/states/inner_states/sti_state_1.h>\n#include <sm_ferrari/states/inner_states/sti_state_2.h>\n#include <sm_ferrari/states/inner_states/sti_state_3.h>\n\n} // namespace SS1\n} // namespace sm_ferrari\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/launch/sm_ferrari.launch",
    "content": "<launch>\n    <arg name=\"debug\" default=\"false\"/>\n\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -e\" />\n\n    <node pkg=\"sm_ferrari\" type=\"sm_ferrari_node\" name=\"sm_ferrari\" launch-prefix=\"$(arg server_nodes_xterms)\" unless=\"$(arg debug)\"/>\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"sm_ferrari\" type=\"temperature_sensor_node\" name=\"temperature_sensor_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_ferrari</name>\n    <version>1.4.16</version>\n  <description>The sm_ferrari package</description>\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n  <license>BSD-3</license>\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_ferrari</url> -->\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>eg_conditional_generator</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n  <export>\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/servers/temperature_sensor_node/src/temperature_sensor_node.cpp",
    "content": "#include <ros/ros.h>\n#include <std_msgs/Float32.h>\n\nint main(int argc, char** argv)\n{\n    ros::init(argc,argv, \"temperature_sensor_node\");\n\n    ros::NodeHandle nh;\n    auto pub = nh.advertise<std_msgs::Float32>(\"/temperature\",1);\n\n    ros::Rate r(30);\n\n    int i=0;\n    while(ros::ok())\n    {\n        std_msgs::Float32 msg;\n        // temperatures varies sinoidally from -20 to 20 degrees, but sporadically it has 32 deg\n        if (i %100 ==0 )\n            msg.data = 32;\n        else\n            msg.data = 20 * sin(0.1 * ros::Time::now().toSec());\n\n        pub.publish(msg);\n\n        r.sleep();\n        ros::spinOnce();\n        i++;\n    }\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ferrari/src/sm_ferrari_node.cpp",
    "content": "#include <sm_ferrari/sm_ferrari.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_ferrari_node\");\n    smacc::run<sm_ferrari::SmFerrari>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_packml\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_packml)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_packML_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_packml_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_packML.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_packml/docs/smacc_state_machine_20200205-104849.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> This example implements the 17 state, PackML Interface State Model, shown on page 17, Fig.9 of the <a href=\"http://omac.org/wp-content/uploads/2016/11/PackML_Unit_Machine_Implementation_Guide-V1-00.pdf\">PackML Unit Machine Implementation Guide</a>.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__packml.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_packml sm_packml.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/config/sm_packml_config.yaml",
    "content": "SmPackML:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nnamespace sm_packml\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\n};\n} // namespace client_1\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_packml/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_packml\n{\nnamespace cl_subscriber\n{\nclass CbDefaultSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n    //-------------------------------------------------------------------------------\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_packml/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_packml\n{\nnamespace cl_subscriber\n{\nclass CbWatchdogSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/mode_states/ms_run.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_packml\n{\n// STATE DECLARATION\nclass MsRun : public smacc::SmaccState<MsRun, SmPackML, StStarting>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/mode_states/ms_stop.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_packml\n{\n// STATE DECLARATION\nclass MsStop : public smacc::SmaccState<MsStop, SmPackML, StStopping>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n //  typedef mpl::list<\n\n  // >reactions;\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_packml\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/orthogonals/or_subscriber.h",
    "content": "#pragma once\n\n#include <sm_packml/clients/cl_subscriber/cl_subscriber.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_packml\n{\nusing namespace sm_packml::cl_subscriber;\n\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto subscriber_client = this->createClient<ClSubscriber>();\n        subscriber_client->initialize();\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_packml\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n#include <std_msgs/String.h>\n\nnamespace sm_packml\n{\nusing namespace cl_ros_publisher;\n\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto ros_publisher_client = this->createClient<ClRosPublisher>();\n        ros_publisher_client->initialize();\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/sm_packml.h",
    "content": "#pragma once\n\n#include <ros/ros.h>\n#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n#include <sm_packml/orthogonals/or_timer.h>\n#include <sm_packml/orthogonals/or_updatable_publisher.h>\n#include <sm_packml/orthogonals/or_subscriber.h>\n#include <sm_packml/orthogonals/or_keyboard.h>\n\nusing namespace cl_ros_timer;\nusing namespace cl_ros_publisher;\nusing namespace cl_keyboard;\n\nusing namespace sm_packml::cl_subscriber;\n\n//CLIENT BEHAVIORS\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n\n#include <sm_packml/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h>\n#include <sm_packml/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h>\n\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n\n#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n\nusing namespace smacc;\nusing namespace smacc::state_reactors;\nusing namespace smacc::default_events;\n\nnamespace sm_packml\n{\n\n//STATES\nclass StIdle; // first state specially needs a forward declaration\nclass StStarting;\nclass StExecute;\nclass StCompleting;\nclass StComplete;\nclass StResetting;\nclass StUnholding;\nclass StHeld;\nclass StHolding;\nclass StSuspending;\nclass StSuspended;\nclass StUnsuspending;\nclass StAborting;\nclass StAborted;\nclass StClearing;\nclass StStopping;\nclass StStopped;\n\nclass MsRun;\nclass MsStop;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\nstruct EvEStop : sc::event<EvEStop>\n{\n};\n\n// STATE MACHINE\nstruct SmPackML\n    : public smacc::SmaccStateMachineBase<SmPackML, MsRun>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_packml\n\n// MODE STATES\n#include <sm_packml/mode_states/ms_run.h>\n#include <sm_packml/mode_states/ms_stop.h>\n\n//STATES\n#include <sm_packml/states/st_idle.h>\n#include <sm_packml/states/st_starting.h>\n#include <sm_packml/states/st_execute.h>\n#include <sm_packml/states/st_completing.h>\n#include <sm_packml/states/st_complete.h>\n#include <sm_packml/states/st_resetting.h>\n#include <sm_packml/states/st_unholding.h>\n#include <sm_packml/states/st_held.h>\n#include <sm_packml/states/st_holding.h>\n#include <sm_packml/states/st_suspending.h>\n#include <sm_packml/states/st_suspended.h>\n#include <sm_packml/states/st_unsuspending.h>\n#include <sm_packml/states/st_aborting.h>\n#include <sm_packml/states/st_aborted.h>\n#include <sm_packml/states/st_clearing.h>\n#include <sm_packml/states/st_stopping.h>\n#include <sm_packml/states/st_stopped.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_aborted.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StAborted : smacc::SmaccState<StAborted, SmPackML>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct CLEAR : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StClearing, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_aborting.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StAborting : smacc::SmaccState<StAborting, SmPackML>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StAborted, SUCCESS>\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_clearing.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StClearing : smacc::SmaccState<StClearing, MsStop>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StStopped, SUCCESS>\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_complete.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StComplete : smacc::SmaccState<StComplete, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct RESET : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StResetting, RESET> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_completing.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StCompleting : smacc::SmaccState<StCompleting, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StComplete>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StComplete, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_execute.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StExecute : smacc::SmaccState<StExecute, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct HOLD : PREEMPT{};\n    struct SUSPEND : PREEMPT{};\n    struct STOP : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SS1::Ss1>,\n    // Keyboard events\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StCompleting, SUCCESS>,\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StHolding, HOLD>,\n    Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, StSuspending, SUSPEND>,\n    Transition<EvKeyPressT<CbDefaultKeyboardBehavior, OrKeyboard>, MsStop, STOP>,\n    Transition<EvKeyPressE<CbDefaultKeyboardBehavior, OrKeyboard>, StAborting, ABORT>\n\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_held.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StHeld : smacc::SmaccState<StHeld, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct UNHOLD : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StUnholding, UNHOLD> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_holding.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StHolding : smacc::SmaccState<StHolding, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StHeld, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_idle.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StIdle : smacc::SmaccState<StIdle, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct START : SUCCESS{};\n\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StStarting, START> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_resetting.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StResetting : smacc::SmaccState<StResetting, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StIdle, SUCCESS> //,\n    // Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StStarting>,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_starting.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StStarting : smacc::SmaccState<StStarting, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<EvAllGo<SrAllEventsGo>, StExecute>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StIdle>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StExecute, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n\n        // Create State Reactor\n\n\n        auto sbAll = static_createStateReactor<SrAllEventsGo,\n                                                smacc::state_reactors::EvAllGo<SrAllEventsGo>,\n                                                mpl::list<EvTimer<CbTimer, OrTimer>, EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>> >();\n\n        //auto sbAll = static_createStateReactor<SrAllEventsGo>();\n        //sbAll->addInputEvent<EvTimer<CbTimer, OrTimer>>();\n        //sbAll->addInputEvent<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>>();\n        //sbAll->setOutputEvent<EvAllGo<SrAllEventsGo>>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_stopped.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StStopped : smacc::SmaccState<StStopped, MsStop>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct RESET : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StResetting, RESET> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_stopping.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StStopping : smacc::SmaccState<StStopping, MsStop>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StStopped, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_suspended.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StSuspended : smacc::SmaccState<StSuspended, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct UNSUSPEND : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StUnsuspending, UNSUSPEND> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_suspending.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StSuspending : smacc::SmaccState<StSuspending, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StSuspended, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_unholding.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StUnholding : smacc::SmaccState<StUnholding, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StExecute, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/include/sm_packml/states/st_unsuspending.h",
    "content": "namespace sm_packml\n{\n// STATE DECLARATION\nstruct StUnsuspending : smacc::SmaccState<StUnsuspending, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrTimer>, StStarting>,\n    // Keyboard events\n    // Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StExecute, SUCCESS> //,\n    // Transition<EvFail, MsStop, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimer>();\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n};\n} // namespace sm_packml\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/launch/sm_packML.launch",
    "content": "<launch>\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <rosparam command=\"load\" file=\"$(find sm_packml)/config/sm_packml_config.yaml\" />\n    <node pkg=\"sm_packml\" type=\"sm_packML_node\" name=\"sm_packml\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_packml</name>\n    <version>1.4.16</version>\n  <description>The sm_packml package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_packml</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_packml/src/sm_packml_node.cpp",
    "content": "#include <sm_packml/sm_packml.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"packML\");\n    smacc::run<sm_packml::SmPackML>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_respira_1\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_respira_1)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_three_some_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_respira_1_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_respira_1.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_respira_1/docs/smacc_state_machine_20200513-165805.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A state machine sketch for the RespiraWorks Ventilator<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__starcraft__ai.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_respira_1 sm_respira_1.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/config/sm_respira_1_config.yaml",
    "content": "SmRespira1:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nnamespace sm_respira_1\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\n};\n} // namespace client_1\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_respira_1/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_respira_1\n{\nnamespace cl_subscriber\n{\nclass CbDefaultSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n    //-------------------------------------------------------------------------------\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_respira_1/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_respira_1\n{\nnamespace cl_subscriber\n{\nclass CbWatchdogSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/mode_states/ms_calibration.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_respira_1\n{\n// STATE DECLARATION\nclass MsCalibration : public smacc::SmaccState<MsCalibration, SmRespira1, StCalibrationStep1>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/mode_states/ms_leaky_lung.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_respira_1\n{\n// STATE DECLARATION\nclass MsLeakyLung : public smacc::SmaccState<MsLeakyLung, SmRespira1, StLeakyLungStep1>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/mode_states/ms_patient_obstruction.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_respira_1\n{\n// STATE DECLARATION\nclass MsPatientObstruction : public smacc::SmaccState<MsPatientObstruction, SmRespira1, StPatientObstructionStep1>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/mode_states/ms_run.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_respira_1\n{\n// STATE DECLARATION\nclass MsRun : public smacc::SmaccState<MsRun, SmRespira1, StObserve>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/mode_states/ms_shutdown.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_respira_1\n{\n// STATE DECLARATION\nclass MsShutdown : public smacc::SmaccState<MsShutdown, SmRespira1, StSystemShutdown>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_respira_1\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/orthogonals/or_subscriber.h",
    "content": "#pragma once\n\n#include <sm_respira_1/clients/cl_subscriber/cl_subscriber.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_respira_1\n{\nusing namespace sm_respira_1::cl_subscriber;\n\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto subscriber_client = this->createClient<ClSubscriber>();\n        subscriber_client->initialize();\n    }\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_respira_1\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.1));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n#include <std_msgs/String.h>\n\nnamespace sm_respira_1\n{\nusing namespace cl_ros_publisher;\n\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto ros_publisher_client = this->createClient<ClRosPublisher>();\n        ros_publisher_client->initialize();\n    }\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/sm_respira_1.h",
    "content": "#pragma once\n\n#include <ros/ros.h>\n#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n#include <sm_respira_1/orthogonals/or_timer.h>\n#include <sm_respira_1/orthogonals/or_updatable_publisher.h>\n#include <sm_respira_1/orthogonals/or_subscriber.h>\n#include <sm_respira_1/orthogonals/or_keyboard.h>\n\nusing namespace cl_ros_timer;\nusing namespace cl_ros_publisher;\nusing namespace cl_keyboard;\nusing namespace sm_respira_1::cl_subscriber;\n\n//CLIENT BEHAVIORS\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n\n#include <sm_respira_1/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h>\n#include <sm_respira_1/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h>\n\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n\n//#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n\nusing namespace smacc;\nusing namespace smacc::state_reactors;\nusing namespace smacc::default_events;\n\nnamespace sm_respira_1\n{\n//SUPERSTATES\nclass SsACCycle;\nnamespace ac_cycle_inner_states\n{\nclass StiACCycleLoop;\nclass StiACCycleInspire;\nclass StiACCyclePlateau;\nclass StiACCycleExpire;\nclass StiACCycleDwell;\n}\n\nclass SsCMVCycle;\n\nnamespace cmv_cycle_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiCMVCycleLoop;\nclass StiCMVCycleInspire;\nclass StiCMVCyclePlateau;\nclass StiCMVCycleExpire;\nclass StiCMVCycleDwell;\n}\n\n\nclass SsPCCycle;\nnamespace pc_cycle_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiPCCycleLoop;\nclass StiPCCycleInspire;\nclass StiPCCyclePlateau;\nclass StiPCCycleExpire;\nclass StiPCCycleDwell;\n}\n\nclass SsPSCycle;\nnamespace ps_cycle_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiPSCycleLoop;\nclass StiPSCycleInspire;\nclass StiPSCyclePlateau;\nclass StiPSCycleExpire;\nclass StiPSCycleDwell;\n}\n\n//STATES\nclass StObserve;\nclass StLeakyLungStep1;\nclass StLeakyLungStep2;\nclass StLeakyLungStep3;\nclass StPatientObstructionStep1;\nclass StPatientObstructionStep2;\nclass StCalibrationStep1;\nclass StSystemShutdown;\n\n//MODE STATES\nclass MsRun;\nclass MsLeakyLung;\nclass MsPatientObstruction;\nclass MsCalibration;\nclass MsShutdown;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\n// STATE MACHINE\nstruct SmRespira1\n    : public smacc::SmaccStateMachineBase<SmRespira1, MsRun>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_respira_1\n\n// MODE STATES\n#include <sm_respira_1/mode_states/ms_run.h>\n#include <sm_respira_1/mode_states/ms_leaky_lung.h>\n#include <sm_respira_1/mode_states/ms_patient_obstruction.h>\n#include <sm_respira_1/mode_states/ms_calibration.h>\n#include <sm_respira_1/mode_states/ms_shutdown.h>\n\n//STATES\n#include <sm_respira_1/states/st_observe.h>\n#include <sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_1.h>\n#include <sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_2.h>\n#include <sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_3.h>\n#include <sm_respira_1/states/ms_patient_obstruction_inner_states/st_patient_obstruction_step_1.h>\n#include <sm_respira_1/states/ms_patient_obstruction_inner_states/st_patient_obstruction_step_2.h>\n#include <sm_respira_1/states/ms_calibration_inner_states/st_calibration_step_1.h>\n#include <sm_respira_1/states/ms_shutdown_inner_states/st_system_shutdown.h>\n\n#include <sm_respira_1/superstates/ss_ac_cycle.h>\n#include <sm_respira_1/superstates/ss_cmv_cycle.h>\n#include <sm_respira_1/superstates/ss_pc_cycle.h>\n#include <sm_respira_1/superstates/ss_ps_cycle.h>\n\n//ss_ac_cycle\n#include <sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_loop.h>\n#include <sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_inspire.h>\n#include <sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_plateau.h>\n#include <sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_expire.h>\n#include <sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_dwell.h>\n\n//ss_cmv_cycle\n#include <sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_loop.h>\n#include <sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_inspire.h>\n#include <sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_plateau.h>\n#include <sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_expire.h>\n#include <sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_dwell.h>\n\n//ss_pc_cycle\n#include <sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_loop.h>\n#include <sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_inspire.h>\n#include <sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_plateau.h>\n#include <sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_expire.h>\n#include <sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_dwell.h>\n\n//ss_ps_cycle\n#include <sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_loop.h>\n#include <sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_inspire.h>\n#include <sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_plateau.h>\n#include <sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_expire.h>\n#include <sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_dwell.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_dwell.h",
    "content": "namespace sm_respira_1\n{\nnamespace ac_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiACCycleDwell : smacc::SmaccState<StiACCycleDwell, SsACCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiACCycleLoop, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleExpire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleLoop, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_expire.h",
    "content": "namespace sm_respira_1\n{\nnamespace ac_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiACCycleExpire : smacc::SmaccState<StiACCycleExpire, SsACCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiACCycleDwell, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCyclePlateau, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleDwell, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_inspire.h",
    "content": "namespace sm_respira_1\n{\nnamespace ac_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiACCycleInspire : smacc::SmaccState<StiACCycleInspire, SsACCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiACCyclePlateau, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCyclePlateau, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleLoop, PREVIOUS>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_loop.h",
    "content": "namespace sm_respira_1\n{\nnamespace ac_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiACCycleLoop : smacc::SmaccState<StiACCycleLoop, SsACCycle>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiACCycleLoop>, StiACCycleInspire, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SsACCycle>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiACCycleLoop::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ac_cycle_inner_states/sti_ac_cycle_plateau.h",
    "content": "namespace sm_respira_1\n{\nnamespace ac_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiACCyclePlateau : smacc::SmaccState<StiACCyclePlateau, SsACCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiACCycleExpire, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleInspire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiACCycleExpire, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_dwell.h",
    "content": "namespace sm_respira_1\n{\nnamespace cmv_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiCMVCycleDwell : smacc::SmaccState<StiCMVCycleDwell, SsCMVCycle>\n{\n  using SmaccState::SmaccState;\n\n  // DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS\n  {\n  };\n  struct NEXT : SUCCESS\n  {\n  };\n  struct PREVIOUS : ABORT\n  {\n  };\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiCMVCycleLoop, TIMEOUT>,\n      Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleExpire, PREVIOUS>,\n      Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleLoop, NEXT>,\n\n      Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n      Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n};\n}  // namespace cmv_cycle_inner_states\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_expire.h",
    "content": "namespace sm_respira_1\n{\nnamespace cmv_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiCMVCycleExpire : smacc::SmaccState<StiCMVCycleExpire, SsCMVCycle>\n{\n  using SmaccState::SmaccState;\n\n  // DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS\n  {\n  };\n  struct NEXT : SUCCESS\n  {\n  };\n  struct PREVIOUS : ABORT\n  {\n  };\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiCMVCycleDwell, TIMEOUT>,\n      Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCyclePlateau, PREVIOUS>,\n      Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleDwell, NEXT>,\n\n      Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n      Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n};\n}  // namespace cmv_cycle_inner_states\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_inspire.h",
    "content": "namespace sm_respira_1\n{\nnamespace cmv_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiCMVCycleInspire : smacc::SmaccState<StiCMVCycleInspire, SsCMVCycle>\n{\n  using SmaccState::SmaccState;\n\n  // DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS\n  {\n  };\n  struct NEXT : SUCCESS\n  {\n  };\n  struct PREVIOUS : ABORT\n  {\n  };\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiCMVCyclePlateau, TIMEOUT>,\n      Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCyclePlateau, NEXT>,\n      Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleLoop, PREVIOUS>,\n\n      Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n      Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n};\n}  // namespace cmv_cycle_inner_states\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_loop.h",
    "content": "namespace sm_respira_1\n{\nnamespace cmv_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiCMVCycleLoop : smacc::SmaccState<StiCMVCycleLoop, SsCMVCycle>\n{\npublic:\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopContinue<StiCMVCycleLoop>, StiCMVCycleInspire, CONTINUELOOP>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SsCMVCycle>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count,\n             superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiCMVCycleLoop::loopWhileCondition);\n  }\n};\n}  // namespace cmv_cycle_inner_states\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/cmv_cycle_inner_states/sti_cmv_cycle_plateau.h",
    "content": "namespace sm_respira_1\n{\nnamespace cmv_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiCMVCyclePlateau : smacc::SmaccState<StiCMVCyclePlateau, SsCMVCycle>\n{\n  using SmaccState::SmaccState;\n\n  // DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS\n  {\n  };\n  struct NEXT : SUCCESS\n  {\n  };\n  struct PREVIOUS : ABORT\n  {\n  };\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiCMVCycleExpire, TIMEOUT>,\n      Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleInspire, PREVIOUS>,\n      Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiCMVCycleExpire, NEXT>,\n\n      Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n      Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n};\n}  // namespace cmv_cycle_inner_states\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_calibration_inner_states/st_calibration_step_1.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StCalibrationStep1 : smacc::SmaccState<StCalibrationStep1, MsCalibration>\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SsACCycle, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SsACCycle>,\n    // Keyboard events\n    Transition<EvKeyPressL<CbDefaultKeyboardBehavior, OrKeyboard>, MsRun, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_1.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StLeakyLungStep1 : smacc::SmaccState<StLeakyLungStep1, MsLeakyLung>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StLeakyLungStep2, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SsACCycle>,\n    // Keyboard events\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StLeakyLungStep2, SUCCESS>\n    // Transition<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>, SsCMVCycle, BUILD>,\n    // Transition<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>, SsPCCycle, ATTACK>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(50);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_2.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StLeakyLungStep2 : smacc::SmaccState<StLeakyLungStep2, MsLeakyLung>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StLeakyLungStep3, SUCCESS>\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SsACCycle>,\n    // Keyboard events\n    // Transition<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>, SsACCycle, MOVE>,\n    // Transition<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>, SsCMVCycle, BUILD>,\n    // Transition<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>, SsPCCycle, ATTACK>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(50);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_leaky_lung_inner_states/st_leaky_lung_step_3.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StLeakyLungStep3 : smacc::SmaccState<StLeakyLungStep3, MsLeakyLung>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, sc::deep_history<MsRun::LastDeepState>, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(50);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_patient_obstruction_inner_states/st_patient_obstruction_step_1.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StPatientObstructionStep1 : smacc::SmaccState<StPatientObstructionStep1, MsPatientObstruction>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StPatientObstructionStep2, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(50);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_patient_obstruction_inner_states/st_patient_obstruction_step_2.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StPatientObstructionStep2 : smacc::SmaccState<StPatientObstructionStep2, MsPatientObstruction>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, sc::deep_history<MsRun::LastDeepState>, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(50);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ms_shutdown_inner_states/st_system_shutdown.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StSystemShutdown : smacc::SmaccState<StSystemShutdown, MsShutdown>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SsACCycle, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SsACCycle>,\n    // Keyboard events\n    // Transition<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>, SsACCycle, MOVE>,\n    // Transition<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>, SsCMVCycle, BUILD>,\n    // Transition<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>, SsPCCycle, ATTACK>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_dwell.h",
    "content": "namespace sm_respira_1\n{\nnamespace pc_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPCCycleDwell : smacc::SmaccState<StiPCCycleDwell, SsPCCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPCCycleLoop, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleExpire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleLoop, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_expire.h",
    "content": "namespace sm_respira_1\n{\nnamespace pc_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPCCycleExpire : smacc::SmaccState<StiPCCycleExpire, SsPCCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPCCycleDwell, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCyclePlateau, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleDwell, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_inspire.h",
    "content": "namespace sm_respira_1\n{\nnamespace pc_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPCCycleInspire : smacc::SmaccState<StiPCCycleInspire, SsPCCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPCCyclePlateau, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCyclePlateau, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleLoop, PREVIOUS>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_loop.h",
    "content": "namespace sm_respira_1\n{\nnamespace pc_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPCCycleLoop : smacc::SmaccState<StiPCCycleLoop, SsPCCycle>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiPCCycleLoop>, StiPCCycleInspire, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SsPCCycle>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiPCCycleLoop::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/pc_cycle_inner_states/sti_pc_cycle_plateau.h",
    "content": "namespace sm_respira_1\n{\nnamespace pc_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPCCyclePlateau : smacc::SmaccState<StiPCCyclePlateau, SsPCCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPCCycleExpire, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleInspire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPCCycleExpire, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_dwell.h",
    "content": "namespace sm_respira_1\n{\nnamespace ps_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPSCycleDwell : smacc::SmaccState<StiPSCycleDwell, SsPSCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPSCycleLoop, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleExpire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleLoop, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_expire.h",
    "content": "namespace sm_respira_1\n{\nnamespace ps_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPSCycleExpire : smacc::SmaccState<StiPSCycleExpire, SsPSCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPSCycleDwell, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCyclePlateau, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleDwell, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_inspire.h",
    "content": "namespace sm_respira_1\n{\nnamespace ps_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPSCycleInspire : smacc::SmaccState<StiPSCycleInspire, SsPSCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPSCyclePlateau, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCyclePlateau, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleLoop, PREVIOUS>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(40);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_loop.h",
    "content": "namespace sm_respira_1\n{\nnamespace ps_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPSCycleLoop : smacc::SmaccState<StiPSCycleLoop, SsPSCycle>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiPSCycleLoop>, StiPSCycleInspire, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SsPSCycle>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiPSCycleLoop::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/ps_cycle_inner_states/sti_ps_cycle_plateau.h",
    "content": "namespace sm_respira_1\n{\nnamespace ps_cycle_inner_states\n{\n// STATE DECLARATION\nstruct StiPSCyclePlateau : smacc::SmaccState<StiPSCyclePlateau, SsPSCycle>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiPSCycleExpire, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleInspire, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiPSCycleExpire, NEXT>,\n\n  Transition<EvKeyPressX<CbDefaultKeyboardBehavior, OrKeyboard>, MsLeakyLung, ABORT>,\n  Transition<EvKeyPressZ<CbDefaultKeyboardBehavior, OrKeyboard>, MsPatientObstruction, ABORT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/states/st_observe.h",
    "content": "namespace sm_respira_1\n{\n// STATE DECLARATION\nstruct StObserve : smacc::SmaccState<StObserve, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct AC_CYCLE : SUCCESS{};\n    struct CMV_CYCLE : SUCCESS{};\n    struct PC_CYCLE : SUCCESS{};\n    struct PS_CYCLE : SUCCESS{};\n    struct SHUTDOWN : SUCCESS{};\n    struct CALIBRATION : PREEMPT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SsACCycle, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SsACCycle>,\n    // Keyboard events\n    Transition<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>, SsACCycle, AC_CYCLE>,\n    Transition<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>, SsCMVCycle, CMV_CYCLE>,\n    Transition<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>, SsPCCycle, PC_CYCLE>,\n    Transition<EvKeyPressD<CbDefaultKeyboardBehavior, OrKeyboard>, SsPSCycle, PS_CYCLE>,\n\n    Transition<EvKeyPressL<CbDefaultKeyboardBehavior, OrKeyboard>, MsCalibration, CALIBRATION>,\n    Transition<EvKeyPressS<CbDefaultKeyboardBehavior, OrKeyboard>, MsShutdown, SHUTDOWN>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/superstates/ss_ac_cycle.h",
    "content": "namespace sm_respira_1\n{\nusing namespace sm_respira_1::ac_cycle_inner_states;\n\n// STATE DECLARATION\nstruct SsACCycle : smacc::SmaccState<SsACCycle, MsRun, StiACCycleLoop>\n{\npublic:\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopEnd<StiACCycleLoop>, StObserve>\n\n      >\n      reactions;\n\n  // STATE VARIABLES\n  static constexpr int total_iterations()\n  {\n    return 1000;\n  }\n  int iteration_count = 0;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};  // namespace SS1\n\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/superstates/ss_cmv_cycle.h",
    "content": "namespace sm_respira_1\n{\n\nusing namespace sm_respira_1::cmv_cycle_inner_states;\n\n// STATE DECLARATION\nstruct SsCMVCycle : smacc::SmaccState<SsCMVCycle, MsRun, StiCMVCycleLoop>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiCMVCycleLoop>, StObserve>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 1000; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n} // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/superstates/ss_pc_cycle.h",
    "content": "namespace sm_respira_1\n{\nusing namespace sm_respira_1::pc_cycle_inner_states;\n\n// STATE DECLARATION\nstruct SsPCCycle : smacc::SmaccState<SsPCCycle, MsRun, StiPCCycleLoop>\n{\npublic:\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopEnd<StiPCCycleLoop>, StObserve>\n\n      >\n      reactions;\n\n  // STATE VARIABLES\n  static constexpr int total_iterations()\n  {\n    return 1000;\n  }\n  int iteration_count = 0;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/include/sm_respira_1/superstates/ss_ps_cycle.h",
    "content": "namespace sm_respira_1\n{\nusing namespace sm_respira_1::ps_cycle_inner_states;\n\n// STATE DECLARATION\nstruct SsPSCycle : smacc::SmaccState<SsPSCycle, MsRun, StiPSCycleLoop>\n{\npublic:\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvLoopEnd<StiPSCycleLoop>, StObserve>\n\n      >\n      reactions;\n\n  // STATE VARIABLES\n  static constexpr int total_iterations()\n  {\n    return 1000;\n  }\n  int iteration_count = 0;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n};\n\n}  // namespace sm_respira_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/launch/sm_respira_1.launch",
    "content": "<launch>\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -e\" />\n\n    <rosparam command=\"load\" file=\"$(find sm_respira_1_node)/config/sm_respira_1_node_config.yaml\" />\n    <node pkg=\"sm_respira_1\" type=\"sm_respira_1_node\" name=\"sm_respira_1\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_respira_1</name>\n    <version>1.4.16</version>\n  <description>The sm_respira_1 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_respira_1</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_respira_1/src/sm_respira_1_node.cpp",
    "content": "#include <sm_respira_1/sm_respira_1.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"respira_1\");\n    smacc::run<sm_respira_1::SmRespira1>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_ridgeback_barrel_search_1\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Merge branch 'master' of https://github.com/robosoft-ai/SMACC\n* Changing waypoints in sm_ridgeback_barrel_search_1\n* improving opencv2 box detection and also restoring sm_moveit example\n* fixing some visual issue in smacc opencv2 demo\n* Merge branch 'master' into melodic-devel\n* progress in opencv2 example\n* missing reference\n* Merge branch 'master' into melodic-devel\n* fixing opencv demos and other minor issues\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency and adding scrollbars\n* adding xterm dependency to examples\n* improving opencv example state machines with the debug image showing the rectangle of the detected object\n* Added Readme's to OpenCV SM's\n* Began to implement new folder structure\n* Renaming OpenCV Perception Node Mains\n* Tweaking OpenCV SM's\n* New OpenCV based SM's\n* Contributors: Brett Aldrich, Pablo Iñigo Blasco, Unknown, pablo.inigo.blasco, pibgeus\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_ridgeback_barrel_search_1)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin cv_bridge)\n\n## System dependencies are found with CMake's conventions\nfind_package(OpenCV REQUIRED COMPONENTS )\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_ridgeback_barrel_search_1\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_ridgeback_barrel_search_1.cpp)\ntarget_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES})\n\nadd_executable(opencv_perception_node_${PROJECT_NAME} servers/opencv_perception_node/opencv_perception_node.cpp)\nset_target_properties(opencv_perception_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"opencv_perception_node\")\n\ntarget_link_libraries(opencv_perception_node_${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# catkin_install_python(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS ${PROJECT_NAME}_node opencv_perception_node_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_ridgeback_barrel_search_1.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_ridgeback_barrel_search_1/docs/smacc_state_machine_20200822-022028.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> This example demonstrates the use of both OpenCV and MoveBase within the same state machine, with cross orthogonal communication between the navigation orthogonal and the perception orthogonal.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__moveit.html\">Doxygen Namespace & Class Reference</a>\n<br></br>\n\n<p align=\"center\">\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_ridgeback_barrel_search_1/docs/sm_ridgeback_barrel_search_1.jpg\" width=\"800\"/>\n </p>\n <br></br>\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_ridgeback_barrel_search_1 sm_ridgeback_barrel_search_1.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/backward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nBackwardLocalPlanner:\n    k_rho: -1.5 # linear distance to the goal gain, default = -1.0 (related with carrot distance)\n    k_alpha: -0.1\n    k_betta: -1.0\n    carrot_distance: 0.3 #meters default 0.5\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.015 # 0.025\n    yaw_goal_tolerance: 0.3\n    pure_spinning_straight_line_mode: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 6.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.157\n  xy_goal_tolerance: 0.25\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/costmap_common_params.yaml",
    "content": "\nmap_type: costmap\norigin_z: 0.0\nz_resolution: 1\nz_voxels: 2\n\nobstacle_range: 12.5\nraytrace_range: 3.0\n\npublish_voxel_map: false\ntransform_tolerance: 0.5\nmeter_scoring: true\n\nfootprint: [[0.48, -0.40], [0.48, 0.40], [-0.48, 0.40], [-0.48, -0.40]]\nfootprint_padding: 0.3\n\nplugins:\n- {name: obstacles_layer, type: \"costmap_2d::ObstacleLayer\"}\n- {name: inflater_layer, type: \"costmap_2d::InflationLayer\"}\n\nobstacles_layer:\n  observation_sources: scan\n  scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 10.5, raytrace_range: 3.0}\n\ninflater_layer:\n inflation_radius: 0.2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/forward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nForwardLocalPlanner:\n    k_rho: 1.0\n    k_alpha: -0.4\n    k_betta: -1.0\n    carrot_distance: 1.5 #meters\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.04\n    yaw_goal_tolerance: 0.01\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/global_costmap_params.yaml",
    "content": "global_costmap:\n  global_frame: odom\n  robot_base_frame: base_link\n  update_frequency: 20\n  publish_frequency: 5\n  width: 250.0\n  height: 120.0\n  resolution: 0.3\n  origin_x: -20.0\n  origin_y: -20.0\n  static_map: true\n  rolling_window: false\n  inflater_layer:\n    inflation_radius: 0.6\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: odom\n   robot_base_frame: base_link\n   update_frequency: 20.0\n   publish_frequency: 5.0\n   width: 10.0\n   height: 10.0\n   resolution: 0.05\n   static_map: false\n   rolling_window: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/move_base_client/waypoints_plan.yaml",
    "content": "waypoints:\n  # POINT intermediate\n  - position:\n      x: 95.77727932\n      y: 45.6510791306\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.246064998984\n      w: 0.969253329257\n\n  # point in the north\n  - position:\n      x: 107.077912308\n      y: 62.5425247432\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.258515919252\n      w: 0.966006997642\n  - position:\n      x: 2.84283538036\n      y: -7.32575383645\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.997535137155\n      w: 0.070168726239\n  - position:\n      x: -7.11926213432\n      y: -7.9932196137\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.439262428811\n      w: 0.898358791706\n  - position:\n      x: -9.28439676048\n      y: 1.41941615072\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: -0.228861605363\n      w: 0.973458969649\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/navigation.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 0\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Odometry1/Shape1\n        - /TF1/Frames1\n        - /SmaccRvizDisplay1\n        - /Image1\n      Splitter Ratio: 0.3861111104488373\n    Tree Height: 359\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nPreferences:\n  PromptSaveOnExit: true\nToolbars:\n  toolButtonStyle: 2\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 209; 209; 214\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 40\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.4000000059604645\n      Class: rviz/RobotModel\n      Collision Enabled: false\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        axle_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        camera_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        chassis_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        mid_mount:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        rear_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        top_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.25\n      Name: Axes\n      Radius: 0.05000000074505806\n      Reference Frame: odom\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.05000000074505806\n      Style: Flat Squares\n      Topic: front/scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: true\n      Enabled: false\n      Name: Costmaps\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Alpha: 1\n      Axes Length: 1\n      Axes Radius: 0.10000000149011612\n      Class: rviz/Pose\n      Color: 255; 0; 255\n      Enabled: true\n      Head Length: 0.20000000298023224\n      Head Radius: 0.10000000149011612\n      Name: MoveBase Goal\n      Shaft Length: 0.5\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow\n      Topic: /move_base/current_goal\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 85; 255\n      Enabled: true\n      Name: Polygon\n      Topic: /move_base/local_costmap/obstacles_layer_footprint/footprint_stamped\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 255; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: FW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 255; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/ForwardGlobalPlanner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 170; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: BW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 170; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /backward_planner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Global Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/NavfnROS/plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Local Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/TrajectoryPlannerROS/local_plan\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/ForwardLocalPlanner/goal_marker\n      Name: FW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/BackwardLocalPlanner/goal_marker\n      Name: BW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/backward_planner/markers\n      Name: BackwardMotionPlanner\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Angle Tolerance: 0.10000000149011612\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.30000001192092896\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 15000\n      Name: Odometry\n      Position Tolerance: 0.10000000149011612\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.10000000149011612\n        Color: 255; 25; 0\n        Head Length: 0.003000000026077032\n        Head Radius: 0\n        Shaft Length: 0.05000000074505806\n        Shaft Radius: 0.019999999552965164\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        axle_link:\n          Value: false\n        base_link:\n          Value: true\n        camera_link:\n          Value: true\n        chassis_link:\n          Value: false\n        front_cover_link:\n          Value: false\n        front_laser:\n          Value: false\n        front_left_wheel_link:\n          Value: false\n        front_lights_link:\n          Value: false\n        front_right_wheel_link:\n          Value: false\n        front_rocker_link:\n          Value: false\n        imu_link:\n          Value: false\n        left_side_cover_link:\n          Value: false\n        mid_mount:\n          Value: false\n        odom:\n          Value: true\n        rear_cover_link:\n          Value: false\n        rear_left_wheel_link:\n          Value: false\n        rear_lights_link:\n          Value: false\n        rear_right_wheel_link:\n          Value: false\n        rear_rocker_link:\n          Value: false\n        right_side_cover_link:\n          Value: false\n        top_link:\n          Value: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: false\n      Show Axes: true\n      Show Names: true\n      Tree:\n        odom:\n          base_link:\n            chassis_link:\n              axle_link:\n                front_rocker_link:\n                  front_left_wheel_link:\n                    {}\n                  front_right_wheel_link:\n                    {}\n                rear_rocker_link:\n                  rear_left_wheel_link:\n                    {}\n                  rear_right_wheel_link:\n                    {}\n              camera_link:\n                {}\n              front_cover_link:\n                {}\n              front_laser:\n                {}\n              front_lights_link:\n                {}\n              imu_link:\n                {}\n              left_side_cover_link:\n                {}\n              rear_cover_link:\n                {}\n              rear_lights_link:\n                {}\n              right_side_cover_link:\n                {}\n              top_link:\n                {}\n            mid_mount:\n              {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 25; 255; 0\n      Enabled: true\n      Name: GridCells\n      Topic: \"\"\n      Value: true\n    - Alpha: 1\n      Arrow Length: 0.30000001192092896\n      Axes Length: 0.30000001192092896\n      Axes Radius: 0.009999999776482582\n      Class: rviz/PoseArray\n      Color: 255; 25; 0\n      Enabled: true\n      Head Length: 0.07000000029802322\n      Head Radius: 0.029999999329447746\n      Name: Pose Estimation\n      Shaft Length: 0.23000000417232513\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow (Flat)\n      Topic: /particlecloud\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /tool_markers\n      Name: MarkerArray\n      Namespaces:\n        {}\n      Queue Size: 1\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: Global Planner Costmap\n      Topic: /move_base/global_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: false\n      Name: LocalPlanner Costmap\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Class: smacc_rviz_plugin/SmaccRvizDisplay\n      CurrentState: \"\"\n      Enabled: true\n      Name: SmaccRvizDisplay\n      Topic: /remap_smacc_status\n      Value: true\n    - Class: rviz/Image\n      Enabled: true\n      Image Topic: /opencv_debug_image\n      Max Value: 1\n      Median window: 5\n      Min Value: 0\n      Name: Image\n      Normalize Range: true\n      Queue Size: 2\n      Transport Hint: raw\n      Unreliable: false\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: odom\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Theta std deviation: 0.2617993950843811\n      Topic: /initialpose\n      X std deviation: 0.5\n      Y std deviation: 0.5\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: -0.005000012926757336\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Scale: 88.7320785522461\n      Target Frame: base_link\n      Value: TopDownOrtho (rviz)\n      X: 3.0729715824127197\n      Y: 0.5892993807792664\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1025\n  Hide Left Dock: false\n  Hide Right Dock: false\n  Image:\n    collapsed: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001ad00000363fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001a4000000c900fffffffb0000000a0049006d00610067006501000001e7000001b90000001600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000073d000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000058a0000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1853\n  X: 67\n  Y: 27\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/radial_motion_sm_config.yaml",
    "content": "RadialMotionStateMachine:\n    NavigateToRadialStart:\n        NavigationOrthogonalLine:\n            Navigate:\n                start_position_x: 3\n                start_position_y: 0\n    RotateDegress:\n        NavigationOrthogonalLine:\n            Navigate:\n                initial_orientation_index: 0 # the initial index of the linear motion (factor of angle_increment_degrees)\n                angle_increment_degree: 15    # the increment of angle between to linear motions\n                linear_trajectories_count: 12  # the number of linear trajectories of the radial motion\n    NavigateToEndPoint:\n        NavigationOrthogonalLine:\n            Navigate:\n                straight_motion_distance: 3.5\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/config/sm_ridgeback_barrel_search_1_config.yaml",
    "content": "SmRidgebackBarrelSearch1:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/clients/opencv_perception_client/cl_opencv_perception_client.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/Int32.h>\n\nnamespace sm_ridgeback_barrel_search_1\n{\nnamespace cl_opencv_perception\n{\nclass ClOpenCVPerception : public smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>\n{\npublic:\n\n  ClOpenCVPerception(std::string topicname = \"/detected_color\")\n    : smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>(topicname)\n  {\n  }\n\n  virtual ~ClOpenCVPerception()\n  {\n  }\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/orthogonals/or_navigation.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n\n\nnamespace sm_ridgeback_barrel_search_1\n{\n    using namespace cl_move_base_z;\n\n    class OrNavigation : public smacc::Orthogonal<OrNavigation>\n    {\n    public:\n        virtual void onInitialize() override\n        {\n            auto movebaseClient = this->createClient<ClMoveBaseZ>();\n            movebaseClient->initialize();\n\n            movebaseClient->createComponent<Pose>();\n\n            // create planner switcher\n            movebaseClient->createComponent<PlannerSwitcher>();\n\n            // create odom tracker\n            movebaseClient->createComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n\n            // create waypoints navigator component\n            auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();\n            loadWaypointsFromYaml(waypointsNavigator);\n\n            // change this to skip some points of the yaml file, default = 0\n            // waypointsNavigator->currentWaypoint_ = 3;\n        }\n\n        void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)\n        {\n            // if it is the first time and the waypoints navigator is not configured\n\n            std::string planfilepath;\n            ros::NodeHandle nh(\"~\");\n            if (nh.getParam(\"waypoints_plan\", planfilepath))\n            {\n                ROS_INFO(\"Loaded waypoints path file: %s\", planfilepath.c_str());\n                waypointsNavigator->loadWayPointsFromFile(planfilepath);\n            }\n            else\n            {\n                ROS_ERROR(\"Error while loading waypoints_path file: not found\");\n            }\n        }\n    };\n} // namespace sm_ridgeback_barrel_search_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/orthogonals/or_perception.h",
    "content": "#pragma once\n\n#include <sm_ridgeback_barrel_search_1/clients/opencv_perception_client/cl_opencv_perception_client.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_ridgeback_barrel_search_1\n{\nclass OrPerception : public smacc::Orthogonal<OrPerception>\n{\npublic:\n  virtual void onInitialize() override\n  {\n    auto opencvPerceptionClient = this->createClient<cl_opencv_perception::ClOpenCVPerception>();\n    opencvPerceptionClient->initialize();\n  }\n};\n}  // namespace sm_ridgeback_barrel_search_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/sm_ridgeback_barrel_search_1.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENT BEHAVIORS\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/client_behaviors.h>\n\n\nusing namespace cl_move_base_z;\n\n// ORTHOGONALS\n#include <sm_ridgeback_barrel_search_1/orthogonals/or_navigation.h>\n#include <sm_ridgeback_barrel_search_1/orthogonals/or_perception.h>\n\nusing namespace smacc;\nusing namespace smacc::default_events;\n\nnamespace sm_ridgeback_barrel_search_1\n{\n    class StNavigateToWaypointX;\n\nstruct SmRidgebackBarrelSearch1\n    : public smacc::SmaccStateMachineBase<SmRidgebackBarrelSearch1, StNavigateToWaypointX>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrNavigation>();\n        this->createOrthogonal<OrPerception>();\n    }\n};\n\n} // namespace sm_ridgeback_barrel_search_1\n\n\n//STATES\n#include <sm_ridgeback_barrel_search_1/states/st_detect_items.h>\n#include <sm_ridgeback_barrel_search_1/states/st_navigate_to_waypoint_x.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/states/st_detect_items.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ridgeback_barrel_search_1\n{\n// STATE DECLARATION\nstruct StDetectItems : smacc::SmaccState<StDetectItems, SmRidgebackBarrelSearch1>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<smacc::Transition<EvTopicMessage<cl_opencv_perception::ClOpenCVPerception, OrPerception>, StNavigateToWaypointX>>\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    //   configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}  // namespace sm_ridgeback_barrel_search_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/include/sm_ridgeback_barrel_search_1/states/st_navigate_to_waypoint_x.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ridgeback_barrel_search_1\n{\n    using namespace smacc::default_events;\n    // STATE DECLARATION\n    struct StNavigateToWaypointX : smacc::SmaccState<StNavigateToWaypointX, SmRidgebackBarrelSearch1>\n    {\n        using SmaccState::SmaccState;\n\n        // TRANSITION TABLE\n        typedef mpl::list<\n\n            Transition<EvCbSuccess<CbNavigateNextWaypoint, OrNavigation>, StDetectItems>,\n            Transition<EvCbFailure<CbNavigateNextWaypoint, OrNavigation>, StNavigateToWaypointX>\n\n            >\n            reactions;\n\n        // STATE FUNCTIONS\n        static void staticConfigure()\n        {\n            // configure_orthogonal<OrLED, CbLEDOn>();\n            // configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n            configure_orthogonal<OrNavigation, CbNavigateNextWaypoint>();\n        }\n\n        void runtimeConfigure()\n        {\n        }\n    };\n} // namespace sm_ridgeback_barrel_search_1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/launch/ridgeback_simulation.launch",
    "content": "<launch>\n    <arg name=\"use_sim_time\" default=\"true\" />\n    <arg name=\"gui\" default=\"true\" />\n    <arg name=\"headless\" default=\"false\" />\n    <arg name=\"world_name\" default=\"$(find sm_ridgeback_barrel_search_1)/simulation/worlds/opencv_world.sdf\" />\n\n    <!-- Configuration of Ridgeback which you would like to simulate.\n         See ridgeback_description for details. -->\n    <arg name=\"config\" default=\"$(optenv RIDGEBACK_CONFIG base)\" />\n\n    <!-- Launch Gazebo with the specified world -->\n    <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\n      <arg name=\"debug\" value=\"0\" />\n      <arg name=\"gui\" value=\"$(arg gui)\" />\n      <arg name=\"use_sim_time\" value=\"$(arg use_sim_time)\" />\n      <arg name=\"headless\" value=\"$(arg headless)\" />\n      <arg name=\"world_name\" value=\"$(arg world_name)\" />\n      <arg name=\"paused\" value=\"false\"/>\n    </include>\n\n    <param name=\"robot_description\"\n           command=\"$(find ridgeback_description)/scripts/env_run\n                    $(find ridgeback_description)/urdf/configs/$(arg config)\n                    $(find xacro)/xacro $(find sm_ridgeback_barrel_search_1)/urdf/ridgeback.urdf.xacro\n                    --inorder \" />\n\n    <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\" />\n\n    <include file=\"$(find ridgeback_control)/launch/control.launch\" />\n    <include file=\"$(find ridgeback_control)/launch/teleop.launch\">\n      <arg name=\"joystick\" value=\"false\"/>\n    </include>\n\n    <rosparam param=\"/gazebo_ros_control/pid_gains\">\n      front_left_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      front_right_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      rear_left_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      rear_right_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n    </rosparam>\n\n    <!-- Spawn Ridgeback -->\n    <node name=\"urdf_spawner\" pkg=\"gazebo_ros\" type=\"spawn_model\"\n          args=\"-urdf -model ridgeback -param robot_description -x 0 -y 0 -z 0.1\" />\n    <!--<node name=\"urdf_spawner\" pkg=\"gazebo_ros\" type=\"spawn_model\"\n          args=\"-sdf -model ridgeback -file /Users/mikepurvis/ridgeback_ws/ridgeback.sdf -x 0 -y 0 -z 0.1\" /> -->\n  </launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/launch/sm_ridgeback_barrel_search_1.launch",
    "content": "<launch>\n    <!--========= LAUNCH FILE ARGUMENTS ======================================================-->\n    <!-- defines the xterm parameters for the clients, set to empty to skip using xterm window-->\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <!-- defines the xterm parameters for the state machine, set to empty to skip using xterm window-->\n    <arg name=\"sm_xterm\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e\" />\n\n    <!-- if true, gazebo client is shown -->\n    <arg name=\"show_gz_client\" default=\"true\" />\n\n    <!-- if true, smacc_viewer is shown -->\n    <arg name=\"show_smacc_viewer\" default=\"true\" />\n\n    <!-- if true, rviz is shown -->\n    <arg name=\"show_rviz\" default=\"true\" />\n\n    <!-- It does not start the sm node in order to start it from your standalone process with debugger-->\n    <arg name=\"debug\" default=\"false\" />\n\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_ridgeback_barrel_search_1)/config/rosconsole.config\" />\n\n    <!--================================================================================-->\n    <!-- load the navigation environment simulated in gazebo-->\n    <include file=\"$(find sm_ridgeback_barrel_search_1)/launch/ridgeback_simulation.launch\">\n\n    </include>\n\n     <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base\" output=\"screen\">\n        <rosparam file=\"$(find ridgeback_navigation)/params/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n\n        <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/odom_nav_params/local_costmap_params.yaml\" command=\"load\" />\n\n        <rosparam file=\"$(find ridgeback_navigation)/params/base_local_planner_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find ridgeback_navigation)/params/move_base_params.yaml\" command=\"load\" />\n\n        <!-- overrides -->\n        <rosparam file=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n        <rosparam file=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n\n        <rosparam file=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/global_costmap_params.yaml\" command=\"load\" />\n        <rosparam file=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/local_costmap_params.yaml\" command=\"load\" />\n\n        <rosparam file=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/base_local_planner_params.yaml\" command=\"load\" />\n        <!-- end overrides -->\n\n        <param name=\"base_global_planner\" type=\"string\" value=\"navfn/NavfnROS\" />\n        <param name=\"base_local_planner\" value=\"base_local_planner/TrajectoryPlannerROS\"/>\n\n        <remap from=\"odom\" to=\"odometry/filtered\" />\n     </node>\n\n    <!-- <include file=\"$(find ridgeback_navigation)/launch/include/amcl.launch\" /> -->\n\n    <!-- load state machine parameters -->\n    <rosparam command=\"load\" file=\"$(find sm_ridgeback_barrel_search_1)/config/sm_ridgeback_barrel_search_1_config.yaml\" />\n\n    <!-- state machine node -->\n    <node pkg=\"sm_ridgeback_barrel_search_1\" type=\"sm_ridgeback_barrel_search_1_node\" name=\"sm_ridgeback_barrel_search_1\" launch-prefix=\"$(arg sm_xterm)\" unless=\"$(arg debug)\">\n        <param name=\"waypoints_plan\" value=\"$(find sm_ridgeback_barrel_search_1)/config/move_base_client/waypoints_plan.yaml\" />\n        <remap from=\"/odom\" to=\"/odometry/filtered\" />\n        <remap from=\"/sm_ridgeback_barrel_search_1/odom_tracker/odom_tracker_path\" to=\"/odom_tracker_path\"/>\n        <remap from=\"/sm_ridgeback_barrel_search_1/odom_tracker/odom_tracker_stacked_path\" to=\"/odom_tracker_path_stacked\"/>\n    </node>\n\n    <node pkg=\"sm_ridgeback_barrel_search_1\" type=\"opencv_perception_node\" name=\"opencv_perception_node\">\n        <remap from=\"image_raw\" to=\"/ridgeback/camera1/image_raw\"/>\n    </node>\n\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find sm_ridgeback_barrel_search_1)/config/navigation.rviz\" if=\"$(arg show_rviz)\">\n        <remap from=\"/remap_smacc_status\" to=\"/SmDanceBot/smacc/status\" />\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/msg/DetectedBlobs.msg",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_ridgeback_barrel_search_1</name>\n    <version>1.4.16</version>\n  <description>The sm_ridgeback_barrel_search_1 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>move_base_z_client_plugin</depend>\n  <depend>cv_bridge</depend>\n\n  <depend>vision_opencv</depend>\n  <depend>ridgeback_gazebo</depend>\n  <depend>ridgeback_navigation</depend>\n  <depend>xterm</depend>\n\n  <export>\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/servers/opencv_perception_node/CMakeLists.txt2",
    "content": "cmake_minimum_required(VERSION 3.8)\n\nfind_package(OpenCV REQUIRED)\n\ninclude_directories($OpenCV_INCLUDE_DIRS)\n\nadd_executable(perception_node \"opencv_perception_node.cpp\")\n\ntarget_link_libraries(perception_node ${OpenCV_LIBRARIES})\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/servers/opencv_perception_node/opencv_perception_node.cpp",
    "content": "#include <cv_bridge/cv_bridge.h>\n#include <ros/ros.h>\n#include <sensor_msgs/Image.h>\n#include <std_msgs/Int32.h>\n#include <iostream>\n#include <opencv2/opencv.hpp>\n#include <opencv2/features2d.hpp>\n\nros::Publisher detectionPub;\nros::Publisher debugImagePub;\nros::Subscriber imageSub;\n\nvoid segmentColor(const cv::Mat& inputRGB, int hueMean, int hueWindow, cv::Mat& out)\n{\n  cv::Mat hsvInput;\n  cv::cvtColor(inputRGB, hsvInput, cv::COLOR_BGR2HSV);\n  cv::inRange(hsvInput, cv::Scalar(hueMean - hueWindow, 20, 20), cv::Scalar(hueMean + hueWindow, 255, 255), out);\n  cv::threshold(out, out, 100, 255, cv::THRESH_BINARY);\n}\n\nint testImage(cv::Mat& input, cv::Mat& debugImage, std::string colorName, int hueMean, int hueWindow)\n{\n  cv::Mat segmented;\n\n  segmentColor(input, hueMean, hueWindow, segmented);\n\n  cv::SimpleBlobDetector::Params params;\n  // params.filterByArea= true;\n  // params.minArea = 10;\n  params.filterByArea = true;\n  params.minArea = 100;\n  params.maxArea = 100000;\n  params.filterByColor = true;\n  params.blobColor = 255;\n\n  auto blobDetector = cv::SimpleBlobDetector::create(params);\n  std::vector<cv::KeyPoint> blobs;\n  blobDetector->detect(segmented, blobs);\n\n  std::cout << \"-------\" << std::endl;\n  for (auto& b : blobs)\n  {\n    std::cout << \"blob \" << colorName << \" detected: \" << b.size << std::endl;\n  }\n\n  if(!blobs.empty())\n  {\n    for(auto& b: blobs)\n    {\n      cv::Rect r;\n      float diameter = b.size;\n      auto radius = diameter*0.5;\n      r.x = b.pt.x - radius;\n      r.y = b.pt.y - radius;\n      r.width = diameter;\n      r.height = diameter;\n      cv::rectangle(debugImage,r, cv::Scalar(255,0,0),1 );\n    }\n  }\n\n  // cv::imshow(colorName + \" filter - \"+ path, segmented);\n  // cv::waitKey();\n\n  return blobs.size();\n}\n\nint testRed(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"red\", 130, 20);\n}\n\nint testBlue(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"blue\", 10, 10);\n}\n\nint testGreen(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"green\", 50, 10);\n}\n\nint testRed(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"red\", 130, 20);\n}\n\nint testBlue(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"blue\", 10, 10);\n}\n\nint testGreen(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"green\", 50, 10);\n}\n\nvoid update()\n{\n}\n\nvoid callback(const sensor_msgs::Image& img)\n{\n  cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(img, \"rgb8\");\n\n  cv::Mat image = cv_image->image;\n  cv_bridge::CvImage debugImageBridge;\n  debugImageBridge.encoding = \"rgb8\";\n  debugImageBridge.image = image.clone();\n\n  int detectedColor = 0;\n  if (testRed(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 1;\n  }\n\n  if (testGreen(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 2;\n  }\n\n  if (testBlue(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 3;\n  }\n\n  std_msgs::Int32 detectedColorMsg;\n  detectedColorMsg.data = detectedColor;\n  detectionPub.publish(detectedColorMsg);\n\n  debugImageBridge.header = img.header;\n  debugImagePub.publish(debugImageBridge.toImageMsg());\n}\n\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"blob_detector_node\");\n  ros::NodeHandle nh;\n\n  detectionPub = nh.advertise<std_msgs::Int32>(\"detected_color\", 1);\n  imageSub = nh.subscribe(\"/image_raw\", 1, callback);\n  debugImagePub = nh.advertise<sensor_msgs::Image>(\"/opencv_debug_image\", 1);\n\n  ros::Rate r(10);\n\n  while (ros::ok())\n  {\n    update();\n    ros::spinOnce();\n    r.sleep();\n  }\n\n  /*\n  testRed(\"../../red1.png\");\n  testRed(\"../../green1.png\");\n  testRed(\"../../blue1.png\");\n  testRed(\"../../red2.png\");\n\n  testGreen(\"../../red1.png\");\n  testGreen(\"../../green1.png\");\n  testGreen(\"../../blue1.png\");\n  testGreen(\"../../red2.png\");\n\n  testBlue(\"../../red1.png\");\n  testBlue(\"../../green1.png\");\n  testBlue(\"../../blue1.png\");\n  testBlue(\"../../red2.png\");\n  */\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/simulation/worlds/opencv_world.sdf",
    "content": "<sdf version='1.6'>\n  <world name='default'>\n    <light name='sun' type='directional'>\n      <cast_shadows>1</cast_shadows>\n      <pose frame=''>0 0 10 0 -0 0</pose>\n      <diffuse>0.8 0.8 0.8 1</diffuse>\n      <specular>0.2 0.2 0.2 1</specular>\n      <attenuation>\n        <range>1000</range>\n        <constant>0.9</constant>\n        <linear>0.01</linear>\n        <quadratic>0.001</quadratic>\n      </attenuation>\n      <direction>-0.5 0.1 -0.9</direction>\n    </light>\n    <model name='ground_plane'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>100 100</size>\n            </plane>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>100</mu>\n                <mu2>50</mu2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <bounce/>\n            <contact>\n              <ode/>\n            </contact>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <visual name='visual'>\n          <cast_shadows>0</cast_shadows>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>100 100</size>\n            </plane>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n          </material>\n        </visual>\n        <velocity_decay>\n          <linear>0</linear>\n          <angular>0</angular>\n        </velocity_decay>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n    </model>\n    <physics name='default_physics' default='0' type='ode'>\n      <max_step_size>0.001</max_step_size>\n      <real_time_factor>1</real_time_factor>\n      <real_time_update_rate>1000</real_time_update_rate>\n    </physics>\n    <scene>\n      <ambient>0.4 0.4 0.4 1</ambient>\n      <background>0.7 0.7 0.7 1</background>\n      <shadows>1</shadows>\n    </scene>\n    <spherical_coordinates>\n      <surface_model>EARTH_WGS84</surface_model>\n      <latitude_deg>0</latitude_deg>\n      <longitude_deg>0</longitude_deg>\n      <elevation>0</elevation>\n      <heading_deg>0</heading_deg>\n    </spherical_coordinates>\n    <state world_name='default'>\n      <sim_time>7043 221000000</sim_time>\n      <real_time>1237 642548413</real_time>\n      <wall_time>1590695981 990722576</wall_time>\n      <iterations>520762</iterations>\n      <model name='BlueBarrel'>\n        <pose frame=''>14.243 -1.60021 0.499991 0 -0 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>14.243 -1.60021 0.499991 0 -0 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone'>\n        <pose frame=''>181.242 115.226 0.499997 3e-06 -1e-06 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>181.242 115.226 0.499997 3e-06 -1e-06 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone_0'>\n        <pose frame=''>192.452 111.096 0.499991 0 -0 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>192.452 111.096 0.499991 0 -0 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone_1'>\n        <pose frame=''>194.277 94.8193 0.499997 4e-06 -1e-06 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>194.277 94.8193 0.499997 4e-06 -1e-06 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone_2'>\n        <pose frame=''>-24.3651 0.418681 0.499991 0 -0 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>-24.3651 0.418681 0.499991 0 -0 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone_3'>\n        <pose frame=''>-9.14868 19.5755 0.499991 0 -0 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>-9.14868 19.5755 0.499991 0 -0 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='BlueBarrel_clone_4'>\n        <pose frame=''>-13.9653 -30.9759 0.499999 0 0 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>-13.9653 -30.9759 0.499999 0 0 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='GreenBarrel'>\n        <pose frame=''>-26.6074 -28.1343 0.499999 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link_1'>\n          <pose frame=''>-26.6074 -28.1343 0.499999 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='RedBarrel'>\n        <pose frame=''>-4.56456 -2.64972 0.499999 0 -0 0.002242</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0'>\n          <pose frame=''>-4.56456 -2.64972 0.499999 0 -0 0.002242</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='RedBarrel_0'>\n        <pose frame=''>2.74759 13.2932 0.499998 -3e-06 1e-06 -0.002212</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0'>\n          <pose frame=''>2.74759 13.2932 0.499998 -3e-06 1e-06 -0.002212</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='ground_plane'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree'>\n        <pose frame=''>1.86518 5.14537 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>1.86518 5.14537 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_0'>\n        <pose frame=''>-0.226399 8.4636 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-0.226399 8.4636 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_1'>\n        <pose frame=''>4.27802 7.17986 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>4.27802 7.17986 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_10'>\n        <pose frame=''>-19.0648 25.739 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-19.0648 25.739 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_11'>\n        <pose frame=''>-27.6553 5.91995 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-27.6553 5.91995 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12'>\n        <pose frame=''>35.3489 18.7402 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>35.3489 18.7402 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone'>\n        <pose frame=''>49.6043 23.4507 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>49.6043 23.4507 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_0'>\n        <pose frame=''>64.9707 31.9794 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>64.9707 31.9794 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_1'>\n        <pose frame=''>89.4228 38.3848 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>89.4228 38.3848 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_10'>\n        <pose frame=''>192.355 88.9741 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>192.355 88.9741 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_11'>\n        <pose frame=''>213.671 101.943 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>213.671 101.943 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_12'>\n        <pose frame=''>153.378 56.9207 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>153.378 56.9207 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_13'>\n        <pose frame=''>149.089 44.0132 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>149.089 44.0132 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_14'>\n        <pose frame=''>127.237 85.1288 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>127.237 85.1288 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_2'>\n        <pose frame=''>48.4924 -12.2033 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>48.4924 -12.2033 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_3'>\n        <pose frame=''>74.008 -10.2126 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>74.008 -10.2126 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_4'>\n        <pose frame=''>86.2688 -7.2695 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>86.2688 -7.2695 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_5'>\n        <pose frame=''>124.386 18.2908 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>124.386 18.2908 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6'>\n        <pose frame=''>122.746 60.9189 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>122.746 60.9189 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone'>\n        <pose frame=''>120.406 66.6883 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>120.406 66.6883 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_0'>\n        <pose frame=''>143.418 33.2855 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>143.418 33.2855 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_1'>\n        <pose frame=''>144 36 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>144 36 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_10'>\n        <pose frame=''>81 14 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>81 14 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_11'>\n        <pose frame=''>81 10 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>81 10 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_12'>\n        <pose frame=''>76 8 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>76 8 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_13'>\n        <pose frame=''>55.6618 15.1212 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>55.6618 15.1212 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_14'>\n        <pose frame=''>153.75 97.1902 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>153.75 97.1902 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_2'>\n        <pose frame=''>151.697 50.9955 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>151.697 50.9955 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_3'>\n        <pose frame=''>141.916 38.0961 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>141.916 38.0961 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_4'>\n        <pose frame=''>119.465 13 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>119.465 13 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_5'>\n        <pose frame=''>115.409 7 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>115.409 7 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_6'>\n        <pose frame=''>127 40 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>127 40 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_7'>\n        <pose frame=''>129.485 48.362 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>129.485 48.362 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_8'>\n        <pose frame=''>125 42 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>125 42 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_6_clone_9'>\n        <pose frame=''>160.813 90.8826 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>160.813 90.8826 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_7'>\n        <pose frame=''>135.964 95.4373 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>135.964 95.4373 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_8'>\n        <pose frame=''>175.948 124.359 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>175.948 124.359 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_9'>\n        <pose frame=''>207.326 115.454 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>207.326 115.454 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone'>\n        <pose frame=''>57.3596 31.9581 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>57.3596 31.9581 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_0'>\n        <pose frame=''>69.7438 31.9664 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>69.7438 31.9664 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_1'>\n        <pose frame=''>85.9758 36.8389 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>85.9758 36.8389 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_10'>\n        <pose frame=''>188 121 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>188 121 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_11'>\n        <pose frame=''>204.376 109.34 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>204.376 109.34 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_12'>\n        <pose frame=''>199.535 119 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>199.535 119 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_13'>\n        <pose frame=''>147.473 114.43 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>147.473 114.43 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_14'>\n        <pose frame=''>142 117 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>142 117 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_15'>\n        <pose frame=''>209 112 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>209 112 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_16'>\n        <pose frame=''>193.583 88.1834 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>193.583 88.1834 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_17'>\n        <pose frame=''>200.407 96.7337 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>200.407 96.7337 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_2'>\n        <pose frame=''>95.6915 42.5998 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>95.6915 42.5998 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_3'>\n        <pose frame=''>119.394 59.5993 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>119.394 59.5993 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_4'>\n        <pose frame=''>127 73.4047 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>127 73.4047 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_5'>\n        <pose frame=''>127.839 80.6978 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>127.839 80.6978 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_6'>\n        <pose frame=''>130.184 87.9134 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>130.184 87.9134 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_7'>\n        <pose frame=''>180.697 122.892 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>180.697 122.892 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8'>\n        <pose frame=''>184.626 117.391 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>184.626 117.391 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone'>\n        <pose frame=''>138.419 110.306 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>138.419 110.306 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_0'>\n        <pose frame=''>133 102 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>133 102 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_1'>\n        <pose frame=''>160.954 65.4821 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>160.954 65.4821 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_2'>\n        <pose frame=''>166 71.5382 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>166 71.5382 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_3'>\n        <pose frame=''>172.141 76.3358 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>172.141 76.3358 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_4'>\n        <pose frame=''>164 74 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>164 74 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_8_clone_5'>\n        <pose frame=''>175 77 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>175 77 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_12_clone_clone_9'>\n        <pose frame=''>176.412 116.656 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>176.412 116.656 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_13'>\n        <pose frame=''>26.2515 15.8464 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>26.2515 15.8464 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_14'>\n        <pose frame=''>22.1029 17.8825 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>22.1029 17.8825 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_15'>\n        <pose frame=''>-19.6919 20.8051 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-19.6919 20.8051 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_2'>\n        <pose frame=''>-12.9826 14.9575 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-12.9826 14.9575 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_3'>\n        <pose frame=''>-15.6072 13.4691 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-15.6072 13.4691 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_4'>\n        <pose frame=''>-9.71803 -12.9006 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-9.71803 -12.9006 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_5'>\n        <pose frame=''>-3.41031 -20.4659 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.41031 -20.4659 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_6'>\n        <pose frame=''>12.4136 18.6043 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>12.4136 18.6043 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_7'>\n        <pose frame=''>8.79449 23.3017 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>8.79449 23.3017 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_8'>\n        <pose frame=''>-0.095714 20.0524 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-0.095714 20.0524 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pine_tree_9'>\n        <pose frame=''>26.7865 -19.0926 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>26.7865 -19.0926 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n\n      <model name='stone_10_2_5_1cm'>\n        <pose frame=''>-10.7066 3.01548 -0.001001 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-10.7066 3.01548 0.003999 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0.002381 -0.000463 0.000421 0.092586 0.476148 0</acceleration>\n          <wrench>0.00015 -2.9e-05 2.6e-05 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='vrc_driving_terrain'>\n        <pose frame=''>-12.9319 3.93559 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='grass_plane'>\n          <pose frame=''>-12.9319 3.93559 0.1 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n        <link name='link'>\n          <pose frame=''>-12.9319 3.93559 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <light name='sun'>\n        <pose frame=''>0 0 10 0 -0 0</pose>\n      </light>\n      <light name='user_point_light_0'>\n        <pose frame=''>-16.8472 -0.68818 2.02228 0 -0 0</pose>\n      </light>\n      <light name='user_point_light_1'>\n        <pose frame=''>179.158 101.45 6.19305 0 -0 0</pose>\n      </light>\n    </state>\n    <gui fullscreen='0'>\n      <camera name='user_camera'>\n        <pose frame=''>160.803 86.2025 17.5161 0 0.595252 0.749128</pose>\n        <view_controller>orbit</view_controller>\n        <projection_type>perspective</projection_type>\n      </camera>\n    </gui>\n    <gravity>0 0 -9.8</gravity>\n    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>\n    <atmosphere type='adiabatic'/>\n    <model name='pine_tree'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>5.67365 0.228859 0 0 -0 0</pose>\n    </model>\n    <model name='BlueBarrel'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-5.78287 -0.024618 0 0 -0 0</pose>\n    </model>\n    <model name='RedBarrel'>\n      <link name='link_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Red</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>1 0 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-5.22409 -3.90999 0 0 -0 0</pose>\n    </model>\n    <model name='GreenBarrel'>\n      <link name='link_1'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <gravity>1</gravity>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 1 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-1.66636 -4.13429 0 0 -0 0</pose>\n    </model>\n    <model name='RedBarrel_0'>\n      <link name='link_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Red</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>1 0 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>2.72763 3.3635 0 0 -0 0</pose>\n    </model>\n    <light name='user_point_light_0' type='point'>\n      <pose frame=''>-15.9446 0.086762 1 0 -0 0</pose>\n      <diffuse>0.5 0.5 0.5 1</diffuse>\n      <specular>0.1 0.1 0.1 1</specular>\n      <attenuation>\n        <range>20</range>\n        <constant>0.5</constant>\n        <linear>0.01</linear>\n        <quadratic>0.001</quadratic>\n      </attenuation>\n      <cast_shadows>0</cast_shadows>\n      <direction>0 0 -1</direction>\n    </light>\n    <audio>\n      <device>default</device>\n    </audio>\n    <wind/>\n    <model name='pine_tree_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-0.226399 8.4636 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>4.27802 7.17986 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_2'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-12.9826 14.9575 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_3'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-15.6072 13.4691 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_4'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-9.71803 -12.9006 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_5'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-3.41031 -20.4659 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_6'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>12.4136 18.6043 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_7'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>8.79449 23.3017 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_8'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-0.095714 20.0524 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_9'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>26.7865 -19.0926 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_10'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-19.0648 25.739 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_11'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-27.6553 5.91995 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>32.4653 25.9104 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_13'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>30.6868 32.4953 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_14'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>26.7674 30.9308 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_15'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-17.6919 37.8051 0 0 -0 0</pose>\n    </model>\n    <model name='stone_10_2_5_1cm'>\n      <link name='link'>\n        <pose frame=''>0 0 0.005 0 -0 0</pose>\n        <inertial>\n          <mass>0.0628</mass>\n          <inertia>\n            <ixx>3.79417e-06</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>5.28567e-05</iyy>\n            <iyz>0</iyz>\n            <izz>5.56042e-05</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <box>\n              <size>0.1 0.025 0.01</size>\n            </box>\n          </geometry>\n          <surface>\n            <contact>\n              <poissons_ratio>0.15</poissons_ratio>\n              <elastic_modulus>8e+10</elastic_modulus>\n              <ode>\n                <kp>100000</kp>\n                <kd>100</kd>\n                <max_vel>100</max_vel>\n                <min_depth>0.001</min_depth>\n              </ode>\n            </contact>\n            <friction>\n              <torsional>\n                <coefficient>1</coefficient>\n                <use_patch_radius>0</use_patch_radius>\n                <surface_radius>0.01</surface_radius>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n            <bounce/>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <box>\n              <size>0.1 0.025 0.01</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-10.7066 3.01548 0 0 -0 0</pose>\n    </model>\n    <model name='vrc_driving_terrain'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <heightmap>\n              <uri>model://vrc_driving_terrain/materials/textures/heightmap.png</uri>\n              <size>500 500 118</size>\n              <pos>0 0 -15</pos>\n              <texture>\n                <size>10</size>\n                <diffuse>__default__</diffuse>\n                <normal>__default__</normal>\n              </texture>\n              <blend>\n                <min_height>0</min_height>\n                <fade_dist>0</fade_dist>\n              </blend>\n            </heightmap>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <heightmap>\n              <texture>\n                <diffuse>file://media/materials/textures/dirt_diffusespecular.png</diffuse>\n                <normal>file://media/materials/textures/flat_normal.png</normal>\n                <size>5</size>\n              </texture>\n              <texture>\n                <diffuse>file://media/materials/textures/grass_diffusespecular.png</diffuse>\n                <normal>file://media/materials/textures/flat_normal.png</normal>\n                <size>5</size>\n              </texture>\n              <texture>\n                <diffuse>file://media/materials/textures/fungus_diffusespecular.png</diffuse>\n                <normal>file://media/materials/textures/flat_normal.png</normal>\n                <size>20</size>\n              </texture>\n              <blend>\n                <min_height>15</min_height>\n                <fade_dist>5</fade_dist>\n              </blend>\n              <blend>\n                <min_height>30</min_height>\n                <fade_dist>10</fade_dist>\n              </blend>\n              <uri>model://vrc_driving_terrain/materials/textures/heightmap.png</uri>\n              <size>500 500 118</size>\n              <pos>0 0 -15</pos>\n            </heightmap>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='grass_plane'>\n        <collision name='collision'>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>500 500</size>\n            </plane>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>0.5</mu>\n                <mu2>0.5</mu2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <visual name='visual_0'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <cast_shadows>0</cast_shadows>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>500 500</size>\n            </plane>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://vrc_driving_terrain/materials/scripts</uri>\n              <uri>model://vrc_driving_terrain/materials/textures</uri>\n              <name>vrc/grass</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-12.9319 3.93559 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>49.6043 23.4507 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>64.9707 31.9794 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>89.4228 38.3848 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>48.4924 -12.2033 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>74.008 -10.2126 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_4'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>86.2688 -7.2695 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_5'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>124.386 18.2908 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>122.746 60.9189 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_7'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>135.964 95.4373 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_8'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>175.948 124.359 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_9'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>207.326 115.454 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_10'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>192.355 88.9741 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_11'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>213.671 101.943 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_12'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>153.378 56.9207 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_13'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>149.089 44.0132 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_14'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>127.237 85.1288 0 0 -0 0</pose>\n    </model>\n    <model name='BlueBarrel_clone'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>160.718 109.896 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='BlueBarrel_clone_0'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>192.452 111.096 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='BlueBarrel_clone_1'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>178.063 90.8484 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='BlueBarrel_clone_2'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-24.3651 0.418681 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='BlueBarrel_clone_3'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-9.14868 19.5755 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='BlueBarrel_clone_4'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-13.9653 -30.9759 0.499999 0 0 -0.035996</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>57.3596 31.9581 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>69.7438 31.9664 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>85.9758 36.8389 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>95.6915 42.5998 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>119.394 59.5993 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_4'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>127 73.4047 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_5'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>127.839 80.6978 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_6'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>130.184 87.9134 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_7'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>180.697 122.892 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>184.626 117.391 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_9'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>176.412 116.656 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_10'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>188 121 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_11'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>204.376 109.34 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_12'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>199.535 119 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_13'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>147.473 114.43 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_14'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>142 117 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_15'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>209 112 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_16'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>193.583 88.1834 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_17'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>200.407 96.7337 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>138.419 110.306 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>133 102 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>160.954 65.4821 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>166 71.5382 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>172.141 76.3358 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_4'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>164 74 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_clone_8_clone_5'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>175 77 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>120.406 66.6883 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>143.418 33.2855 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>144 36 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>151.697 50.9955 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>141.916 38.0961 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_4'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>119.465 13 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_5'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>115.409 7 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_6'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>127 40 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_7'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>129.485 48.362 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_8'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>125 42 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_9'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>160.813 90.8826 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_10'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>81 14 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_11'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>81 10 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_12'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>76 8 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_13'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>55.6618 15.1212 0 0 -0 0</pose>\n    </model>\n    <model name='pine_tree_12_clone_6_clone_14'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='branch'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Branch</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Branch</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='bark'>\n          <geometry>\n            <mesh>\n              <uri>model://pine_tree/meshes/pine_tree.dae</uri>\n              <submesh>\n                <name>Bark</name>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://pine_tree/materials/scripts/</uri>\n              <uri>model://pine_tree/materials/textures/</uri>\n              <name>PineTree/Bark</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>153.75 97.1902 0 0 -0 0</pose>\n    </model>\n\n    <light name='user_point_light_1' type='point'>\n      <pose frame=''>173.03 98.1241 1 0 -0 0</pose>\n      <diffuse>0.5 0.5 0.5 1</diffuse>\n      <specular>0.1 0.1 0.1 1</specular>\n      <attenuation>\n        <range>20</range>\n        <constant>0.5</constant>\n        <linear>0.01</linear>\n        <quadratic>0.001</quadratic>\n      </attenuation>\n      <cast_shadows>0</cast_shadows>\n      <direction>0 0 -1</direction>\n    </light>\n  </world>\n</sdf>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/src/sm_ridgeback_barrel_search_1.cpp",
    "content": "#include <sm_ridgeback_barrel_search_1/sm_ridgeback_barrel_search_1.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_ridgeback_barrel_search_1\");\n    ros::NodeHandle nh;\n\n    ros::Duration(5).sleep();\n    smacc::run<sm_ridgeback_barrel_search_1::SmRidgebackBarrelSearch1>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/urdf/ridgeback.camera.gazebo",
    "content": "<?xml version=\"1.0\" ?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"gazebo_camera\">\n\n    <joint name=\"$camera_joint\" type=\"fixed\">\n      <origin xyz=\"0.3 0 0.5330\" rpy=\"0 0 0\" />\n      <parent link=\"chassis_link\" />\n      <child link=\"camera_link\" />\n    </joint>\n\n    <link name=\"camera_link\">\n      <inertial>\n        <mass value=\"0.130\" />\n        <origin xyz=\"0 0 0\" />\n        <inertia ixx=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.07*0.07)}\" ixy=\"0.0\" ixz=\"0.0\" iyy=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.07*0.07)}\" iyz=\"0.0\" izz=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.05*0.05)}\" />\n      </inertial>\n      <visual>\n        <origin xyz=\"-0.15 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <!-- Origin of this mesh is the focal point of the LIDAR. -->\n          <mesh filename=\"package://ridgeback_description/meshes/ust-10lx.stl\" />\n        </geometry>\n        <material name=\"dark_grey\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 -0.0122\" rpy=\"0 0 0\" />\n        <geometry>\n          <box size=\"0.05 0.05 0.07\" />\n        </geometry>\n      </collision>\n    </link>\n\n    <!-- camera -->\n    <gazebo reference=\"camera_link\">\n      <sensor type=\"camera\" name=\"camera1\">\n        <update_rate>30.0</update_rate>\n        <camera name=\"head\">\n          <horizontal_fov>1.3962634</horizontal_fov>\n          <image>\n            <width>800</width>\n            <height>800</height>\n            <format>R8G8B8</format>\n          </image>\n          <clip>\n            <near>0.02</near>\n            <far>300</far>\n          </clip>\n          <noise>\n            <type>gaussian</type>\n            <!-- Noise is sampled independently per pixel on each frame.\n               That pixel's noise value is added to each of its color\n               channels, which at that point lie in the range [0,1]. -->\n            <mean>0.0</mean>\n            <stddev>0.007</stddev>\n          </noise>\n        </camera>\n        <plugin name=\"camera_controller\" filename=\"libgazebo_ros_camera.so\">\n          <alwaysOn>true</alwaysOn>\n          <updateRate>0.0</updateRate>\n          <cameraName>ridgeback/camera1</cameraName>\n          <imageTopicName>image_raw</imageTopicName>\n          <cameraInfoTopicName>camera_info</cameraInfoTopicName>\n          <frameName>camera_link</frameName>\n          <hackBaseline>0.07</hackBaseline>\n          <distortionK1>0.0</distortionK1>\n          <distortionK2>0.0</distortionK2>\n          <distortionK3>0.0</distortionK3>\n          <distortionT1>0.0</distortionT1>\n          <distortionT2>0.0</distortionT2>\n        </plugin>\n      </sensor>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_1/urdf/ridgeback.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot name=\"ridgeback\" xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <xacro:property name=\"PI\" value=\"3.1415926535897931\" />\n\n  <xacro:property name=\"wheel_radius\" value=\"0.0759\" />\n  <xacro:property name=\"wheel_width\" value=\"0.0790\" />\n\n  <xacro:property name=\"chassis_length\" value=\"0.960\" />\n  <xacro:property name=\"chassis_width\" value=\"0.793\" />\n  <xacro:property name=\"chassis_height\" value=\"0.216\" />\n  <xacro:property name=\"deck_height\" value=\"0.280\" />\n\n  <xacro:property name=\"axle_offset\" value=\"0.0500\" />\n  <xacro:property name=\"rocker_offset\" value=\"0.319\" />\n  <xacro:property name=\"rocker_width\" value=\"0.472\" />\n\n  <xacro:property name=\"imu_offset_x\" value=\"0.2085\" />\n  <xacro:property name=\"imu_offset_y\" value=\"-0.2902\" />\n  <xacro:property name=\"imu_offset_z\" value=\"0.1681\" />\n\n  <xacro:property name=\"dummy_inertia\" value=\"1e-09\"/>\n\n  <material name=\"dark_grey\"><color rgba=\"0.2 0.2 0.2 1.0\" /></material>\n  <material name=\"light_grey\"><color rgba=\"0.4 0.4 0.4 1.0\" /></material>\n  <material name=\"red\"><color rgba=\"0.8 0.0 0.0 1.0\" /></material>\n  <material name=\"white\"><color rgba=\"0.9 0.9 0.9 1.0\" /></material>\n  <material name=\"yellow\"><color rgba=\"0.8 0.8 0.0 1.0\" /></material>\n  <material name=\"black\"><color rgba=\"0.15 0.15 0.15 1.0\" /></material>\n\n  <xacro:macro name=\"wheel\" params=\"prefix side *joint_pose\">\n    <link name=\"${prefix}_${side}_wheel_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 0\"/>\n        <geometry>\n          <mesh filename=\"package://ridgeback_description/meshes/wheel.stl\"/>\n        </geometry>\n        <material name=\"black\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 0\"/>\n        <geometry>\n          <cylinder radius=\"${wheel_radius}\" length=\"${wheel_width}\"/>\n        </geometry>\n      </collision>\n      <inertial>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <mass value=\"2.3\"/>\n        <inertia\n          ixx=\"3.3212e-3\" ixy=\"0\" ixz=\"0\"\n          iyy=\"6.6424e-3\" iyz=\"0\"\n          izz=\"3.3212e-3\"/>\n      </inertial>\n    </link>\n\n    <joint name=\"${prefix}_${side}_wheel\" type=\"continuous\">\n      <parent link=\"${prefix}_rocker_link\"/>\n      <child link=\"${prefix}_${side}_wheel_link\" />\n      <xacro:insert_block name=\"joint_pose\" />\n      <axis xyz=\"0 1 0\" />\n    </joint>\n\n    <transmission name=\"${prefix}_wheel_trans\">\n      <type>transmission_interface/SimpleTransmission</type>\n      <joint name=\"${prefix}_${side}_wheel\">\n        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>\n      </joint>\n      <actuator name=\"${prefix}_${side}_actuator\">\n        <mechanicalReduction>1</mechanicalReduction>\n      </actuator>\n    </transmission>\n  </xacro:macro>\n\n\n  <xacro:macro name=\"rocker\" params=\"prefix joint_type location *joint_limits\">\n    <link name=\"${prefix}_rocker_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 ${PI/2}\" />\n        <geometry>\n          <mesh filename=\"package://ridgeback_description/meshes/rocker.stl\"/>\n        </geometry>\n        <material name=\"black\" />\n      </visual>\n      <inertial>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 ${PI/2}\"/>\n        <mass value=\"10.267\"/>\n        <inertia\n          ixx=\"0.0288\" ixy=\"2.20484e-6\" ixz=\"-1.3145e-5\"\n          iyy=\"0.4324\" iyz=\"1.8944e-3\"\n          izz=\"0.4130\"/>\n      </inertial>\n    </link>\n\n    <joint name=\"${prefix}_rocker\" type=\"${joint_type}\">\n      <parent link=\"axle_link\"/>\n      <child link=\"${prefix}_rocker_link\" />\n      <origin xyz=\"${location*rocker_offset} 0 0\" rpy=\"0 0 0\" />\n      <axis xyz=\"1 0 0\" />\n      <xacro:insert_block name=\"joint_limits\" />\n    </joint>\n\n    <xacro:wheel prefix=\"${prefix}\" side=\"left\">\n      <origin xyz=\"0 ${rocker_width/2 + wheel_width/2} 0\" rpy=\"0 0 0\" />\n    </xacro:wheel>\n    <xacro:wheel prefix=\"${prefix}\" side=\"right\">\n      <origin xyz=\"0 ${-(rocker_width/2 + wheel_width/2)} 0\" rpy=\"0 0 0\" />\n    </xacro:wheel>\n  </xacro:macro>\n\n  <xacro:rocker prefix=\"front\" joint_type=\"revolute\" location=\"1\" >\n    <limit lower=\"-0.08726\" upper=\"0.08726\" effort=\"0\" velocity=\"0\" />\n  </xacro:rocker>\n\n  <xacro:rocker prefix=\"rear\" joint_type=\"fixed\" location=\"-1\" >\n    <limit effort=\"0\" velocity=\"0\" />\n  </xacro:rocker>\n\n  <link name=\"base_link\"></link>\n\n  <joint name=\"base_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"base_link\"/>\n    <child link=\"chassis_link\" />\n  </joint>\n\n  <link name=\"chassis_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/body.stl\"/>\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n    <collision>\n      <origin xyz=\"0 0 0\"/>\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/body-collision.stl\"/>\n      </geometry>\n    </collision>\n    <inertial>\n      <origin xyz=\"0.012 0.002 0.067\" rpy=\"${PI/2} 0 ${PI/2}\"/>\n      <mass value=\"165.304\"/>\n      <inertia\n        ixx=\"4.4744\" ixy=\"0.03098\" ixz=\"0.003647\"\n        iyy=\"7.1624\" iyz=\"0.1228\"\n        izz=\"4.6155\"/>\n    </inertial>\n  </link>\n\n  <joint name=\"right_side_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"right_side_cover_link\" />\n  </joint>\n  <joint name=\"left_side_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"left_side_cover_link\" />\n  </joint>\n\n  <link name=\"left_side_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/side-cover.stl\"/>\n      </geometry>\n      <material name=\"yellow\" />\n    </visual>\n  </link>\n  <link name=\"right_side_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/side-cover.stl\"/>\n      </geometry>\n      <material name=\"yellow\" />\n    </visual>\n  </link>\n\n  <joint name=\"front_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"front_cover_link\" />\n  </joint>\n\n  <link name=\"front_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/end-cover.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <joint name=\"rear_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"rear_cover_link\" />\n  </joint>\n\n  <link name=\"rear_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/end-cover.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <joint name=\"front_lights_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"front_lights_link\" />\n  </joint>\n  <joint name=\"rear_lights_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"rear_lights_link\" />\n  </joint>\n\n  <link name=\"front_lights_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/lights.stl\" />\n      </geometry>\n      <material name=\"white\" />\n    </visual>\n  </link>\n  <link name=\"rear_lights_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/lights.stl\" />\n      </geometry>\n      <material name=\"red\" />\n    </visual>\n  </link>\n\n  <joint name=\"top_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"top_link\" />\n  </joint>\n\n  <link name=\"top_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/top.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n    <collision>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/top.stl\"/>\n      </geometry>\n    </collision>\n  </link>\n\n  <joint name=\"axle_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 ${axle_offset}\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"axle_link\" />\n  </joint>\n\n  <link name=\"axle_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 ${PI/2} 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/axle.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <link name=\"imu_link\">\n    <inertial>\n      <mass value=\"0.001\"/>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n      <inertia ixx=\"${dummy_inertia}\" ixy=\"0.0\" ixz=\"0.0\" iyy=\"${dummy_inertia}\" iyz=\"0.0\" izz=\"${dummy_inertia}\"/>\n    </inertial>\n  </link>\n  <joint name=\"imu_joint\" type=\"fixed\">\n    <parent link=\"chassis_link\" />\n    <child link=\"imu_link\" />\n    <origin xyz=\"${imu_offset_x} ${imu_offset_y} ${imu_offset_z}\" rpy=\"0 0 0\"/>\n  </joint>\n\n  <link name=\"mid_mount\" />\n  <joint name=\"mid_mount_joint\" type=\"fixed\">\n    <parent link=\"base_link\" />\n    <child link=\"mid_mount\" />\n    <origin xyz=\"0 0 ${deck_height}\" rpy=\"0 0 0\"/>\n  </joint>\n\n  <!-- Bring in simulation data for Gazebo. -->\n  <xacro:include filename=\"$(find ridgeback_description)/urdf/ridgeback.gazebo\" />\n\n  <!-- Optional standard accessories, including their simulation data. The rendering\n       of these into the final description is controlled by optenv variables, which\n       default each one to off.-->\n  <xacro:include filename=\"$(find ridgeback_description)/urdf/accessories.urdf.xacro\" />\n\n  <xacro:include filename=\"$(find sm_ridgeback_barrel_search_1)/urdf/ridgeback.camera.gazebo\"/>\n\n  <xacro:gazebo_camera />\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_ridgeback_barrel_search_2\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Added gazebo camera changes to sm_opencv and sm_ridgeback_barrel_search_2\n* Merge branch 'master' into melodic-devel\n* fixing opencv demos and other minor issues\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency and adding scrollbars\n* adding xterm dependency to examples\n* improving opencv example state machines with the debug image showing the rectangle of the detected object\n* Added Readme's to OpenCV SM's\n* Began to implement new folder structure\n* Renaming OpenCV Perception Node Mains\n* Tweaking OpenCV SM's\n* New OpenCV based SM's\n* Contributors: Brett Aldrich, Pabo Iñigo Blasco, Unknown, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_ridgeback_barrel_search_2)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin cv_bridge)\n\n## System dependencies are found with CMake's conventions\nfind_package(OpenCV REQUIRED COMPONENTS )\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_ridgeback_barrel_search_2\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_ridgeback_barrel_search_2.cpp)\ntarget_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES})\n\nadd_executable(opencv_perception_node_${PROJECT_NAME} servers/opencv_perception_node/opencv_perception_node.cpp)\nset_target_properties(opencv_perception_node_${PROJECT_NAME} PROPERTIES OUTPUT_NAME \"opencv_perception_node\")\ntarget_link_libraries(opencv_perception_node_${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# catkin_install_python(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS ${PROJECT_NAME}_node opencv_perception_node_${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_ridgeback_barrel_search_2.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/README.md",
    "content": " <h2>State Machine Diagram</h2>\n<img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_ridgeback_barrel_search_2/docs/smacc_state_machine_20200822-022028.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n<h2>Description</h2> This example demonstrates the use of both OpenCV and MoveBase within the same state machine, with cross orthogonal communication between the navigation orthogonal and the perception orthogonal.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__moveit.html\">Doxygen Namespace & Class Reference</a>\n <br></br>\n\n <p align=\"center\">\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_ridgeback_barrel_search_2/docs/sm_ridgeback_barrel_search_2.JPG\" width=\"800\"/>\n </p>\n <br></br>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_ridgeback_barrel_search_2 sm_ridgeback_barrel_search_2.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/backward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nBackwardLocalPlanner:\n    k_rho: -1.5 # linear distance to the goal gain, default = -1.0 (related with carrot distance)\n    k_alpha: -0.1\n    k_betta: -1.0\n    carrot_distance: 0.3 #meters default 0.5\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.015 # 0.025\n    yaw_goal_tolerance: 0.3\n    pure_spinning_straight_line_mode: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.157\n  xy_goal_tolerance: 0.25\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/costmap_common_params.yaml",
    "content": "\nmap_type: costmap\norigin_z: 0.0\nz_resolution: 1\nz_voxels: 2\n\nobstacle_range: 12.5\nraytrace_range: 3.0\n\npublish_voxel_map: false\ntransform_tolerance: 0.5\nmeter_scoring: true\n\nfootprint: [[0.48, -0.40], [0.48, 0.40], [-0.48, 0.40], [-0.48, -0.40]]\nfootprint_padding: 0.3\n\nplugins:\n- {name: obstacles_layer, type: \"costmap_2d::ObstacleLayer\"}\n- {name: inflater_layer, type: \"costmap_2d::InflationLayer\"}\n\nobstacles_layer:\n  observation_sources: scan\n  scan: {sensor_frame: front_laser, data_type: LaserScan, topic: front/scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 10.5, raytrace_range: 3.0}\n\ninflater_layer:\n inflation_radius: 0.2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/forward_local_planner.yaml",
    "content": "# backwards configuration, the robot will move backwards\nForwardLocalPlanner:\n    k_rho: 1.0\n    k_alpha: -0.4\n    k_betta: -1.0\n    carrot_distance: 1.5 #meters\n    carrot_angular_distance: 0.5 # no constraint, max 3.1416\n    xy_goal_tolerance: 0.04\n    yaw_goal_tolerance: 0.01\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/global_costmap_params.yaml",
    "content": "global_costmap:\n  global_frame: odom\n  robot_base_frame: base_link\n  update_frequency: 20\n  publish_frequency: 5\n  width: 40.0\n  height: 40.0\n  resolution: 0.05\n  origin_x: -20.0\n  origin_y: -20.0\n  static_map: true\n  rolling_window: false\n  inflater_layer:\n    inflation_radius: 0.6\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: odom\n   robot_base_frame: base_link\n   update_frequency: 20.0\n   publish_frequency: 5.0\n   width: 10.0\n   height: 10.0\n   resolution: 0.05\n   static_map: false\n   rolling_window: true\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/move_base_client/waypoints_plan.yaml",
    "content": "waypoints:\n  # POINT 0\n  - position:\n      x: 3.46467864669\n      y: -1.99485644148\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.559672711157\n      w: 0.828713736091\n  - position:\n      x: 2.84283538036\n      y: -7.32575383645\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.997535137155\n      w: 0.070168726239\n  - position:\n      x: -7.11926213432\n      y: -7.9932196137\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: 0.439262428811\n      w: 0.898358791706\n  - position:\n      x: -9.28439676048\n      y: 1.41941615072\n      z: 0.0\n    orientation:\n      x: 0.0\n      y: 0.0\n      z: -0.228861605363\n      w: 0.973458969649\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/navigation.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 0\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Odometry1/Shape1\n        - /TF1/Frames1\n        - /SmaccRvizDisplay1\n        - /Image1\n      Splitter Ratio: 0.3861111104488373\n    Tree Height: 359\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nPreferences:\n  PromptSaveOnExit: true\nToolbars:\n  toolButtonStyle: 2\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 209; 209; 214\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 40\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.4000000059604645\n      Class: rviz/RobotModel\n      Collision Enabled: false\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        axle_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        base_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        camera_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        chassis_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_laser:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        front_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        imu_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        left_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        mid_mount:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n        rear_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_left_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_lights_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_right_wheel_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        rear_rocker_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        right_side_cover_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n        top_link:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n      Name: RobotModel\n      Robot Description: robot_description\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.25\n      Name: Axes\n      Radius: 0.05000000074505806\n      Reference Frame: odom\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.05000000074505806\n      Style: Flat Squares\n      Topic: front/scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: true\n      Enabled: false\n      Name: Costmaps\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Alpha: 1\n      Axes Length: 1\n      Axes Radius: 0.10000000149011612\n      Class: rviz/Pose\n      Color: 255; 0; 255\n      Enabled: true\n      Head Length: 0.20000000298023224\n      Head Radius: 0.10000000149011612\n      Name: MoveBase Goal\n      Shaft Length: 0.5\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow\n      Topic: /move_base/current_goal\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 85; 255\n      Enabled: true\n      Name: Polygon\n      Topic: /move_base/local_costmap/obstacles_layer_footprint/footprint_stamped\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: OdomTrackerPath\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /odom_tracker_path\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 255; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: FW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 255; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/ForwardGlobalPlanner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 170; 0\n      Enabled: true\n      Head Diameter: 0.029999999329447746\n      Head Length: 0.019999999552965164\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: BW Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 170; 0\n      Pose Style: Arrows\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.009999999776482582\n      Shaft Length: 0.10000000149011612\n      Topic: /backward_planner/global_plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Global Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/NavfnROS/plan\n      Unreliable: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Head Diameter: 0.30000001192092896\n      Head Length: 0.20000000298023224\n      Length: 0.30000001192092896\n      Line Style: Lines\n      Line Width: 0.029999999329447746\n      Name: ROS Local Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.029999999329447746\n      Shaft Diameter: 0.10000000149011612\n      Shaft Length: 0.10000000149011612\n      Topic: /move_base/TrajectoryPlannerROS/local_plan\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/ForwardLocalPlanner/goal_marker\n      Name: FW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/BackwardLocalPlanner/goal_marker\n      Name: BW Goal\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /move_base/backward_planner/markers\n      Name: BackwardMotionPlanner\n      Namespaces:\n        {}\n      Queue Size: 100\n      Value: true\n    - Angle Tolerance: 0.10000000149011612\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.30000001192092896\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 15000\n      Name: Odometry\n      Position Tolerance: 0.10000000149011612\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.10000000149011612\n        Color: 255; 25; 0\n        Head Length: 0.003000000026077032\n        Head Radius: 0\n        Shaft Length: 0.05000000074505806\n        Shaft Radius: 0.019999999552965164\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        axle_link:\n          Value: false\n        base_link:\n          Value: true\n        camera_link:\n          Value: true\n        chassis_link:\n          Value: false\n        front_cover_link:\n          Value: false\n        front_laser:\n          Value: false\n        front_left_wheel_link:\n          Value: false\n        front_lights_link:\n          Value: false\n        front_right_wheel_link:\n          Value: false\n        front_rocker_link:\n          Value: false\n        imu_link:\n          Value: false\n        left_side_cover_link:\n          Value: false\n        mid_mount:\n          Value: false\n        odom:\n          Value: true\n        rear_cover_link:\n          Value: false\n        rear_left_wheel_link:\n          Value: false\n        rear_lights_link:\n          Value: false\n        rear_right_wheel_link:\n          Value: false\n        rear_rocker_link:\n          Value: false\n        right_side_cover_link:\n          Value: false\n        top_link:\n          Value: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: false\n      Show Axes: true\n      Show Names: true\n      Tree:\n        odom:\n          base_link:\n            chassis_link:\n              axle_link:\n                front_rocker_link:\n                  front_left_wheel_link:\n                    {}\n                  front_right_wheel_link:\n                    {}\n                rear_rocker_link:\n                  rear_left_wheel_link:\n                    {}\n                  rear_right_wheel_link:\n                    {}\n              camera_link:\n                {}\n              front_cover_link:\n                {}\n              front_laser:\n                {}\n              front_lights_link:\n                {}\n              imu_link:\n                {}\n              left_side_cover_link:\n                {}\n              rear_cover_link:\n                {}\n              rear_lights_link:\n                {}\n              right_side_cover_link:\n                {}\n              top_link:\n                {}\n            mid_mount:\n              {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 25; 255; 0\n      Enabled: true\n      Name: GridCells\n      Topic: \"\"\n      Value: true\n    - Alpha: 1\n      Arrow Length: 0.30000001192092896\n      Axes Length: 0.30000001192092896\n      Axes Radius: 0.009999999776482582\n      Class: rviz/PoseArray\n      Color: 255; 25; 0\n      Enabled: true\n      Head Length: 0.07000000029802322\n      Head Radius: 0.029999999329447746\n      Name: Pose Estimation\n      Shaft Length: 0.23000000417232513\n      Shaft Radius: 0.009999999776482582\n      Shape: Arrow (Flat)\n      Topic: /particlecloud\n      Unreliable: false\n      Value: true\n    - Class: rviz/MarkerArray\n      Enabled: true\n      Marker Topic: /tool_markers\n      Name: MarkerArray\n      Namespaces:\n        {}\n      Queue Size: 1\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: Global Planner Costmap\n      Topic: /move_base/global_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 0.699999988079071\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: false\n      Name: LocalPlanner Costmap\n      Topic: /move_base/local_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: false\n    - Class: smacc_rviz_plugin/SmaccRvizDisplay\n      CurrentState: \"\"\n      Enabled: true\n      Name: SmaccRvizDisplay\n      Topic: /remap_smacc_status\n      Value: true\n    - Class: rviz/Image\n      Enabled: true\n      Image Topic: /opencv_debug_image\n      Max Value: 1\n      Median window: 5\n      Min Value: 0\n      Name: Image\n      Normalize Range: true\n      Queue Size: 2\n      Transport Hint: raw\n      Unreliable: false\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: odom\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Theta std deviation: 0.2617993950843811\n      Topic: /initialpose\n      X std deviation: 0.5\n      Y std deviation: 0.5\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: -0.005000012926757336\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Scale: 88.7320785522461\n      Target Frame: base_link\n      Value: TopDownOrtho (rviz)\n      X: 3.0729715824127197\n      Y: 0.5892993807792664\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1025\n  Hide Left Dock: false\n  Hide Right Dock: false\n  Image:\n    collapsed: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001ad00000363fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001a4000000c900fffffffb0000000a0049006d00610067006501000001e7000001b90000001600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000073d000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000058a0000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1853\n  X: 67\n  Y: 27\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/config/sm_ridgeback_barrel_search_2_config.yaml",
    "content": "SmRidgebackBarrelSearch2:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/clients/opencv_perception_client/cl_opencv_perception_client.h",
    "content": "#pragma once\n\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/Int32.h>\n\nnamespace sm_ridgeback_barrel_search_2\n{\nnamespace cl_opencv_perception\n{\nclass ClOpenCVPerception : public smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>\n{\npublic:\n\n  ClOpenCVPerception(std::string topicname = \"/detected_color\")\n    : smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>(topicname)\n  {\n  }\n\n  virtual ~ClOpenCVPerception()\n  {\n  }\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    smacc::client_bases::SmaccSubscriberClient<std_msgs::Int32>::onOrthogonalAllocation<TOrthogonal, TSourceObject>();\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/orthogonals/or_navigation.h",
    "content": "#pragma once\n\n#include <smacc/smacc_orthogonal.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n\n#include <move_base_z_client_plugin/components/odom_tracker/odom_tracker.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n#include <move_base_z_client_plugin/components/waypoints_navigator/waypoints_navigator.h>\n\nnamespace sm_ridgeback_barrel_search_2\n{\n    using namespace cl_move_base_z;\n\n    class OrNavigation : public smacc::Orthogonal<OrNavigation>\n    {\n    public:\n        virtual void onInitialize() override\n        {\n            auto movebaseClient = this->createClient<ClMoveBaseZ>();\n            movebaseClient->initialize();\n\n            movebaseClient->createComponent<Pose>();\n\n            // create planner switcher\n            movebaseClient->createComponent<PlannerSwitcher>();\n\n            // create odom tracker\n            movebaseClient->createComponent<cl_move_base_z::odom_tracker::OdomTracker>();\n\n            // create waypoints navigator component\n            auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();\n            loadWaypointsFromYaml(waypointsNavigator);\n\n            // change this to skip some points of the yaml file, default = 0\n            // waypointsNavigator->currentWaypoint_ = 3;\n        }\n\n        void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)\n        {\n            // if it is the first time and the waypoints navigator is not configured\n\n            std::string planfilepath;\n            ros::NodeHandle nh(\"~\");\n            if (nh.getParam(\"waypoints_plan\", planfilepath))\n            {\n                ROS_INFO(\"Loaded waypoints path file: %s\", planfilepath.c_str());\n                waypointsNavigator->loadWayPointsFromFile(planfilepath);\n            }\n            else\n            {\n                ROS_ERROR(\"Error while loading waypoints_path file: not found\");\n            }\n        }\n    };\n} // namespace sm_ridgeback_barrel_search_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/orthogonals/or_perception.h",
    "content": "#pragma once\n\n#include <sm_ridgeback_barrel_search_2/clients/opencv_perception_client/cl_opencv_perception_client.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_ridgeback_barrel_search_2\n{\nclass OrPerception : public smacc::Orthogonal<OrPerception>\n{\npublic:\n  virtual void onInitialize() override\n  {\n    auto opencvPerceptionClient = this->createClient<cl_opencv_perception::ClOpenCVPerception>();\n    opencvPerceptionClient->initialize();\n  }\n};\n}  // namespace sm_ridgeback_barrel_search_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/sm_ridgeback_barrel_search_2.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENT BEHAVIORS\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/client_behaviors.h>\n\n\nusing namespace cl_move_base_z;\n\n// ORTHOGONALS\n#include <sm_ridgeback_barrel_search_2/orthogonals/or_navigation.h>\n#include <sm_ridgeback_barrel_search_2/orthogonals/or_perception.h>\n\nusing namespace smacc;\nusing namespace smacc::default_events;\n\nnamespace sm_ridgeback_barrel_search_2\n{\n    class StNavigateToWaypointX;\n\nstruct SmRidgebackBarrelSearch2\n    : public smacc::SmaccStateMachineBase<SmRidgebackBarrelSearch2, StNavigateToWaypointX>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrNavigation>();\n        this->createOrthogonal<OrPerception>();\n    }\n};\n\n} // namespace sm_ridgeback_barrel_search_2\n\n\n//STATES\n#include <sm_ridgeback_barrel_search_2/states/st_detect_items.h>\n#include <sm_ridgeback_barrel_search_2/states/st_navigate_to_waypoint_x.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/states/st_detect_items.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ridgeback_barrel_search_2\n{\n// STATE DECLARATION\nstruct StDetectItems : smacc::SmaccState<StDetectItems, SmRidgebackBarrelSearch2>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<smacc::Transition<EvTopicMessage<cl_opencv_perception::ClOpenCVPerception, OrPerception>, StNavigateToWaypointX>>\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    //   configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n  }\n};\n}  // namespace sm_ridgeback_barrel_search_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/include/sm_ridgeback_barrel_search_2/states/st_navigate_to_waypoint_x.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_ridgeback_barrel_search_2\n{\n    using namespace smacc::default_events;\n    // STATE DECLARATION\n    struct StNavigateToWaypointX : smacc::SmaccState<StNavigateToWaypointX, SmRidgebackBarrelSearch2>\n    {\n        using SmaccState::SmaccState;\n\n        // TRANSITION TABLE\n        typedef mpl::list<\n\n            Transition<EvCbSuccess<CbNavigateNextWaypoint, OrNavigation>, StDetectItems>,\n            Transition<EvCbFailure<CbNavigateNextWaypoint, OrNavigation>, StNavigateToWaypointX>\n\n            >\n            reactions;\n\n        // STATE FUNCTIONS\n        static void staticConfigure()\n        {\n            // configure_orthogonal<OrLED, CbLEDOn>();\n            // configure_orthogonal<OrObstaclePerception, CbLidarSensor>();\n            configure_orthogonal<OrNavigation, CbNavigateNextWaypoint>();\n        }\n\n        void runtimeConfigure()\n        {\n        }\n    };\n} // namespace sm_ridgeback_barrel_search_2\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/launch/ridgeback_simulation.launch",
    "content": "<launch>\n    <arg name=\"use_sim_time\" default=\"true\" />\n    <arg name=\"gui\" default=\"true\" />\n    <arg name=\"headless\" default=\"false\" />\n    <arg name=\"world_name\" default=\"$(find sm_ridgeback_barrel_search_2)/simulation/worlds/opencv_world.sdf\" />\n\n    <!-- Configuration of Ridgeback which you would like to simulate.\n         See ridgeback_description for details. -->\n    <arg name=\"config\" default=\"$(optenv RIDGEBACK_CONFIG base)\" />\n\n    <!-- Launch Gazebo with the specified world -->\n    <include file=\"$(find gazebo_ros)/launch/empty_world.launch\">\n      <arg name=\"debug\" value=\"0\" />\n      <arg name=\"gui\" value=\"$(arg gui)\" />\n      <arg name=\"use_sim_time\" value=\"$(arg use_sim_time)\" />\n      <arg name=\"headless\" value=\"$(arg headless)\" />\n      <arg name=\"world_name\" value=\"$(arg world_name)\" />\n      <arg name=\"paused\" value=\"false\"/>\n    </include>\n\n    <param name=\"robot_description\"\n           command=\"$(find ridgeback_description)/scripts/env_run\n                    $(find ridgeback_description)/urdf/configs/$(arg config)\n                    $(find xacro)/xacro $(find sm_ridgeback_barrel_search_2)/urdf/ridgeback.urdf.xacro\n                    --inorder \" />\n\n    <node name=\"robot_state_publisher\" pkg=\"robot_state_publisher\" type=\"robot_state_publisher\" />\n\n    <include file=\"$(find ridgeback_control)/launch/control.launch\" />\n    <include file=\"$(find ridgeback_control)/launch/teleop.launch\">\n      <arg name=\"joystick\" value=\"false\"/>\n    </include>\n\n    <rosparam param=\"/gazebo_ros_control/pid_gains\">\n      front_left_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      front_right_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      rear_left_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n      rear_right_wheel:\n        p: 1\n        i: 0.1\n        d: 0\n    </rosparam>\n\n    <!-- Spawn Ridgeback -->\n    <node name=\"urdf_spawner\" pkg=\"gazebo_ros\" type=\"spawn_model\"\n          args=\"-urdf -model ridgeback -param robot_description -x 0 -y 0 -z 0.1\" />\n    <!--<node name=\"urdf_spawner\" pkg=\"gazebo_ros\" type=\"spawn_model\"\n          args=\"-sdf -model ridgeback -file /Users/mikepurvis/ridgeback_ws/ridgeback.sdf -x 0 -y 0 -z 0.1\" /> -->\n  </launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/launch/sm_ridgeback_barrel_search_2.launch",
    "content": "<launch>\n    <!--========= LAUNCH FILE ARGUMENTS ======================================================-->\n    <!-- defines the xterm parameters for the clients, set to empty to skip using xterm window-->\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -sl 10000 -hold -e\" />\n\n    <!-- defines the xterm parameters for the state machine, set to empty to skip using xterm window-->\n    <arg name=\"sm_xterm\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e\" />\n\n    <!-- if true, gazebo client is shown -->\n    <arg name=\"show_gz_client\" default=\"true\" />\n\n    <!-- if true, smacc_viewer is shown -->\n    <arg name=\"show_smacc_viewer\" default=\"true\" />\n\n    <!-- if true, rviz is shown -->\n    <arg name=\"show_rviz\" default=\"true\" />\n\n    <!-- It does not start the sm node in order to start it from your standalone process with debugger-->\n    <arg name=\"debug\" default=\"false\" />\n\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_ridgeback_barrel_search_2)/config/rosconsole.config\" />\n\n    <!--================================================================================-->\n    <!-- load the navigation environment simulated in gazebo-->\n    <include file=\"$(find sm_ridgeback_barrel_search_2)/launch/ridgeback_simulation.launch\">\n\n    </include>\n\n    <include file=\"$(find ridgeback_navigation)/launch/odom_navigation_demo.launch\"/>\n\n    <!-- <include file=\"$(find ridgeback_navigation)/launch/include/amcl.launch\" /> -->\n\n    <!-- load state machine parameters -->\n    <rosparam command=\"load\" file=\"$(find sm_ridgeback_barrel_search_2)/config/sm_ridgeback_barrel_search_2_config.yaml\" />\n\n    <!-- state machine node -->\n    <node pkg=\"sm_ridgeback_barrel_search_2\" type=\"sm_ridgeback_barrel_search_2_node\" name=\"sm_ridgeback_barrel_search_2\" launch-prefix=\"$(arg sm_xterm)\" unless=\"$(arg debug)\">\n        <param name=\"waypoints_plan\" value=\"$(find sm_ridgeback_barrel_search_2)/config/move_base_client/waypoints_plan.yaml\" />\n        <remap from=\"/odom\" to=\"/odometry/filtered\" />\n        <remap from=\"/sm_ridgeback_barrel_search_2/odom_tracker/odom_tracker_path\" to=\"/odom_tracker_path\"/>\n        <remap from=\"/sm_ridgeback_barrel_search_2/odom_tracker/odom_tracker_stacked_path\" to=\"/odom_tracker_path_stacked\"/>\n    </node>\n\n    <node pkg=\"sm_ridgeback_barrel_search_2\" type=\"opencv_perception_node\" name=\"opencv_perception_node\">\n        <remap from=\"image_raw\" to=\"/ridgeback/camera1/image_raw\"/>\n    </node>\n\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find sm_ridgeback_barrel_search_2)/config/navigation.rviz\" if=\"$(arg show_rviz)\">\n        <remap from=\"/remap_smacc_status\" to=\"/SmDanceBot/smacc/status\" />\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/msg/DetectedBlobs.msg",
    "content": ""
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_ridgeback_barrel_search_2</name>\n    <version>1.4.16</version>\n  <description>The sm_ridgeback_barrel_search_2 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>move_base_z_client_plugin</depend>\n  <depend>cv_bridge</depend>\n  <depend>ridgeback_gazebo</depend>\n  <depend>ridgeback_navigation</depend>\n  <depend>xterm</depend>\n  <export>\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/servers/opencv_perception_node/CMakeLists.txt2",
    "content": "cmake_minimum_required(VERSION 3.8)\n\nfind_package(OpenCV REQUIRED)\n\ninclude_directories($OpenCV_INCLUDE_DIRS)\n\nadd_executable(perception_node \"opencv_perception_node.cpp\")\n\ntarget_link_libraries(perception_node ${OpenCV_LIBRARIES})\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/servers/opencv_perception_node/opencv_perception_node.cpp",
    "content": "#include <cv_bridge/cv_bridge.h>\n#include <ros/ros.h>\n#include <sensor_msgs/Image.h>\n#include <std_msgs/Int32.h>\n#include <iostream>\n#include <opencv2/opencv.hpp>\n#include <opencv2/features2d.hpp>\n\nros::Publisher detectionPub;\nros::Publisher debugImagePub;\nros::Subscriber imageSub;\n\nvoid segmentColor(const cv::Mat& inputRGB, int hueMean, int hueWindow, cv::Mat& out)\n{\n  cv::Mat hsvInput;\n  cv::cvtColor(inputRGB, hsvInput, cv::COLOR_BGR2HSV);\n  cv::inRange(hsvInput, cv::Scalar(hueMean - hueWindow, 20, 20), cv::Scalar(hueMean + hueWindow, 255, 255), out);\n  cv::threshold(out, out, 100, 255, cv::THRESH_BINARY);\n}\n\nint testImage(cv::Mat& input, cv::Mat& debugImage, std::string colorName, int hueMean, int hueWindow)\n{\n  cv::Mat segmented;\n\n  segmentColor(input, hueMean, hueWindow, segmented);\n\n  cv::SimpleBlobDetector::Params params;\n  // params.filterByArea= true;\n  // params.minArea = 10;\n  params.filterByArea = true;\n  params.minArea = 100;\n  params.maxArea = 100000;\n  params.filterByColor = true;\n  params.blobColor = 255;\n\n  auto blobDetector = cv::SimpleBlobDetector::create(params);\n  std::vector<cv::KeyPoint> blobs;\n  blobDetector->detect(segmented, blobs);\n\n  std::cout << \"-------\" << std::endl;\n  for (auto& b : blobs)\n  {\n    std::cout << \"blob \" << colorName << \" detected: \" << b.size << std::endl;\n  }\n\n  if(!blobs.empty())\n  {\n    auto& b = blobs.front();\n    cv::Rect r;\n    float diameter = b.size;\n    auto radius = diameter*0.5;\n    r.x = b.pt.x - radius;\n    r.y = b.pt.y - radius;\n    r.width = diameter;\n    r.height = diameter;\n    cv::rectangle(debugImage,r, cv::Scalar(255,0,0),1 );\n  }\n\n  // cv::imshow(colorName + \" filter - \"+ path, segmented);\n  // cv::waitKey();\n\n  return blobs.size();\n}\n\nint testRed(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"red\", 130, 20);\n}\n\nint testBlue(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"blue\", 10, 10);\n}\n\nint testGreen(cv::Mat& input, cv::Mat& debugImage)\n{\n  return testImage(input, debugImage, \"green\", 50, 10);\n}\n\nint testRed(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"red\", 130, 20);\n}\n\nint testBlue(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"blue\", 10, 10);\n}\n\nint testGreen(std::string path, cv::Mat& debugImage)\n{\n  cv::Mat input = cv::imread(path);\n  return testImage(input, debugImage, \"green\", 50, 10);\n}\n\nvoid update()\n{\n}\n\nvoid callback(const sensor_msgs::Image& img)\n{\n  cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(img, \"rgb8\");\n\n  cv::Mat image = cv_image->image;\n  cv_bridge::CvImage debugImageBridge;\n  debugImageBridge.encoding = \"rgb8\";\n  debugImageBridge.image = image.clone();\n\n  int detectedColor = 0;\n  if (testRed(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 1;\n  }\n  else if (testGreen(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 2;\n  }\n  else if (testBlue(image, debugImageBridge.image) > 0)\n  {\n    detectedColor = 3;\n  }\n\n  std_msgs::Int32 detectedColorMsg;\n  detectedColorMsg.data = detectedColor;\n  detectionPub.publish(detectedColorMsg);\n\n  debugImageBridge.header = img.header;\n  debugImagePub.publish(debugImageBridge.toImageMsg());\n}\n\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"blob_detector_node\");\n  ros::NodeHandle nh;\n\n  detectionPub = nh.advertise<std_msgs::Int32>(\"detected_color\", 1);\n  imageSub = nh.subscribe(\"/image_raw\", 1, callback);\n  debugImagePub = nh.advertise<sensor_msgs::Image>(\"/opencv_debug_image\", 1);\n\n  ros::Rate r(10);\n\n  while (ros::ok())\n  {\n    update();\n    ros::spinOnce();\n    r.sleep();\n  }\n\n  /*\n  testRed(\"../../red1.png\");\n  testRed(\"../../green1.png\");\n  testRed(\"../../blue1.png\");\n  testRed(\"../../red2.png\");\n\n  testGreen(\"../../red1.png\");\n  testGreen(\"../../green1.png\");\n  testGreen(\"../../blue1.png\");\n  testGreen(\"../../red2.png\");\n\n  testBlue(\"../../red1.png\");\n  testBlue(\"../../green1.png\");\n  testBlue(\"../../blue1.png\");\n  testBlue(\"../../red2.png\");\n  */\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/simulation/worlds/opencv_world.sdf",
    "content": "<sdf version='1.6'>\n  <world name='default'>\n    <light name='sun' type='directional'>\n      <cast_shadows>1</cast_shadows>\n      <pose frame=''>0 0 10 0 -0 0</pose>\n      <diffuse>0.8 0.8 0.8 1</diffuse>\n      <specular>0.2 0.2 0.2 1</specular>\n      <attenuation>\n        <range>1000</range>\n        <constant>0.9</constant>\n        <linear>0.01</linear>\n        <quadratic>0.001</quadratic>\n      </attenuation>\n      <direction>-0.5 0.1 -0.9</direction>\n    </light>\n    <model name='ground_plane'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>100 100</size>\n            </plane>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>100</mu>\n                <mu2>50</mu2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <bounce/>\n            <contact>\n              <ode/>\n            </contact>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <visual name='visual'>\n          <cast_shadows>0</cast_shadows>\n          <geometry>\n            <plane>\n              <normal>0 0 1</normal>\n              <size>100 100</size>\n            </plane>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n          </material>\n        </visual>\n        <velocity_decay>\n          <linear>0</linear>\n          <angular>0</angular>\n        </velocity_decay>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n    </model>\n    <physics name='default_physics' default='0' type='ode'>\n      <max_step_size>0.001</max_step_size>\n      <real_time_factor>1</real_time_factor>\n      <real_time_update_rate>1000</real_time_update_rate>\n    </physics>\n    <scene>\n      <ambient>0.4 0.4 0.4 1</ambient>\n      <background>0.7 0.7 0.7 1</background>\n      <shadows>1</shadows>\n    </scene>\n    <spherical_coordinates>\n      <surface_model>EARTH_WGS84</surface_model>\n      <latitude_deg>0</latitude_deg>\n      <longitude_deg>0</longitude_deg>\n      <elevation>0</elevation>\n      <heading_deg>0</heading_deg>\n    </spherical_coordinates>\n    <state world_name='default'>\n      <sim_time>5547 272000000</sim_time>\n      <real_time>662 779421085</real_time>\n      <wall_time>1589617063 947492641</wall_time>\n      <iterations>373284</iterations>\n      <model name='BlueBarrel'>\n        <pose frame=''>-4.75702 -0.60021 0.499996 -2e-06 2e-06 -0.035996</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0_0'>\n          <pose frame=''>-4.75702 -0.60021 0.499996 -2e-06 2e-06 -0.035996</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='Dumpster'>\n        <pose frame=''>-29.3577 -14.8022 0.001376 2e-06 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-29.3577 -14.8022 0.001376 2e-06 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='GreenBarrel'>\n        <pose frame=''>-2.60736 -4.13429 0.499991 -0 -0 -0</pose>\n        <scale>1 1 1</scale>\n        <link name='link_1'>\n          <pose frame=''>-2.60736 -4.13429 0.499991 -0 -0 -0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='Lamp Post'>\n        <pose frame=''>-3.8889 4.97621 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.8889 4.97621 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='Lamp Post_0'>\n        <pose frame=''>-7.65374 2.42933 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-7.65374 2.42933 -0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='Lamp Post_1'>\n        <pose frame=''>-34.6742 4.63066 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-34.6742 4.63066 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='RedBarrel'>\n        <pose frame=''>-4.56456 -2.64972 0.499992 -3e-06 -1e-06 0.002242</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0'>\n          <pose frame=''>-4.56456 -2.64972 0.499992 -3e-06 -1e-06 0.002242</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='RedBarrel_0'>\n        <pose frame=''>2.74614 3.30158 0.5 0 0 -3.4e-05</pose>\n        <scale>1 1 1</scale>\n        <link name='link_0'>\n          <pose frame=''>2.74614 3.30158 0.5 0 0 -3.4e-05</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 -9.8 0 -0 0</acceleration>\n          <wrench>0 0 -9.8 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='collapsed_fire_station'>\n        <pose frame=''>-4.91313 29.544 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-4.91313 29.544 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='collapsed_house'>\n        <pose frame=''>-24.3321 12.813 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-24.3321 12.813 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='collapsed_industrial'>\n        <pose frame=''>-21.192 -23.1741 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-21.192 -23.1741 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='collapsed_police_station'>\n        <pose frame=''>24.1418 10.6792 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>24.1418 10.6792 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='ground_plane'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier'>\n        <pose frame=''>-7.98027 5.74165 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-7.98027 5.74165 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_0'>\n        <pose frame=''>-3.82665 5.59964 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.82665 5.59964 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_1'>\n        <pose frame=''>-0.173755 4.06589 0 0 0 -0.788711</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-0.173755 4.06589 0 0 0 -0.788711</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_2'>\n        <pose frame=''>-3.73179 -0.407188 0 0 0 -1.53901</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.73179 -0.407188 0 0 0 -1.53901</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_3'>\n        <pose frame=''>-6.26014 -1.71307 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-6.26014 -1.71307 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4'>\n        <pose frame=''>-1.16178 -2.12305 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-1.16178 -2.12305 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone'>\n        <pose frame=''>3.93424 -15.7558 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>3.93424 -15.7558 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_0'>\n        <pose frame=''>8.36075 -15.8115 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>8.36075 -15.8115 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_1'>\n        <pose frame=''>12.7963 -16.0046 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>12.7963 -16.0046 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_1_clone'>\n        <pose frame=''>12.2167 27.0293 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>12.2167 27.0293 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_1_clone_0'>\n        <pose frame=''>16.6463 26.9914 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>16.6463 26.9914 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_1_clone_1'>\n        <pose frame=''>21.1348 26.8869 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>21.1348 26.8869 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_1_clone_2'>\n        <pose frame=''>25.9366 26.953 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>25.9366 26.953 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_2'>\n        <pose frame=''>17.1574 -15.9183 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>17.1574 -15.9183 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_4_clone_3'>\n        <pose frame=''>21.321 -15.8712 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>21.321 -15.8712 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5'>\n        <pose frame=''>-3.56534 -4.56105 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.56534 -4.56105 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone'>\n        <pose frame=''>1.39245 -17.4731 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>1.39245 -17.4731 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_0'>\n        <pose frame=''>1.65386 -21.9382 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>1.65386 -21.9382 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_1'>\n        <pose frame=''>2.02401 -26.5573 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>2.02401 -26.5573 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_2'>\n        <pose frame=''>2.49775 -31.3259 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>2.49775 -31.3259 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_3'>\n        <pose frame=''>23.9218 -14.2164 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>23.9218 -14.2164 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_4'>\n        <pose frame=''>23.6135 -8.79449 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>23.6135 -8.79449 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_5'>\n        <pose frame=''>-32.2131 1.68011 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-32.2131 1.68011 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_6'>\n        <pose frame=''>-32.1347 -2.79168 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-32.1347 -2.79168 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_7'>\n        <pose frame=''>-32.1268 -7.26736 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-32.1268 -7.26736 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_5_clone_8'>\n        <pose frame=''>-31.834 -11.6836 0 0 0 -1.52415</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-31.834 -11.6836 0 0 0 -1.52415</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='jersey_barrier_6'>\n        <pose frame=''>-6.24135 1.32488 0 0 0 -0.414923</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-6.24135 1.32488 0 0 0 -0.414923</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='pickup'>\n        <pose frame=''>-25.4727 -11.7368 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-25.4727 -11.7368 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='polaris_ranger_xp900'>\n        <pose frame=''>-32.1938 5.47156 -0.027848 -3e-06 2.3e-05 -2.2e-05</pose>\n        <scale>1 1 1</scale>\n        <link name='FNR_switch'>\n          <pose frame=''>-31.6537 5.57156 1.12214 -3e-06 0.189404 -2.3e-05</pose>\n          <velocity>0.004702 -9.1e-05 -0.005568 0.000104 -0.00194 -2.8e-05</velocity>\n          <acceleration>-0.000615 -1.3e-05 1e-06 1.6e-05 1e-06 -1e-06</acceleration>\n          <wrench>-6.1e-05 -1e-06 0 0 -0 0</wrench>\n        </link>\n        <link name='brake_pedal'>\n          <pose frame=''>-31.4851 5.74155 0.510975 -4e-06 2.4e-05 -2.2e-05</pose>\n          <velocity>0.005892 -3.4e-05 -0.005214 0.000136 -0.002029 -2.5e-05</velocity>\n          <acceleration>-0.000614 -4e-06 4e-06 1.6e-05 -0 -1e-06</acceleration>\n          <wrench>-6.1e-05 -0 0 0 -0 0</wrench>\n        </link>\n        <link name='chassis'>\n          <pose frame=''>-32.1938 5.47156 -0.027848 -3e-06 2.3e-05 -2.2e-05</pose>\n          <velocity>0.006941 4.3e-05 -0.006646 0.000102 -0.00194 -2.7e-05</velocity>\n          <acceleration>-0.000615 -1e-06 -1e-06 1.6e-05 -0 -1e-06</acceleration>\n          <wrench>-0.442657 -0.000584 -0.000387 0 -0 0</wrench>\n        </link>\n        <link name='front_left_wheel'>\n          <pose frame=''>-30.9901 6.18714 0.319143 -1.51645 0.368413 0.012604</pose>\n          <velocity>0.00637 0.00012 -0.007884 0.000986 0.019926 0.00075</velocity>\n          <acceleration>-0.000609 -3e-06 -1.1e-05 1.3e-05 -0.000959 -0.00019</acceleration>\n          <wrench>-0.007309 -4e-05 -0.000134 0 -0 0</wrench>\n        </link>\n        <link name='front_left_wheel_steering_block'>\n          <pose frame=''>-30.9915 5.97153 0.327336 1.5708 2.3e-05 -0.006683</pose>\n          <velocity>0.006281 0.000117 -0.008766 -0.000323 -0.001933 -0.000348</velocity>\n          <acceleration>-0.000614 -3e-06 -2e-05 1.2e-05 -0 -2.3e-05</acceleration>\n          <wrench>-0.000614 -3e-06 -2e-05 0 -0 0</wrench>\n        </link>\n        <link name='front_right_wheel'>\n          <pose frame=''>-30.9905 4.75593 0.319145 1.51645 0.3678 -0.014456</pose>\n          <velocity>0.006329 -0.000191 -0.007633 -0.00072 0.019823 -0.000806</velocity>\n          <acceleration>-0.000611 -3e-06 1e-05 1.2e-05 -0.000961 0.000184</acceleration>\n          <wrench>-0.007333 -4.1e-05 0.000115 0 -0 0</wrench>\n        </link>\n        <link name='front_right_wheel_steering_block'>\n          <pose frame=''>-30.9915 4.97155 0.327336 1.57079 2.3e-05 0.004799</pose>\n          <velocity>0.006252 -0.000192 -0.008373 0.000497 -0.001946 0.000288</velocity>\n          <acceleration>-0.000615 -4e-06 1.8e-05 1.2e-05 0 2e-05</acceleration>\n          <wrench>-0.000615 -4e-06 1.8e-05 0 -0 0</wrench>\n        </link>\n        <link name='gas_pedal'>\n          <pose frame=''>-31.5072 5.57155 0.495567 -4e-06 2.4e-05 -2.2e-05</pose>\n          <velocity>0.005917 -3.1e-05 -0.005278 0.000117 -0.002031 -2.6e-05</velocity>\n          <acceleration>-0.000615 -3e-06 1e-06 1.6e-05 -0 -1e-06</acceleration>\n          <wrench>-6.1e-05 -0 0 0 -0 0</wrench>\n        </link>\n        <link name='hand_brake'>\n          <pose frame=''>-31.6637 5.67656 1.02214 -3e-06 -0.060726 -2.2e-05</pose>\n          <velocity>0.0049 -8e-05 -0.005577 0.000104 -0.00194 -2.8e-05</velocity>\n          <acceleration>-0.000614 -1.2e-05 3e-06 1.6e-05 -0 -2e-06</acceleration>\n          <wrench>-0.000307 -6e-06 1e-06 0 -0 0</wrench>\n        </link>\n        <link name='rear_left_wheel'>\n          <pose frame=''>-33.1875 6.18721 0.319143 -1.51645 0.366474 0.019167</pose>\n          <velocity>0.006291 0.000131 -0.00853 0.000928 0.019814 0.001073</velocity>\n          <acceleration>-0.000614 -0 1.2e-05 0 -0.00535 -0.000875</acceleration>\n          <wrench>-0.007367 -6e-06 0.000141 0 -0 0</wrench>\n        </link>\n        <link name='rear_right_wheel'>\n          <pose frame=''>-33.1875 4.75597 0.319142 1.51644 0.366492 -0.019213</pose>\n          <velocity>0.006254 -9.7e-05 -0.008661 -0.001066 0.019717 -0.00112</velocity>\n          <acceleration>-0.000616 -0 -1.2e-05 -5e-06 0.003427 -0.000469</acceleration>\n          <wrench>-0.007391 -4e-06 -0.000145 0 -0 0</wrench>\n        </link>\n        <link name='steering_wheel'>\n          <pose frame=''>-31.7737 5.93156 1.17214 -4.1e-05 -0.869977 2.9e-05</pose>\n          <velocity>0.004614 -9.3e-05 -0.005766 0.000103 -0.001956 -2.7e-05</velocity>\n          <acceleration>-0.000614 -1.4e-05 7e-06 4e-06 -0 1e-06</acceleration>\n          <wrench>-0.000614 -1.4e-05 7e-06 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='radio_tower'>\n        <pose frame=''>-43.2862 -5.42772 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-43.2862 -5.42772 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <model name='suv'>\n        <pose frame=''>-3.90558 -17.9855 0 0 -0 0</pose>\n        <scale>1 1 1</scale>\n        <link name='link'>\n          <pose frame=''>-3.90558 -17.9855 0 0 -0 0</pose>\n          <velocity>0 0 0 0 -0 0</velocity>\n          <acceleration>0 0 0 0 -0 0</acceleration>\n          <wrench>0 0 0 0 -0 0</wrench>\n        </link>\n      </model>\n      <light name='sun'>\n        <pose frame=''>0 0 10 0 -0 0</pose>\n      </light>\n      <light name='user_point_light_0'>\n        <pose frame=''>-16.8472 -0.68818 2.02228 0 -0 0</pose>\n      </light>\n    </state>\n    <gui fullscreen='0'>\n      <camera name='user_camera'>\n        <pose frame=''>32.3638 -6.5704 31.4571 0 0.719249 2.95951</pose>\n        <view_controller>orbit</view_controller>\n        <projection_type>perspective</projection_type>\n      </camera>\n    </gui>\n    <gravity>0 0 -9.8</gravity>\n    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>\n    <atmosphere type='adiabatic'/>\n    <model name='jersey_barrier_0'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-3.82665 5.59964 0 0 -0 0</pose>\n    </model>\n    <model name='Lamp Post'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-3.8889 1.15752 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-7.98027 5.74165 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_1'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>0.244845 5.38664 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_2'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-3.73179 -0.407188 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_3'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-6.18482 -2.18469 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-1.16178 -2.12305 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_5'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-3.56534 -4.56105 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_6'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-6.01027 1.86999 0 0 -0 0</pose>\n    </model>\n    <model name='BlueBarrel'>\n      <link name='link_0_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 0 1 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-5.78287 -0.024618 0 0 -0 0</pose>\n    </model>\n    <model name='RedBarrel'>\n      <link name='link_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Red</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>1 0 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-5.22409 -3.90999 0 0 -0 0</pose>\n    </model>\n    <model name='GreenBarrel'>\n      <link name='link_1'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <gravity>1</gravity>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Grey</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>0 1 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>-1.66636 -4.13429 0 0 -0 0</pose>\n    </model>\n    <model name='RedBarrel_0'>\n      <link name='link_0'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>0.145833</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.145833</iyy>\n            <iyz>0</iyz>\n            <izz>0.125</izz>\n          </inertia>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n        </inertial>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <material>\n            <lighting>1</lighting>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/Red</name>\n            </script>\n            <ambient>0.3 0.3 0.3 1</ambient>\n            <diffuse>1 0 0 1</diffuse>\n            <specular>0.01 0.01 0.01 1</specular>\n            <emissive>0 0 0 1</emissive>\n            <shader type='vertex'>\n              <normal_map>__default__</normal_map>\n            </shader>\n          </material>\n          <cast_shadows>1</cast_shadows>\n          <transparency>0</transparency>\n        </visual>\n        <collision name='collision'>\n          <laser_retro>0</laser_retro>\n          <max_contacts>10</max_contacts>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <geometry>\n            <cylinder>\n              <radius>0.5</radius>\n              <length>1</length>\n            </cylinder>\n          </geometry>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 0</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <coefficient>1</coefficient>\n                <patch_radius>0</patch_radius>\n                <surface_radius>0</surface_radius>\n                <use_patch_radius>1</use_patch_radius>\n                <ode>\n                  <slip>0</slip>\n                </ode>\n              </torsional>\n            </friction>\n            <bounce>\n              <restitution_coefficient>0</restitution_coefficient>\n              <threshold>1e+06</threshold>\n            </bounce>\n            <contact>\n              <collide_without_contact>0</collide_without_contact>\n              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>\n              <collide_bitmask>1</collide_bitmask>\n              <ode>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n                <max_vel>0.01</max_vel>\n                <min_depth>0</min_depth>\n              </ode>\n              <bullet>\n                <split_impulse>1</split_impulse>\n                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>\n                <soft_cfm>0</soft_cfm>\n                <soft_erp>0.2</soft_erp>\n                <kp>1e+13</kp>\n                <kd>1</kd>\n              </bullet>\n            </contact>\n          </surface>\n        </collision>\n        <enable_wind>0</enable_wind>\n      </link>\n      <static>0</static>\n      <allow_auto_disable>1</allow_auto_disable>\n      <pose frame=''>2.72763 3.3635 0 0 -0 0</pose>\n    </model>\n    <light name='user_point_light_0' type='point'>\n      <pose frame=''>-15.9446 0.086762 1 0 -0 0</pose>\n      <diffuse>0.5 0.5 0.5 1</diffuse>\n      <specular>0.1 0.1 0.1 1</specular>\n      <attenuation>\n        <range>20</range>\n        <constant>0.5</constant>\n        <linear>0.01</linear>\n        <quadratic>0.001</quadratic>\n      </attenuation>\n      <cast_shadows>0</cast_shadows>\n      <direction>0 0 -1</direction>\n    </light>\n    <model name='Lamp Post_0'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-8.13567 1.9188 0 0 -0 0</pose>\n    </model>\n    <audio>\n      <device>default</device>\n    </audio>\n    <wind/>\n    <model name='collapsed_industrial'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_industrial/meshes/collapsed_industrial.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_industrial/meshes/collapsed_industrial.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-21.192 -14.1741 0 0 -0 0</pose>\n    </model>\n    <model name='collapsed_house'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <scale>1.5 1.5 1.5</scale>\n              <uri>model://collapsed_house/meshes/collapsed_house.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <scale>1.5 1.5 1.5</scale>\n              <uri>model://collapsed_house/meshes/collapsed_house.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-26.3321 12.813 0 0 -0 0</pose>\n    </model>\n    <model name='collapsed_fire_station'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_fire_station/meshes/collapsed_fire_station.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_fire_station/meshes/collapsed_fire_station.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-4.91313 22.544 0 0 -0 0</pose>\n    </model>\n    <model name='collapsed_police_station'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_police_station/meshes/collapsed_police_station.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://collapsed_police_station/meshes/collapsed_police_station.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>24.1418 10.6792 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>3.93424 -15.7558 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>8.36075 -15.8115 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>12.7963 -16.0046 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>17.1574 -15.9183 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>21.321 -15.8712 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_5_clone'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>1.39245 -17.4731 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>1.65386 -21.9382 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>2.02401 -26.5573 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>2.49775 -31.3259 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_3'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>23.9218 -14.2164 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_4'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>23.6135 -8.79449 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_5'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-32.2131 1.68011 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_6'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-32.1347 -2.79168 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_7'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-32.1268 -7.26736 0 0 0 -1.52415</pose>\n    </model>\n    <model name='jersey_barrier_5_clone_8'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>-31.834 -11.6836 0 0 0 -1.52415</pose>\n    </model>\n    <model name='Lamp Post_1'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>3 3 3</scale>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://lamp_post/meshes/lamp_post.dae</uri>\n              <scale>3 3 3</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-34.6742 4.63066 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_1_clone'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>12.2167 27.0293 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_1_clone_0'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>16.6463 26.9914 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_1_clone_1'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>21.1348 26.8869 0 0 -0 0</pose>\n    </model>\n    <model name='jersey_barrier_4_clone_1_clone_2'>\n      <static>1</static>\n      <link name='link'>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://jersey_barrier/meshes/jersey_barrier.dae</uri>\n              <scale>1 1 1</scale>\n            </mesh>\n          </geometry>\n        </visual>\n        <collision name='upright'>\n          <pose frame=''>0 0 0.5715 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.3063 1.143</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base'>\n          <pose frame=''>0 0 0.032258 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.8107 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base2'>\n          <pose frame=''>0 0 0.1 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.65 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='base3'>\n          <pose frame=''>0 0 0.2 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='left-angle'>\n          <pose frame=''>0 -0.224 0.2401 0.9 -0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='right-angle'>\n          <pose frame=''>0 0.224 0.2401 -0.9 0 0</pose>\n          <geometry>\n            <box>\n              <size>4.06542 0.5 0.064516</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <kinematic>0</kinematic>\n        <gravity>1</gravity>\n        <enable_wind>0</enable_wind>\n      </link>\n      <pose frame=''>25.9366 26.953 0 0 -0 0</pose>\n    </model>\n    <model name='Dumpster'>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <scale>1.5 1.5 1.5</scale>\n              <uri>model://dumpster/meshes/dumpster.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <scale>1.5 1.5 1.5</scale>\n              <uri>model://dumpster/meshes/dumpster.dae</uri>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://dumpster/materials/scripts</uri>\n              <uri>model://dumpster/materials/textures</uri>\n              <name>Dumpster/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <inertial>\n          <inertia>\n            <ixx>1</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>1</iyy>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n          <mass>1</mass>\n        </inertial>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-29.3577 -14.8022 0 0 -0 0</pose>\n    </model>\n    <model name='pickup'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <pose frame=''>0 0 0 0 0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://pickup/meshes/pickup.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://pickup/meshes/pickup.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-25.4727 -11.7368 0 0 -0 0</pose>\n    </model>\n    <model name='polaris_ranger_xp900'>\n      <static>0</static>\n      <link name='chassis'>\n        <inertial>\n          <mass>720</mass>\n          <inertia>\n            <ixx>140</ixx>\n            <ixy>0</ixy>\n            <iyy>550</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>550</izz>\n          </inertia>\n          <pose frame=''>0.1 0 0.4 0 -0 0</pose>\n        </inertial>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900_no_roll_cage/meshes/chasis.dae</uri>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <collision name='chassis_bottom'>\n          <pose frame=''>0.2 0 0.335 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>1.34 1.65746 0.06</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='cargo_bottom'>\n          <pose frame=''>-1 0 0.921 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>1.04609 1.6998 0.01</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='cargo_front'>\n          <pose frame=''>-0.495 0 1.06 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.05 1.69982 0.27</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='cargo_back'>\n          <pose frame=''>-1.465 0 1.06 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.05 1.69982 0.27</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='cargo_left'>\n          <pose frame=''>-0.97 0.82491 1.06 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>1.04609 0.05 0.27</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='cargo_right'>\n          <pose frame=''>-0.97 -0.82491 1.06 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>1.04609 0.05 0.27</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='seat'>\n          <pose frame=''>0 0 0.62 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.52167 1.37206 0.53369</size>\n            </box>\n          </geometry>\n          <surface>\n            <contact>\n              <ode>\n                <min_depth>0.01</min_depth>\n              </ode>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <collision name='mud_seat'>\n          <pose frame=''>0 0 0.86 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.52167 1.3 0.1</size>\n            </box>\n          </geometry>\n          <surface>\n            <contact>\n              <collide_without_contact>1</collide_without_contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <sensor name='seat_contact' type='contact'>\n          <always_on>1</always_on>\n          <update_rate>1000</update_rate>\n          <contact>\n            <collision>mud_seat</collision>\n            <topic>__default_topic__</topic>\n          </contact>\n        </sensor>\n        <collision name='seat_back'>\n          <pose frame=''>-0.26 0 1.125 0 -0.2 0</pose>\n          <geometry>\n            <box>\n              <size>0.06 1.37206 0.6</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='engine'>\n          <pose frame=''>1.12 0 0.7 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.58 1.3 0.8</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump1_collision'>\n          <pose frame=''>0.55 -0.1 0.4 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.6 0.15 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump2_collision'>\n          <pose frame=''>0.7 -0.05 0.45 0 -0.5 0</pose>\n          <geometry>\n            <box>\n              <size>0.2 0.05 0.1</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump3_collision'>\n          <pose frame=''>0.798 -0.125 0.478 0 -0.8 0</pose>\n          <geometry>\n            <box>\n              <size>0.129 0.1 0.05</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump4_collision'>\n          <pose frame=''>0.8135 -0.05 0.45 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.1 0.05 0.1835</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump5_collision'>\n          <pose frame=''>0.84 -0.125 0.45 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.03 0.1 0.1835</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <collision name='central_hump6_collision'>\n          <pose frame=''>0.82 -0.125 0.475 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.03 0.1 0.05</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='cargo_visual'>\n          <pose frame=''>-1 0 1.0323 0 0 -1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Bed</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='tailgate_visual'>\n          <pose frame=''>-1.492 0 1.03 0 0 -1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Tail_Gate</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='front_left_brake_visual'>\n          <pose frame=''>1.12 -0.57488 0.35516 3.1415 -0 1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Brake_Front_Left</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='front_right_brake_visual'>\n          <pose frame=''>1.12 0.57488 0.35516 3.1415 -0 1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Brake_Front_Right</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump1'>\n          <pose frame=''>0.55 -0.1 0.4 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.6 0.15 0.1</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump2'>\n          <pose frame=''>0.7 -0.05 0.45 0 -0.5 0</pose>\n          <geometry>\n            <box>\n              <size>0.2 0.05 0.1</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump3'>\n          <pose frame=''>0.798 -0.125 0.478 0 -0.8 0</pose>\n          <geometry>\n            <box>\n              <size>0.129 0.1 0.05</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump4'>\n          <pose frame=''>0.8135 -0.05 0.45 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.1 0.05 0.1835</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump5'>\n          <pose frame=''>0.84 -0.125 0.45 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.03 0.1 0.1835</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='central_hump6'>\n          <pose frame=''>0.82 -0.125 0.475 0 -0 0</pose>\n          <geometry>\n            <box>\n              <size>0.03 0.1 0.05</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>file://media/materials/scripts/gazebo.material</uri>\n              <name>Gazebo/DarkGrey</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='front_left_wheel'>\n        <pose frame=''>1.20223 0.71562 0.34697 -1.52 0 0</pose>\n        <inertial>\n          <mass>12</mass>\n          <inertia>\n            <ixx>0.5</ixx>\n            <ixy>0</ixy>\n            <iyy>0.5</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.3175</radius>\n              <length>0.2794</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>1</max_contacts>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 1</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <contact>\n              <ode>\n                <min_depth>0.005</min_depth>\n                <kp>1e+08</kp>\n              </ode>\n            </contact>\n            <bounce/>\n          </surface>\n        </collision>\n        <visual name='tire_visual'>\n          <pose frame=''>0 0 0 -3e-06 1.57079 3.14159</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <scale>1.0037 0.8862 0.8862</scale>\n              <submesh>\n                <name>Wheel_Front_Left</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='front_right_wheel'>\n        <pose frame=''>1.20223 -0.71562 0.34697 1.52 -0 0</pose>\n        <inertial>\n          <mass>12</mass>\n          <inertia>\n            <ixx>0.5</ixx>\n            <ixy>0</ixy>\n            <iyy>0.5</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.3175</radius>\n              <length>0.2794</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>1</max_contacts>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 1</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <contact>\n              <ode>\n                <min_depth>0.005</min_depth>\n                <kp>1e+08</kp>\n              </ode>\n            </contact>\n            <bounce/>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 3.14159 -1.57079 3.14159</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <scale>1.0037 0.8862 0.8862</scale>\n              <submesh>\n                <name>Wheel_Front_Right</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='rear_left_wheel'>\n        <pose frame=''>-0.99377 0.71562 0.34697 -1.52 0 0</pose>\n        <inertial>\n          <mass>12</mass>\n          <inertia>\n            <ixx>0.5</ixx>\n            <ixy>0</ixy>\n            <iyy>0.5</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.3175</radius>\n              <length>0.2794</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>1</max_contacts>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 1</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <contact>\n              <ode>\n                <min_depth>0.005</min_depth>\n                <kp>1e+08</kp>\n              </ode>\n            </contact>\n            <bounce/>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 3.14159 -1.57079 3.14159</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <scale>1.0037 0.8862 0.8862</scale>\n              <submesh>\n                <name>Wheels_Rear_Left</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='rear_right_wheel'>\n        <pose frame=''>-0.99377 -0.71562 0.34697 1.52 -0 0</pose>\n        <inertial>\n          <mass>12</mass>\n          <inertia>\n            <ixx>0.5</ixx>\n            <ixy>0</ixy>\n            <iyy>0.5</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.3175</radius>\n              <length>0.2794</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>1</max_contacts>\n          <surface>\n            <friction>\n              <ode>\n                <mu>1</mu>\n                <mu2>1</mu2>\n                <fdir1>0 0 1</fdir1>\n                <slip1>0</slip1>\n                <slip2>0</slip2>\n              </ode>\n              <torsional>\n                <ode/>\n              </torsional>\n            </friction>\n            <contact>\n              <ode>\n                <min_depth>0.005</min_depth>\n                <kp>1e+08</kp>\n              </ode>\n            </contact>\n            <bounce/>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 3.14159 -1.57079 3.14159</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <scale>1.0037 0.8862 0.8862</scale>\n              <submesh>\n                <name>Wheels_Rear_Right</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='gas_pedal'>\n        <pose frame=''>0.63 0.1 0.58 0 -0 0</pose>\n        <gravity>0</gravity>\n        <inertial>\n          <mass>0.1</mass>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <inertia>\n            <ixx>0.01</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.01</iyy>\n            <iyz>0</iyz>\n            <izz>0.01</izz>\n          </inertia>\n        </inertial>\n        <collision name='gas_pedal_collision'>\n          <pose frame=''>-0.0385 0 -0.086 3.14159 1.12559 3.14159</pose>\n          <geometry>\n            <box>\n              <size>0.1069 0.077 0.01</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 0 -1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Gas_Pedal</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='brake_pedal'>\n        <gravity>0</gravity>\n        <pose frame=''>0.64 0.27 0.58 0 -0 0</pose>\n        <inertial>\n          <mass>0.1</mass>\n          <pose frame=''>0 0 0 0 -0 0</pose>\n          <inertia>\n            <ixx>0.01</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.01</iyy>\n            <iyz>0</iyz>\n            <izz>0.01</izz>\n          </inertia>\n        </inertial>\n        <collision name='brake_pedal_collision'>\n          <pose frame=''>-0.04 0 -0.086 3.14159 1.14259 3.14159</pose>\n          <geometry>\n            <box>\n              <size>0.063 0.08 0.01</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 0 -1.5707</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Brake_Pedal</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='front_right_wheel_steering_block'>\n        <pose frame=''>1.20223 -0.5 0.35515 1.5708 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>1</ixx>\n            <ixy>0</ixy>\n            <iyy>1</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.05</radius>\n              <length>0.01</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='front_left_wheel_steering_block'>\n        <pose frame=''>1.20223 0.5 0.35515 1.5708 -0 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <inertia>\n            <ixx>1</ixx>\n            <ixy>0</ixy>\n            <iyy>1</iyy>\n            <ixz>0</ixz>\n            <iyz>0</iyz>\n            <izz>1</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <geometry>\n            <cylinder>\n              <radius>0.05</radius>\n              <length>0.01</length>\n            </cylinder>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='steering_wheel'>\n        <pose frame=''>0.42 0.46 1.2 0 -0.87 0</pose>\n        <inertial>\n          <mass>1</mass>\n          <pose frame=''>-0.002 0 0 0 -0 0</pose>\n          <inertia>\n            <ixx>0.012</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.012</iyy>\n            <iyz>0</iyz>\n            <izz>0.024</izz>\n          </inertia>\n        </inertial>\n        <collision name='collision'>\n          <pose frame=''>-0.03 0 -0.120825 -0.6108 -0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Steering_Wheel</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <surface>\n            <contact>\n              <ode>\n                <min_depth>0.003</min_depth>\n              </ode>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n          <max_contacts>10</max_contacts>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>-0.03 0 -0.120825 -0.6108 -0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Steering_Wheel</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='hand_brake'>\n        <pose frame=''>0.53 0.205 1.05 0 -0 0</pose>\n        <inertial>\n          <mass>0.5</mass>\n          <inertia>\n            <ixx>0.1</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>0.1</iyy>\n            <iyz>0</iyz>\n            <izz>0.05</izz>\n          </inertia>\n        </inertial>\n        <collision name='hand_brake_collision'>\n          <pose frame=''>0 0 0.05 -0.2 -0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Shifter</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='hand_brake_visual'>\n          <pose frame=''>0 0 0.05 -0.2 -0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <uri>model://polaris_ranger_xp900/meshes/polaris.dae</uri>\n              <submesh>\n                <name>Shifter</name>\n                <center>1</center>\n              </submesh>\n            </mesh>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_xp900/materials/scripts</uri>\n              <uri>model://polaris_ranger_xp900/materials/textures</uri>\n              <name>PolarisXP900/Diffuse</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <link name='FNR_switch'>\n        <pose frame=''>0.54 0.1 1.15 0 0.25 0</pose>\n        <inertial>\n          <mass>0.1</mass>\n          <inertia>\n            <ixx>0.1</ixx>\n            <ixy>0</ixy>\n            <ixz>0</ixz>\n            <iyy>6e-05</iyy>\n            <iyz>0</iyz>\n            <izz>0.1</izz>\n          </inertia>\n        </inertial>\n        <collision name='FNR_switch'>\n          <geometry>\n            <box>\n              <size>0.02 0.04 0.08</size>\n            </box>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='FNR_switch_F'>\n          <transparency>0</transparency>\n          <geometry>\n            <box>\n              <size>0.02 0.04 0.08</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_ev/materials/scripts</uri>\n              <uri>model://polaris_ranger_ev/materials/textures</uri>\n              <name>FNR_switch_F</name>\n            </script>\n          </material>\n        </visual>\n        <visual name='FNR_switch_R'>\n          <transparency>1</transparency>\n          <geometry>\n            <box>\n              <size>0.0199 0.0399 0.0799</size>\n            </box>\n          </geometry>\n          <material>\n            <script>\n              <uri>model://polaris_ranger_ev/materials/scripts</uri>\n              <uri>model://polaris_ranger_ev/materials/textures</uri>\n              <name>FNR_switch_R</name>\n            </script>\n          </material>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <joint name='front_left_steering_joint' type='revolute'>\n        <child>front_left_wheel_steering_block</child>\n        <parent>chassis</parent>\n        <axis>\n          <xyz>0 0 1</xyz>\n          <limit>\n            <lower>-0.7727</lower>\n            <upper>0.7727</upper>\n          </limit>\n          <dynamics>\n            <damping>50</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.9</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='front_left_wheel_joint' type='revolute'>\n        <child>front_left_wheel</child>\n        <parent>front_left_wheel_steering_block</parent>\n        <axis>\n          <xyz>0 1 0.05</xyz>\n          <use_parent_model_frame>1</use_parent_model_frame>\n          <limit>\n            <lower>-1e+16</lower>\n            <upper>1e+16</upper>\n          </limit>\n          <dynamics>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n        </axis>\n      </joint>\n      <joint name='front_right_steering_joint' type='revolute'>\n        <child>front_right_wheel_steering_block</child>\n        <parent>chassis</parent>\n        <axis>\n          <xyz>0 0 1</xyz>\n          <limit>\n            <lower>-0.7727</lower>\n            <upper>0.7727</upper>\n          </limit>\n          <dynamics>\n            <damping>50</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.9</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='front_right_wheel_joint' type='revolute'>\n        <child>front_right_wheel</child>\n        <parent>front_right_wheel_steering_block</parent>\n        <axis>\n          <xyz>0 1 -0.05</xyz>\n          <use_parent_model_frame>1</use_parent_model_frame>\n          <limit>\n            <lower>-1e+16</lower>\n            <upper>1e+16</upper>\n          </limit>\n          <dynamics>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n        </axis>\n      </joint>\n      <joint name='rear_left_wheel_joint' type='revolute'>\n        <child>rear_left_wheel</child>\n        <parent>chassis</parent>\n        <axis>\n          <xyz>0 1 0.05</xyz>\n          <use_parent_model_frame>1</use_parent_model_frame>\n          <limit>\n            <lower>-1e+16</lower>\n            <upper>1e+16</upper>\n          </limit>\n          <dynamics>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n        </axis>\n      </joint>\n      <joint name='rear_right_wheel_joint' type='revolute'>\n        <pose frame=''>0 0 -0.1 0 -0 0</pose>\n        <child>rear_right_wheel</child>\n        <parent>chassis</parent>\n        <axis>\n          <xyz>0 1 -0.05</xyz>\n          <use_parent_model_frame>1</use_parent_model_frame>\n          <limit>\n            <lower>-1e+16</lower>\n            <upper>1e+16</upper>\n          </limit>\n          <dynamics>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n        </axis>\n      </joint>\n      <joint name='rear_differential_joint' type='revolute'>\n        <child>rear_right_wheel</child>\n        <parent>rear_left_wheel</parent>\n        <axis>\n          <xyz>0 1 0</xyz>\n          <dynamics>\n            <damping>70</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n          <limit>\n            <lower>-1e+16</lower>\n            <upper>1e+16</upper>\n          </limit>\n        </axis>\n        <physics>\n          <ode>\n            <erp>0</erp>\n            <cfm>1000</cfm>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='gas_joint' type='prismatic'>\n        <parent>chassis</parent>\n        <child>gas_pedal</child>\n        <axis>\n          <xyz>1 0 -1</xyz>\n          <limit>\n            <lower>0</lower>\n            <upper>0.08</upper>\n          </limit>\n          <dynamics>\n            <damping>3</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='brake_joint' type='prismatic'>\n        <parent>chassis</parent>\n        <child>brake_pedal</child>\n        <axis>\n          <xyz>1 0 -0.6</xyz>\n          <limit>\n            <lower>0</lower>\n            <upper>0.08</upper>\n          </limit>\n          <dynamics>\n            <damping>3</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='steering_joint' type='revolute'>\n        <pose frame=''>0 0 0 0 -0 0</pose>\n        <parent>chassis</parent>\n        <child>steering_wheel</child>\n        <axis>\n          <xyz>-1 0 0.84365</xyz>\n          <limit>\n            <lower>-3.14</lower>\n            <upper>3.14</upper>\n          </limit>\n          <dynamics>\n            <damping>1</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='hand_brake_joint' type='revolute'>\n        <parent>chassis</parent>\n        <child>hand_brake</child>\n        <axis>\n          <xyz>0 -1 0</xyz>\n          <limit>\n            <lower>0</lower>\n            <upper>0.6</upper>\n          </limit>\n          <dynamics>\n            <damping>1</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <joint name='FNR_switch_joint' type='revolute'>\n        <parent>chassis</parent>\n        <child>FNR_switch</child>\n        <axis>\n          <xyz>0 -1 0</xyz>\n          <limit>\n            <lower>-0.3</lower>\n            <upper>0.3</upper>\n          </limit>\n          <dynamics>\n            <damping>0.01</damping>\n            <spring_reference>0</spring_reference>\n            <spring_stiffness>0</spring_stiffness>\n          </dynamics>\n          <use_parent_model_frame>1</use_parent_model_frame>\n        </axis>\n        <physics>\n          <ode>\n            <cfm_damping>1</cfm_damping>\n            <limit>\n              <cfm>0</cfm>\n              <erp>0.2</erp>\n            </limit>\n          </ode>\n        </physics>\n      </joint>\n      <pose frame=''>-32.3103 5.4716 0 0 -0 0</pose>\n    </model>\n    <model name='radio_tower'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <geometry>\n            <mesh>\n              <uri>model://radio_tower/meshes/radio_tower.dae</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <geometry>\n            <mesh>\n              <uri>model://radio_tower/meshes/radio_tower.dae</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-43.2862 -5.42772 0 0 -0 0</pose>\n    </model>\n    <model name='suv'>\n      <static>1</static>\n      <link name='link'>\n        <collision name='collision'>\n          <pose frame=''>0 0 0 0 0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <scale>0.06 0.06 0.06</scale>\n              <uri>model://suv/meshes/suv.obj</uri>\n            </mesh>\n          </geometry>\n          <max_contacts>10</max_contacts>\n          <surface>\n            <contact>\n              <ode/>\n            </contact>\n            <bounce/>\n            <friction>\n              <torsional>\n                <ode/>\n              </torsional>\n              <ode/>\n            </friction>\n          </surface>\n        </collision>\n        <visual name='visual'>\n          <pose frame=''>0 0 0 0 0 -1.5708</pose>\n          <geometry>\n            <mesh>\n              <scale>0.06 0.06 0.06</scale>\n              <uri>model://suv/meshes/suv.obj</uri>\n            </mesh>\n          </geometry>\n        </visual>\n        <self_collide>0</self_collide>\n        <enable_wind>0</enable_wind>\n        <kinematic>0</kinematic>\n      </link>\n      <pose frame=''>-3.90558 -17.9855 0 0 -0 0</pose>\n    </model>\n  </world>\n</sdf>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/src/sm_ridgeback_barrel_search_2.cpp",
    "content": "#include <sm_ridgeback_barrel_search_2/sm_ridgeback_barrel_search_2.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_ridgeback_barrel_search_2\");\n    ros::NodeHandle nh;\n\n    ros::Duration(5).sleep();\n    smacc::run<sm_ridgeback_barrel_search_2::SmRidgebackBarrelSearch2>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/urdf/ridgeback.camera.gazebo",
    "content": "<?xml version=\"1.0\" ?>\n<robot xmlns:xacro=\"http://ros.org/wiki/xacro\">\n\n  <xacro:macro name=\"gazebo_camera\">\n\n    <joint name=\"$camera_joint\" type=\"fixed\">\n      <origin xyz=\"0.3 0 0.5330\" rpy=\"0 0 0\" />\n      <parent link=\"chassis_link\" />\n      <child link=\"camera_link\" />\n    </joint>\n\n    <link name=\"camera_link\">\n      <inertial>\n        <mass value=\"0.130\" />\n        <origin xyz=\"0 0 0\" />\n        <inertia ixx=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.07*0.07)}\" ixy=\"0.0\" ixz=\"0.0\" iyy=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.07*0.07)}\" iyz=\"0.0\" izz=\"${0.0833333 * 0.130 * (0.05*0.05 + 0.05*0.05)}\" />\n      </inertial>\n      <visual>\n        <origin xyz=\"-0.15 0 0\" rpy=\"0 0 0\" />\n        <geometry>\n          <!-- Origin of this mesh is the focal point of the LIDAR. -->\n          <mesh filename=\"package://ridgeback_description/meshes/ust-10lx.stl\" />\n        </geometry>\n        <material name=\"dark_grey\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 -0.0122\" rpy=\"0 0 0\" />\n        <geometry>\n          <box size=\"0.05 0.05 0.07\" />\n        </geometry>\n      </collision>\n    </link>\n\n    <!-- camera -->\n    <gazebo reference=\"camera_link\">\n      <sensor type=\"camera\" name=\"camera1\">\n        <update_rate>30.0</update_rate>\n        <camera name=\"head\">\n          <horizontal_fov>1.3962634</horizontal_fov>\n          <image>\n            <width>800</width>\n            <height>800</height>\n            <format>R8G8B8</format>\n          </image>\n          <clip>\n            <near>0.02</near>\n            <far>300</far>\n          </clip>\n          <noise>\n            <type>gaussian</type>\n            <!-- Noise is sampled independently per pixel on each frame.\n               That pixel's noise value is added to each of its color\n               channels, which at that point lie in the range [0,1]. -->\n            <mean>0.0</mean>\n            <stddev>0.007</stddev>\n          </noise>\n        </camera>\n        <plugin name=\"camera_controller\" filename=\"libgazebo_ros_camera.so\">\n          <alwaysOn>true</alwaysOn>\n          <updateRate>0.0</updateRate>\n          <cameraName>ridgeback/camera1</cameraName>\n          <imageTopicName>image_raw</imageTopicName>\n          <cameraInfoTopicName>camera_info</cameraInfoTopicName>\n          <frameName>camera_link</frameName>\n          <hackBaseline>0.07</hackBaseline>\n          <distortionK1>0.0</distortionK1>\n          <distortionK2>0.0</distortionK2>\n          <distortionK3>0.0</distortionK3>\n          <distortionT1>0.0</distortionT1>\n          <distortionT2>0.0</distortionT2>\n        </plugin>\n      </sensor>\n    </gazebo>\n  </xacro:macro>\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_barrel_search_2/urdf/ridgeback.urdf.xacro",
    "content": "<?xml version=\"1.0\"?>\n<robot name=\"ridgeback\" xmlns:xacro=\"http://ros.org/wiki/xacro\">\n  <xacro:property name=\"PI\" value=\"3.1415926535897931\" />\n\n  <xacro:property name=\"wheel_radius\" value=\"0.0759\" />\n  <xacro:property name=\"wheel_width\" value=\"0.0790\" />\n\n  <xacro:property name=\"chassis_length\" value=\"0.960\" />\n  <xacro:property name=\"chassis_width\" value=\"0.793\" />\n  <xacro:property name=\"chassis_height\" value=\"0.216\" />\n  <xacro:property name=\"deck_height\" value=\"0.280\" />\n\n  <xacro:property name=\"axle_offset\" value=\"0.0500\" />\n  <xacro:property name=\"rocker_offset\" value=\"0.319\" />\n  <xacro:property name=\"rocker_width\" value=\"0.472\" />\n\n  <xacro:property name=\"imu_offset_x\" value=\"0.2085\" />\n  <xacro:property name=\"imu_offset_y\" value=\"-0.2902\" />\n  <xacro:property name=\"imu_offset_z\" value=\"0.1681\" />\n\n  <xacro:property name=\"dummy_inertia\" value=\"1e-09\"/>\n\n  <material name=\"dark_grey\"><color rgba=\"0.2 0.2 0.2 1.0\" /></material>\n  <material name=\"light_grey\"><color rgba=\"0.4 0.4 0.4 1.0\" /></material>\n  <material name=\"red\"><color rgba=\"0.8 0.0 0.0 1.0\" /></material>\n  <material name=\"white\"><color rgba=\"0.9 0.9 0.9 1.0\" /></material>\n  <material name=\"yellow\"><color rgba=\"0.8 0.8 0.0 1.0\" /></material>\n  <material name=\"black\"><color rgba=\"0.15 0.15 0.15 1.0\" /></material>\n\n  <xacro:macro name=\"wheel\" params=\"prefix side *joint_pose\">\n    <link name=\"${prefix}_${side}_wheel_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 0\"/>\n        <geometry>\n          <mesh filename=\"package://ridgeback_description/meshes/wheel.stl\"/>\n        </geometry>\n        <material name=\"black\" />\n      </visual>\n      <collision>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 0\"/>\n        <geometry>\n          <cylinder radius=\"${wheel_radius}\" length=\"${wheel_width}\"/>\n        </geometry>\n      </collision>\n      <inertial>\n        <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n        <mass value=\"2.3\"/>\n        <inertia\n          ixx=\"3.3212e-3\" ixy=\"0\" ixz=\"0\"\n          iyy=\"6.6424e-3\" iyz=\"0\"\n          izz=\"3.3212e-3\"/>\n      </inertial>\n    </link>\n\n    <joint name=\"${prefix}_${side}_wheel\" type=\"continuous\">\n      <parent link=\"${prefix}_rocker_link\"/>\n      <child link=\"${prefix}_${side}_wheel_link\" />\n      <xacro:insert_block name=\"joint_pose\" />\n      <axis xyz=\"0 1 0\" />\n    </joint>\n\n    <transmission name=\"${prefix}_wheel_trans\">\n      <type>transmission_interface/SimpleTransmission</type>\n      <joint name=\"${prefix}_${side}_wheel\">\n        <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>\n      </joint>\n      <actuator name=\"${prefix}_${side}_actuator\">\n        <mechanicalReduction>1</mechanicalReduction>\n      </actuator>\n    </transmission>\n  </xacro:macro>\n\n\n  <xacro:macro name=\"rocker\" params=\"prefix joint_type location *joint_limits\">\n    <link name=\"${prefix}_rocker_link\">\n      <visual>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 ${PI/2}\" />\n        <geometry>\n          <mesh filename=\"package://ridgeback_description/meshes/rocker.stl\"/>\n        </geometry>\n        <material name=\"black\" />\n      </visual>\n      <inertial>\n        <origin xyz=\"0 0 0\" rpy=\"${PI/2} 0 ${PI/2}\"/>\n        <mass value=\"10.267\"/>\n        <inertia\n          ixx=\"0.0288\" ixy=\"2.20484e-6\" ixz=\"-1.3145e-5\"\n          iyy=\"0.4324\" iyz=\"1.8944e-3\"\n          izz=\"0.4130\"/>\n      </inertial>\n    </link>\n\n    <joint name=\"${prefix}_rocker\" type=\"${joint_type}\">\n      <parent link=\"axle_link\"/>\n      <child link=\"${prefix}_rocker_link\" />\n      <origin xyz=\"${location*rocker_offset} 0 0\" rpy=\"0 0 0\" />\n      <axis xyz=\"1 0 0\" />\n      <xacro:insert_block name=\"joint_limits\" />\n    </joint>\n\n    <xacro:wheel prefix=\"${prefix}\" side=\"left\">\n      <origin xyz=\"0 ${rocker_width/2 + wheel_width/2} 0\" rpy=\"0 0 0\" />\n    </xacro:wheel>\n    <xacro:wheel prefix=\"${prefix}\" side=\"right\">\n      <origin xyz=\"0 ${-(rocker_width/2 + wheel_width/2)} 0\" rpy=\"0 0 0\" />\n    </xacro:wheel>\n  </xacro:macro>\n\n  <xacro:rocker prefix=\"front\" joint_type=\"revolute\" location=\"1\" >\n    <limit lower=\"-0.08726\" upper=\"0.08726\" effort=\"0\" velocity=\"0\" />\n  </xacro:rocker>\n\n  <xacro:rocker prefix=\"rear\" joint_type=\"fixed\" location=\"-1\" >\n    <limit effort=\"0\" velocity=\"0\" />\n  </xacro:rocker>\n\n  <link name=\"base_link\"></link>\n\n  <joint name=\"base_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"base_link\"/>\n    <child link=\"chassis_link\" />\n  </joint>\n\n  <link name=\"chassis_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/body.stl\"/>\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n    <collision>\n      <origin xyz=\"0 0 0\"/>\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/body-collision.stl\"/>\n      </geometry>\n    </collision>\n    <inertial>\n      <origin xyz=\"0.012 0.002 0.067\" rpy=\"${PI/2} 0 ${PI/2}\"/>\n      <mass value=\"165.304\"/>\n      <inertia\n        ixx=\"4.4744\" ixy=\"0.03098\" ixz=\"0.003647\"\n        iyy=\"7.1624\" iyz=\"0.1228\"\n        izz=\"4.6155\"/>\n    </inertial>\n  </link>\n\n  <joint name=\"right_side_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"right_side_cover_link\" />\n  </joint>\n  <joint name=\"left_side_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"left_side_cover_link\" />\n  </joint>\n\n  <link name=\"left_side_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/side-cover.stl\"/>\n      </geometry>\n      <material name=\"yellow\" />\n    </visual>\n  </link>\n  <link name=\"right_side_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/side-cover.stl\"/>\n      </geometry>\n      <material name=\"yellow\" />\n    </visual>\n  </link>\n\n  <joint name=\"front_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"front_cover_link\" />\n  </joint>\n\n  <link name=\"front_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/end-cover.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <joint name=\"rear_cover_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"rear_cover_link\" />\n  </joint>\n\n  <link name=\"rear_cover_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/end-cover.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <joint name=\"front_lights_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"front_lights_link\" />\n  </joint>\n  <joint name=\"rear_lights_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"rear_lights_link\" />\n  </joint>\n\n  <link name=\"front_lights_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/lights.stl\" />\n      </geometry>\n      <material name=\"white\" />\n    </visual>\n  </link>\n  <link name=\"rear_lights_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 ${PI}\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/lights.stl\" />\n      </geometry>\n      <material name=\"red\" />\n    </visual>\n  </link>\n\n  <joint name=\"top_link_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"top_link\" />\n  </joint>\n\n  <link name=\"top_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/top.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n    <collision>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/top.stl\"/>\n      </geometry>\n    </collision>\n  </link>\n\n  <joint name=\"axle_joint\" type=\"fixed\">\n    <origin xyz=\"0 0 ${axle_offset}\" rpy=\"0 0 0\" />\n    <parent link=\"chassis_link\"/>\n    <child link=\"axle_link\" />\n  </joint>\n\n  <link name=\"axle_link\">\n    <visual>\n      <origin xyz=\"0 0 0\" rpy=\"0 ${PI/2} 0\" />\n      <geometry>\n        <mesh filename=\"package://ridgeback_description/meshes/axle.stl\" />\n      </geometry>\n      <material name=\"black\" />\n    </visual>\n  </link>\n\n  <link name=\"imu_link\">\n    <inertial>\n      <mass value=\"0.001\"/>\n      <origin xyz=\"0 0 0\" rpy=\"0 0 0\"/>\n      <inertia ixx=\"${dummy_inertia}\" ixy=\"0.0\" ixz=\"0.0\" iyy=\"${dummy_inertia}\" iyz=\"0.0\" izz=\"${dummy_inertia}\"/>\n    </inertial>\n  </link>\n  <joint name=\"imu_joint\" type=\"fixed\">\n    <parent link=\"chassis_link\" />\n    <child link=\"imu_link\" />\n    <origin xyz=\"${imu_offset_x} ${imu_offset_y} ${imu_offset_z}\" rpy=\"0 0 0\"/>\n  </joint>\n\n  <link name=\"mid_mount\" />\n  <joint name=\"mid_mount_joint\" type=\"fixed\">\n    <parent link=\"base_link\" />\n    <child link=\"mid_mount\" />\n    <origin xyz=\"0 0 ${deck_height}\" rpy=\"0 0 0\"/>\n  </joint>\n\n  <!-- Bring in simulation data for Gazebo. -->\n  <xacro:include filename=\"$(find ridgeback_description)/urdf/ridgeback.gazebo\" />\n\n  <!-- Optional standard accessories, including their simulation data. The rendering\n       of these into the final description is controlled by optenv variables, which\n       default each one to off.-->\n  <xacro:include filename=\"$(find ridgeback_description)/urdf/accessories.urdf.xacro\" />\n\n  <xacro:include filename=\"$(find sm_ridgeback_barrel_search_2)/urdf/ridgeback.camera.gazebo\"/>\n\n  <xacro:gazebo_camera />\n</robot>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_floor_coverage_dynamic_1/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.057\n  xy_goal_tolerance: 0.15\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_ridgeback_floor_coverage_static_1/config/move_base_client/base_local_planner_params.yaml",
    "content": "TrajectoryPlannerROS:\n\n  # Robot Configuration Parameters\n  acc_lim_x: 10.0\n  acc_lim_y: 10.0\n  acc_lim_theta:  20.0\n\n  max_vel_x: 0.5\n  min_vel_x: 0.1\n\n  max_vel_y: 0.5\n  min_vel_y: 0.1\n  holonomic_robot: true # was true for omni-motion\n\n  max_vel_theta: 0.57\n  min_vel_theta: -0.57\n\n  min_in_place_vel_theta: 0.314\n\n  escape_vel: -0.5\n\n  # Goal Tolerance Parameters\n  yaw_goal_tolerance: 0.157\n  xy_goal_tolerance: 0.15\n  latch_xy_goal_tolerance: false\n\n  # Forward Simulation Parameters\n  sim_time: 2.0\n  sim_granularity: 0.02\n  angular_sim_granularity: 0.02\n  vx_samples: 6\n  vtheta_samples: 20\n  controller_frequency: 20.0\n\n  # Trajectory scoring parameters\n  meter_scoring: true # Whether the gdist_scale and pdist_scale parameters should assume that goal_distance and path_distance are expressed in units of meters or cells. Cells are assumed by default (false).\n  occdist_scale:  0.06 #The weighting for how much the controller should attempt to avoid obstacles. default 0.01\n  pdist_scale: 0.6  #     The weighting for how much the controller should stay close to the path it was given . default 0.6\n  gdist_scale: 0.8 #     The weighting for how much the controller should attempt to reach its local goal, also controls speed  default 0.8\n\n  heading_lookahead: 0.325  #How far to look ahead in meters when scoring different in-place-rotation trajectories\n  heading_scoring: false  #Whether to score based on the robot's heading to the path or its distance from the path. default false\n  heading_scoring_timestep: 0.8   #How far to look ahead in time in seconds along the simulated trajectory when using heading scoring (double, default: 0.8)\n  dwa: true #Whether to use the Dynamic Window Approach (DWA)_ or whether to use Trajectory Rollout\n  simple_attractor: false\n  publish_cost_grid_pc: true\n\n  #Oscillation Prevention Parameters\n  oscillation_reset_dist: 0.05 #How far the robot must travel in meters before oscillation flags are reset (double, default: 0.05)\n  escape_reset_dist: 0.1\n  escape_reset_theta: 0.1\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_starcraft_ai\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_starcraft_ai)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_three_some_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_starcraft_ai_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_starcraft_ai.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\n install(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_starcraft_ai/docs/smacc_state_machine_20200302-001012.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> Inspired by StarcraftAI, this state machine provides a state machine shell, that can be easily adapted to AI applications. One would simply insert the AI objective function into the state_reactor of the Observe state.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__starcraft__ai.html\">Doxygen Namespace & Class Reference</a>\n\n <p>For more information see...</p>\n  <a href=\"https://www.google.com/url?sa=t&rct=j&q=&esrc=s&source=web&cd=10&ved=2ahUKEwiThZKprvvnAhVLvZ4KHbKFDHkQFjAJegQIBxAB&url=https%3A%2F%2Fychai.uk%2Fslides%2F2019-11-12-AlphaStarII.pdf&usg=AOvVaw0jRIVMd3gdb4fM4mmQ4nG1l\">AlphaStar: Grandmaster level in StarCraft II Explained</a>\n\n  <a href=\"https://www.google.com/url?sa=t&rct=j&q=&esrc=s&source=web&cd=1&cad=rja&uact=8&ved=2ahUKEwiqtLHorvvnAhUNs54KHZyOBtMQFjAAegQIBhAB&url=https%3A%2F%2Fhci.iwr.uni-heidelberg.de%2Fsystem%2Ffiles%2Fprivate%2Fdownloads%2F1448422913%2Freport_johannes_daub.pdf&usg=AOvVaw1ZfV12L1svm6sYG7Y2E9Wj\">A new Star is born - Looking into AlphaStar</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_starcraft_ai sm_starcraft_ai.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/config/sm_starcraft_ai_config.yaml",
    "content": "SmStarcraftAI:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nnamespace sm_starcraft_ai\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\n};\n} // namespace client_1\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_starcraft_ai/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_starcraft_ai\n{\nnamespace cl_subscriber\n{\nclass CbDefaultSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n    //-------------------------------------------------------------------------------\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_starcraft_ai/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_starcraft_ai\n{\nnamespace cl_subscriber\n{\nclass CbWatchdogSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/mode_states/ms_run.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_starcraft_ai\n{\n// STATE DECLARATION\nclass MsRun : public smacc::SmaccState<MsRun, SmStarcraftAI, StObserve>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_starcraft_ai\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/orthogonals/or_subscriber.h",
    "content": "#pragma once\n\n#include <sm_starcraft_ai/clients/cl_subscriber/cl_subscriber.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_starcraft_ai\n{\nusing namespace sm_starcraft_ai::cl_subscriber;\n\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto subscriber_client = this->createClient<ClSubscriber>();\n        subscriber_client->initialize();\n    }\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_starcraft_ai\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n#include <std_msgs/String.h>\n\nnamespace sm_starcraft_ai\n{\nusing namespace cl_ros_publisher;\n\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto ros_publisher_client = this->createClient<ClRosPublisher>();\n        ros_publisher_client->initialize();\n    }\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/sm_starcraft_ai.h",
    "content": "#pragma once\n\n#include <ros/ros.h>\n#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n#include <sm_starcraft_ai/orthogonals/or_timer.h>\n#include <sm_starcraft_ai/orthogonals/or_updatable_publisher.h>\n#include <sm_starcraft_ai/orthogonals/or_subscriber.h>\n#include <sm_starcraft_ai/orthogonals/or_keyboard.h>\n\nusing namespace cl_ros_timer;\nusing namespace cl_ros_publisher;\nusing namespace cl_keyboard;\n\nusing namespace sm_starcraft_ai::cl_subscriber;\n\n//CLIENT BEHAVIORS\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n\n#include <sm_starcraft_ai/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h>\n#include <sm_starcraft_ai/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h>\n\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n\n//#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n\nusing namespace smacc;\nusing namespace smacc::state_reactors;\nusing namespace smacc::default_events;\n\nnamespace sm_starcraft_ai\n{\n//SUPERSTATES\nnamespace SS1\n{\nclass SsMove;\n} // namespace SS1\n\nnamespace SS2\n{\nclass SsBuild;\n} // namespace SS2\n\nnamespace SS3\n{\nclass SsAttack;\n} // namespace SS3\n\n//STATES\nclass StObserve;\n\n//MODE STATES\nclass MsRun;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\n// STATE MACHINE\nstruct SmStarcraftAI\n    : public smacc::SmaccStateMachineBase<SmStarcraftAI, MsRun>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_starcraft_ai\n\n// MODE STATES\n#include <sm_starcraft_ai/mode_states/ms_run.h>\n\n//STATES\n#include <sm_starcraft_ai/states/st_observe.h>\n\n#include <sm_starcraft_ai/superstates/ss_move.h>\n#include <sm_starcraft_ai/superstates/ss_build.h>\n#include <sm_starcraft_ai/superstates/ss_attack.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/attack_inner_states/sti_attack_1.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace attack_inner_states\n{\n// STATE DECLARATION\nstruct StiAttack1 : smacc::SmaccState<StiAttack1, SS>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiAttack1>, StiAttack2, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiAttack1::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/attack_inner_states/sti_attack_2.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace attack_inner_states\n{\n// STATE DECLARATION\nstruct StiAttack2 : smacc::SmaccState<StiAttack2, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiAttack3, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiAttack3, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiAttack1, PREVIOUS>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/attack_inner_states/sti_attack_3.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace attack_inner_states\n{\n// STATE DECLARATION\nstruct StiAttack3 : smacc::SmaccState<StiAttack3, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiAttack1, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiAttack2, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiAttack1, NEXT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n  void onTimerClientTickCallback()\n  {\n    ROS_INFO(\"timer client tick!\");\n  }\n\n  void onSingleBehaviorTickCallback()\n  {\n    ROS_INFO(\"single behavior tick!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/build_inner_states/sti_build_1.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace build_inner_states\n{\n// STATE DECLARATION\nstruct StiBuild1 : smacc::SmaccState<StiBuild1, SS>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiBuild1>, StiBuild2, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiBuild1::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/build_inner_states/sti_build_2.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace build_inner_states\n{\n// STATE DECLARATION\nstruct StiBuild2 : smacc::SmaccState<StiBuild2, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiBuild3, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiBuild3, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiBuild1, PREVIOUS>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/build_inner_states/sti_build_3.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace build_inner_states\n{\n// STATE DECLARATION\nstruct StiBuild3 : smacc::SmaccState<StiBuild3, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiBuild1, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiBuild2, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiBuild1, NEXT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/move_inner_states/sti_move_1.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace move_inner_states\n{\n// STATE DECLARATION\nstruct StiMove1 : smacc::SmaccState<StiMove1, SS>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiMove1>, StiMove2, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiMove1::loopWhileCondition);\n  }\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/move_inner_states/sti_move_2.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace move_inner_states\n{\n// STATE DECLARATION\nstruct StiMove2 : smacc::SmaccState<StiMove2, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiMove3, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiMove3, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiMove1, PREVIOUS>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/move_inner_states/sti_move_3.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace move_inner_states\n{\n// STATE DECLARATION\nstruct StiMove3 : smacc::SmaccState<StiMove3, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiMove1, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiMove2, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiMove1, NEXT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/states/st_observe.h",
    "content": "namespace sm_starcraft_ai\n{\n// STATE DECLARATION\nstruct StObserve : smacc::SmaccState<StObserve, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct MOVE : SUCCESS{};\n    struct BUILD : SUCCESS{};\n    struct ATTACK : SUCCESS{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    // Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SS1::SsMove, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SS1::SsMove>,\n    // Keyboard events\n    Transition<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::SsMove, MOVE>,\n    Transition<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>, SS2::SsBuild, BUILD>,\n    Transition<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>, SS3::SsAttack, ATTACK>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/superstates/ss_attack.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace SS3\n{\nnamespace sm_starcraft_ai\n{\nnamespace attack_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiAttack1;\nclass StiAttack2;\nclass StiAttack3;\n} // namespace ss1_states\n} // namespace sm_starcraft_ai\n\nusing namespace sm_starcraft_ai::attack_inner_states;\n\n// STATE DECLARATION\nstruct SsAttack : smacc::SmaccState<SsAttack, MsRun, StiAttack1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiAttack1>, StObserve>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS3::SsAttack;\n\n#include <sm_starcraft_ai/states/attack_inner_states/sti_attack_1.h>\n#include <sm_starcraft_ai/states/attack_inner_states/sti_attack_2.h>\n#include <sm_starcraft_ai/states/attack_inner_states/sti_attack_3.h>\n\n} // namespace SS3\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/superstates/ss_build.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace SS2\n{\nnamespace sm_starcraft_ai\n{\nnamespace build_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiBuild1;\nclass StiBuild2;\nclass StiBuild3;\n} // namespace ss2_states\n} // namespace sm_starcraft_ai\n\nusing namespace sm_starcraft_ai::build_inner_states;\n\n// STATE DECLARATION\nstruct SsBuild : smacc::SmaccState<SsBuild, MsRun, StiBuild1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiBuild1>, StObserve>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS2::SsBuild;\n\n#include <sm_starcraft_ai/states/build_inner_states/sti_build_1.h>\n#include <sm_starcraft_ai/states/build_inner_states/sti_build_2.h>\n#include <sm_starcraft_ai/states/build_inner_states/sti_build_3.h>\n\n} // namespace SS2\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/include/sm_starcraft_ai/superstates/ss_move.h",
    "content": "namespace sm_starcraft_ai\n{\nnamespace SS1\n{\nnamespace sm_starcraft_ai\n{\nnamespace move_inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiMove1;\nclass StiMove2;\nclass StiMove3;\n} // namespace ss1_states\n} // namespace sm_starcraft_ai\n\nusing namespace sm_starcraft_ai::move_inner_states;\n\n// STATE DECLARATION\nstruct SsMove : smacc::SmaccState<SsMove, MsRun, StiMove1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiMove1>, StObserve>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS1\n\n//forward declaration for the superstate\nusing SS = SS1::SsMove;\n\n#include <sm_starcraft_ai/states/move_inner_states/sti_move_1.h>\n#include <sm_starcraft_ai/states/move_inner_states/sti_move_2.h>\n#include <sm_starcraft_ai/states/move_inner_states/sti_move_3.h>\n\n} // namespace SS1\n} // namespace sm_starcraft_ai\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/launch/sm_starcraft_ai.launch",
    "content": "<launch>\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -e\" />\n\n    <rosparam command=\"load\" file=\"$(find sm_starcraft_ai)/config/sm_starcraft_ai_config.yaml\" />\n    <node pkg=\"sm_starcraft_ai\" type=\"sm_starcraft_ai_node\" name=\"sm_starcraft_ai\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_starcraft_ai</name>\n    <version>1.4.16</version>\n  <description>The sm_starcraft_ai package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_starcraft_ai</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_starcraft_ai/src/sm_starcraft_ai_node.cpp",
    "content": "#include <sm_starcraft_ai/sm_starcraft_ai.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"starcraft_ai\");\n    smacc::run<sm_starcraft_ai::SmStarcraftAI>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_subscriber\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n* 0.9.4\n* noetic versioning update\n* code format and spelling - code quality via pre-commit\n* new noetic version\n* better subscribers client behaviors\n* better subscribers client behaviors\n* Contributors: pabloinigoblasco\n\n0.9.1 (2020-06-29)\n------------------\n\n0.9.0 (2020-06-26)\n------------------\n\n0.0.1 (2019-11-18)\n------------------\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_subscriber)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_subscriber\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_subscriber.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_subscriber_node.cpp)\n\n\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n add_executable(numbers_publisher_node servers/numbers_publisher/numbers_publisher.cpp)\n\n target_link_libraries(numbers_publisher_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node numbers_publisher_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_subscriber.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_subscriber.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.smacc=WARN\nlog4j.logger.ros.sm_subscriber=INFO\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/config/sm_subscriber_config.yaml",
    "content": "global_parameter_server:\n    ros__parameters:\n        signal_detector_loop_freq: 200\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/clients/cl_numbers_subscription/cl_numbers_subscription.h",
    "content": "#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nusing namespace smacc::client_bases;\n\nnamespace sm_subscriber\n{\nclass ClNumbersSubscription : public SmaccSubscriberClient<std_msgs::UInt16>\n{\npublic:\n  ClNumbersSubscription(std::string topicname) : SmaccSubscriberClient<std_msgs::UInt16>(topicname)\n  {\n  }\n};\n}  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/clients/cl_numbers_subscription/client_behaviors/cb_post_custom_event.h",
    "content": "\n#include <sm_subscriber/clients/cl_numbers_subscription/cl_numbers_subscription.h>\n#include <smacc/client_behavior_bases/cb_subscription_callback_base.h>\n\nnamespace sm_subscriber\n{\ntemplate <typename TSourceObject, typename Orthogonal>\nstruct EvImportantMessage : sc::event<EvImportantMessage<TSourceObject, Orthogonal>>\n{\n  int value;\n};\n\nclass CbPostCustomEvent : public smacc::CbSubscriptionCallbackBase<std_msgs::UInt16>\n{\npublic:\n  void onMessageReceived(const std_msgs::UInt16& msg) override\n  {\n    if (msg.data % 4 == 0)\n    {\n      ROS_WARN_STREAM(\"**** [CbPostCustomEvent] MESSAGE RECEIVED NUMBER MULTIPLE OF 4 \"<< msg.data <<\" , POSTING EvImportantMessage\");\n      this->postEventImportantMessage(msg.data);\n    }\n  }\n\n  template <typename TOrthogonal, typename TSourceObject>\n  void onOrthogonalAllocation()\n  {\n    postEventImportantMessage = [=](int value) {\n      auto ev = new EvImportantMessage<TSourceObject, TOrthogonal>();\n      ev->value =  value;\n      this->postEvent(ev);\n    };\n  }\n\n  std::function<void(int)> postEventImportantMessage;\n};\n\n};  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/clients/cl_numbers_subscription/client_behaviors/cb_print_message_number.h",
    "content": "#pragma once\n\n#include <sm_subscriber/clients/cl_numbers_subscription/cl_numbers_subscription.h>\n#include <smacc/client_behavior_bases/cb_subscription_callback_base.h>\n\nnamespace sm_subscriber\n{\n\nclass CbPrintMessageNumber : public smacc::CbSubscriptionCallbackBase<std_msgs::UInt16>\n{\npublic:\n  void onMessageReceived(const std_msgs::UInt16& msg) override\n  {\n    ROS_WARN_STREAM(\"**** [CbPrintMessageNumber] MESSAGE RECEIVED NUMBER: \" << msg.data);\n  }\n};\n\n};  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/orthogonals/or_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/smacc_orthogonal.h>\n#include <sm_subscriber/clients/cl_numbers_subscription/cl_numbers_subscription.h>\n\nnamespace sm_subscriber\n{\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n  virtual void onInitialize() override\n  {\n    auto subscriber_client = this->createClient<ClNumbersSubscription>(\"/numbers\");\n    subscriber_client ->initialize();\n  }\n};\n}  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_subscriber\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_atomic\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/sm_subscriber.h",
    "content": "#include <smacc/smacc.h>\n\n// ORTHOGONALS\n#include \"orthogonals/or_subscriber.h\"\n#include \"orthogonals/or_timer.h\"\n\n//CLIENTS\n#include \"clients/cl_numbers_subscription/cl_numbers_subscription.h\"\n#include <ros_timer_client/cl_ros_timer.h>\n\n// CLIENT BEHAVIORS\n#include \"clients/cl_numbers_subscription/client_behaviors/cb_post_custom_event.h\"\n#include \"clients/cl_numbers_subscription/client_behaviors/cb_print_message_number.h\"\n\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\nusing namespace cl_ros_timer;\n\n\nnamespace sm_subscriber\n{\n// STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n// STATE_MACHINE\nstruct SmSubscriber : public smacc::SmaccStateMachineBase<SmSubscriber, State1>\n{\n  using SmaccStateMachineBase::SmaccStateMachineBase;\n\n  virtual void onInitialize() override\n  {\n    this->createOrthogonal<OrSubscriber>();\n    this->createOrthogonal<OrTimer>();\n  }\n};\n\n}  // namespace sm_subscriber\n\n#include \"states/st_state_1.h\"\n#include \"states/st_state_2.h\"\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_subscriber\n{\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmSubscriber>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      //Transition<EvTopicMessage<ClNumbersSubscription, OrSubscriber>, State2, SUCCESS>\n      Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State2, SUCCESS>\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n      configure_orthogonal<OrSubscriber, CbPrintMessageNumber>();  // EvTimer triggers once at 10 client ticks\n      configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry state1 !\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit state1!\");\n  }\n};\n}  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/include/sm_subscriber/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_subscriber\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, SmSubscriber>\n{\n  using SmaccState::SmaccState;\n\n  // TRANSITION TABLE\n  typedef mpl::list<\n\n      Transition<EvImportantMessage<CbPostCustomEvent, OrSubscriber>, State1, SUCCESS>\n\n      >\n      reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrSubscriber, CbPostCustomEvent>();  // EvTimer triggers once at 10 client ticks\n  }\n\n  void runtimeConfigure()\n  {\n    ROS_INFO(\"Entering State2\");\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n};\n}  // namespace sm_subscriber\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/launch/sm_subscriber.launch",
    "content": "<launch>\n    <!-- <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_subscriber)/config/rosconsole.config\" /> -->\n    <rosparam command=\"load\" file=\"$(find sm_subscriber)/config/sm_subscriber_config.yaml\" />\n    <node pkg=\"sm_subscriber\" type=\"sm_subscriber_node\" name=\"sm_subscriber\" output=\"screen\"/>\n    <node pkg=\"sm_subscriber\" type=\"numbers_publisher_node\" name=\"sm_numbers_publisher\" output=\"screen\"/>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_subscriber</name>\n    <version>1.4.16</version>\n  <description>The sm_subscriber package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_atomic</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>xterm</depend>\n  <depend>ros_timer_client</depend>\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/servers/numbers_publisher/numbers_publisher.cpp",
    "content": "#include <ros/ros.h>\n#include <std_msgs/UInt16.h>\n\nint main(int argc, char** argv)\n{\n  ros::init(argc, argv, \"numbers_publisher\");\n\n  ros::NodeHandle nh_;\n\n  auto pub = nh_.advertise<std_msgs::UInt16>(\"/numbers\", 1);\n\n  ros::Rate r(0.5);\n\n  int i = 0;\n  while (ros::ok())\n  {\n    std_msgs::UInt16 msg;\n    msg.data = i++;\n\n    pub.publish(msg);\n\n    r.sleep();\n    ros::spinOnce();\n  }\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_subscriber/src/sm_subscriber_node.cpp",
    "content": "#include <sm_subscriber/sm_subscriber.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"SmSubscriber\");\n    smacc::run<sm_subscriber::SmSubscriber>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_three_some\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_three_some)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n\n#add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc multirole_sensor_client ros_timer_client sr_all_events_go ros_publisher_client keyboard_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_three_some_example\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME}_node src/sm_three_some_node.cpp)\n\nadd_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   yourfile\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}_node\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_three_some.launch\n   # myfile2\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n )\n\n install(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_three_some.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_three_some/docs/smacc_state_machine_20200220-115155.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A simple, but complete state machine example. We highly recommend using this example as a starting point for users state machine projects.<br></br>\n\n <a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__three__some.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_three_some sm_three_some.launch\n```\n\n<h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/config/sm_three_some_config.yaml",
    "content": "SmThreeSome:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/clients/cl_subscriber/cl_subscriber.h",
    "content": "\n#pragma once\n#include <smacc/client_bases/smacc_subscriber_client.h>\n#include <std_msgs/UInt16.h>\n\nnamespace sm_three_some\n{\nnamespace cl_subscriber\n{\nclass ClSubscriber : public smacc::client_bases::SmaccSubscriberClient<std_msgs::UInt16>\n{\n};\n} // namespace client_1\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_three_some/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_three_some\n{\nnamespace cl_subscriber\n{\nclass CbDefaultSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n    //-------------------------------------------------------------------------------\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h",
    "content": "\n#pragma once\n#include <sm_three_some/clients/cl_subscriber/cl_subscriber.h>\n\nnamespace sm_three_some\n{\nnamespace cl_subscriber\n{\nclass CbWatchdogSubscriberBehavior : public smacc::SmaccClientBehavior\n{\npublic:\n    typedef std_msgs::UInt16 TMessageType;\n\n    void onEntry()\n    {\n    }\n};\n} // namespace cl_subscriber\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/mode_states/ms_recover.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_three_some\n{\n// STATE DECLARATION\nclass MsRecover : public smacc::SmaccState<MsRecover, SmThreeSome>\n{\npublic:\n   using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n   typedef mpl::list<\n\n   Transition<EvToDeep, sc::deep_history<MsRun::LastDeepState>, SUCCESS>\n\n   >reactions;\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/mode_states/ms_run.h",
    "content": "#include <smacc/smacc.h>\nnamespace sm_three_some\n{\n// STATE DECLARATION\nclass MsRun : public smacc::SmaccState<MsRun, SmThreeSome, StState1>\n{\npublic:\n   using SmaccState::SmaccState;\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/orthogonals/or_keyboard.h",
    "content": "#pragma once\n\n#include <keyboard_client/cl_keyboard.h>\n#include <smacc/smacc_orthogonal.h>\nnamespace sm_three_some\n{\n\nclass OrKeyboard : public smacc::Orthogonal<OrKeyboard>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto clKeyboard = this->createClient<cl_keyboard::ClKeyboard>();\n\n        //ClKeyboard.queueSize = 1;\n        clKeyboard->initialize();\n    }\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/orthogonals/or_subscriber.h",
    "content": "#pragma once\n\n#include <sm_three_some/clients/cl_subscriber/cl_subscriber.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_three_some\n{\nusing namespace sm_three_some::cl_subscriber;\n\nclass OrSubscriber : public smacc::Orthogonal<OrSubscriber>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto subscriber_client = this->createClient<ClSubscriber>();\n        subscriber_client->initialize();\n    }\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/orthogonals/or_timer.h",
    "content": "#pragma once\n\n#include <ros_timer_client/cl_ros_timer.h>\n#include <smacc/smacc_orthogonal.h>\n\nnamespace sm_three_some\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto actionclient = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(0.5));\n        actionclient->initialize();\n    }\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/orthogonals/or_updatable_publisher.h",
    "content": "#pragma once\n\n#include <ros_publisher_client/cl_ros_publisher.h>\n#include <smacc/smacc_orthogonal.h>\n#include <std_msgs/String.h>\n\nnamespace sm_three_some\n{\nusing namespace cl_ros_publisher;\n\nclass OrUpdatablePublisher : public smacc::Orthogonal<OrUpdatablePublisher>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto ros_publisher_client = this->createClient<ClRosPublisher>();\n        ros_publisher_client->initialize();\n    }\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/sm_three_some.h",
    "content": "#pragma once\n\n#include <ros/ros.h>\n#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n#include <keyboard_client/cl_keyboard.h>\n\n// ORTHOGONALS\n#include <sm_three_some/orthogonals/or_timer.h>\n#include <sm_three_some/orthogonals/or_updatable_publisher.h>\n#include <sm_three_some/orthogonals/or_subscriber.h>\n#include <sm_three_some/orthogonals/or_keyboard.h>\n\nusing namespace cl_ros_timer;\nusing namespace cl_ros_publisher;\nusing namespace cl_keyboard;\n\nusing namespace sm_three_some::cl_subscriber;\n\n//CLIENT BEHAVIORS\n#include <ros_publisher_client/client_behaviors/cb_default_publish_loop.h>\n#include <ros_publisher_client/client_behaviors/cb_muted_behavior.h>\n#include <ros_publisher_client/client_behaviors/cb_publish_once.h>\n\n#include <sm_three_some/clients/cl_subscriber/client_behaviors/cb_default_subscriber_behavior.h>\n#include <sm_three_some/clients/cl_subscriber/client_behaviors/cb_watchdog_subscriber_behavior.h>\n\n#include <keyboard_client/client_behaviors/cb_default_keyboard_behavior.h>\n\n//#include <ros_timer_client/client_behaviors/cb_ros_timer.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\n//STATE REACTORS\n#include <sr_all_events_go/sr_all_events_go.h>\n\nusing namespace smacc;\nusing namespace smacc::state_reactors;\nusing namespace smacc::default_events;\n\nnamespace sm_three_some\n{\n//SUPERSTATES\nnamespace SS1\n{\nclass Ss1;\n} // namespace SS1\n\n//SUPERSTATES\nnamespace SS2\n{\nclass Ss2;\n} // namespace SS1\n\n\n//STATES\nclass StState1; // first state specially needs a forward declaration\nclass StState2;\nclass StState3;\nclass StState4;\n\nclass MsRun;\nclass MsRecover;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\n// STATE MACHINE\nstruct SmThreeSome\n    : public smacc::SmaccStateMachineBase<SmThreeSome, MsRun>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n        this->createOrthogonal<OrUpdatablePublisher>();\n        this->createOrthogonal<OrKeyboard>();\n        this->createOrthogonal<OrSubscriber>();\n    }\n};\n} // namespace sm_three_some\n\n// MODE STATES\n#include <sm_three_some/mode_states/ms_run.h>\n#include <sm_three_some/mode_states/ms_recover.h>\n\n//STATES\n#include <sm_three_some/states/st_state_1.h>\n#include <sm_three_some/states/st_state_2.h>\n#include <sm_three_some/states/st_state_3.h>\n#include <sm_three_some/states/st_state_4.h>\n\n#include <sm_three_some/superstates/ss_superstate_1.h>\n#include <sm_three_some/superstates/ss_superstate_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/inner_states/sti_state_1.h",
    "content": "namespace sm_three_some\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState1 : smacc::SmaccState<StiState1, SS>\n{\npublic:\n  using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvLoopContinue<StiState1>, StiState2, CONTINUELOOP>\n\n  >reactions;\n\n// STATE FUNCTIONS\n  static void staticConfigure()\n  {\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  bool loopWhileCondition()\n  {\n    auto &superstate = this->context<SS>();\n\n    ROS_INFO(\"Loop start, current iterations: %d, total iterations: %d\", superstate.iteration_count, superstate.total_iterations());\n    return superstate.iteration_count++ < superstate.total_iterations();\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"LOOP START ON ENTRY\");\n    checkWhileLoopConditionAndThrowEvent(&StiState1::loopWhileCondition);\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/inner_states/sti_state_2.h",
    "content": "namespace sm_three_some\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState2 : smacc::SmaccState<StiState2, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiState3, TIMEOUT>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiState3, NEXT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiState1, PREVIOUS>\n\n  >reactions;\n\n  // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/inner_states/sti_state_3.h",
    "content": "namespace sm_three_some\n{\nnamespace inner_states\n{\n// STATE DECLARATION\nstruct StiState3 : smacc::SmaccState<StiState3, SS>\n{\n  using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n  struct TIMEOUT : SUCCESS{};\n  struct NEXT : SUCCESS{};\n  struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n  typedef mpl::list<\n\n  Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StiState1, TIMEOUT>,\n  Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StiState2, PREVIOUS>,\n  Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StiState1, NEXT>\n\n  >reactions;\n\n // STATE FUNCTIONS\n  static void staticConfigure()\n  {\n    configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n    configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n    configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n    configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n  }\n\n  void runtimeConfigure()\n  {\n  }\n\n  void onEntry()\n  {\n    ROS_INFO(\"On Entry!\");\n  }\n\n  void onExit()\n  {\n    ROS_INFO(\"On Exit!\");\n  }\n\n};\n}\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/st_state_1.h",
    "content": "namespace sm_three_some\n{\n// STATE DECLARATION\nstruct StState1 : smacc::SmaccState<StState1, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StState2, TIMEOUT>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1, PREVIOUS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StState2, NEXT>,\n    Transition<EvFail, MsRecover, smacc::ABORT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/st_state_2.h",
    "content": "namespace sm_three_some\n{\n// STATE DECLARATION\nstruct StState2 : smacc::SmaccState<StState2, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n   Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, StState3, TIMEOUT>,\n    Transition<EvAllGo<SrAllEventsGo>, StState3>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StState1, PREVIOUS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, StState3, NEXT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n\n        // Create State Reactor\n        // auto sbAll = static_createStateReactor<SrAllEventsGo>();\n\n        auto sbAll = static_createStateReactor<smacc::state_reactors::SrAllEventsGo,\n                                               smacc::state_reactors::EvAllGo<SrAllEventsGo>,\n                                               mpl::list<\n                                                           EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>,\n                                                           EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>,\n                                                           EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>\n                                                           >>();\n        /*sbAll->addInputEvent<EvKeyPressA<CbDefaultKeyboardBehavior, OrKeyboard>>();\n        sbAll->addInputEvent<EvKeyPressB<CbDefaultKeyboardBehavior, OrKeyboard>>();\n        sbAll->addInputEvent<EvKeyPressC<CbDefaultKeyboardBehavior, OrKeyboard>>();\n        sbAll->setOutputEvent<EvAllGo<SrAllEventsGo>>();*/\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/st_state_3.h",
    "content": "namespace sm_three_some\n{\n// STATE DECLARATION\nstruct StState3 : smacc::SmaccState<StState3, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, SS1::Ss1, TIMEOUT>,\n    // Transition<smacc::EvTopicMessage<CbWatchdogSubscriberBehavior, OrSubscriber>, SS1::Ss1>,\n    // Keyboard events\n    Transition<EvKeyPressP<CbDefaultKeyboardBehavior, OrKeyboard>, StState2, PREVIOUS>,\n    Transition<EvKeyPressN<CbDefaultKeyboardBehavior, OrKeyboard>, SS1::Ss1, NEXT>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(10);\n        configure_orthogonal<OrSubscriber, CbWatchdogSubscriberBehavior>();\n        configure_orthogonal<OrUpdatablePublisher, CbDefaultPublishLoop>();\n        configure_orthogonal<OrKeyboard, CbDefaultKeyboardBehavior>();\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/states/st_state_4.h",
    "content": "namespace sm_three_some\n{\n// STATE DECLARATION\nstruct StState4 : smacc::SmaccState<StState4, MsRun>\n{\n    using SmaccState::SmaccState;\n\n// DECLARE CUSTOM OBJECT TAGS\n    struct TIMEOUT : SUCCESS{};\n    struct NEXT : SUCCESS{};\n    struct PREVIOUS : ABORT{};\n\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/superstates/ss_superstate_1.h",
    "content": "namespace sm_three_some\n{\nnamespace SS1\n{\nnamespace sm_three_some\n{\nnamespace inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiState1;\nclass StiState2;\nclass StiState3;\n} // namespace ss1_states\n} // namespace sm_three_some\n\nusing namespace sm_three_some::inner_states;\n\n// STATE DECLARATION\nstruct Ss1 : smacc::SmaccState<Ss1, MsRun, StiState1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiState1>, SS2::Ss2>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS1::Ss1;\n\n#include <sm_three_some/states/inner_states/sti_state_1.h>\n#include <sm_three_some/states/inner_states/sti_state_2.h>\n#include <sm_three_some/states/inner_states/sti_state_3.h>\n\n} // namespace SS1\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/include/sm_three_some/superstates/ss_superstate_2.h",
    "content": "namespace sm_three_some\n{\nnamespace SS2\n{\nnamespace sm_three_some\n{\nnamespace inner_states\n{\n//FORWARD DECLARATIONS OF ALL INNER STATES\nclass StiState1;\nclass StiState2;\nclass StiState3;\n} // namespace ss1_states\n} // namespace sm_three_some\n\nusing namespace sm_three_some::inner_states;\n\n// STATE DECLARATION\nstruct Ss2 : smacc::SmaccState<Ss2, MsRun, StiState1>\n{\npublic:\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvLoopEnd<StiState1>, StState4>\n\n    >reactions;\n\n// STATE VARIABLES\n    static constexpr int total_iterations() { return 5; }\n    int iteration_count = 0;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void runtimeConfigure()\n    {\n    }\n}; // namespace SS4\n\n//forward declaration for the superstate\nusing SS = SS2::Ss2;\n\n#include <sm_three_some/states/inner_states/sti_state_1.h>\n#include <sm_three_some/states/inner_states/sti_state_2.h>\n#include <sm_three_some/states/inner_states/sti_state_3.h>\n\n} // namespace SS1\n} // namespace sm_three_some\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/launch/sm_three_some.launch",
    "content": "<launch>\n    <arg name=\"server_nodes_xterms\" default=\"xterm -xrm 'XTerm*scrollBar:  true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -e\" />\n\n    <node pkg=\"sm_three_some\" type=\"sm_three_some_node\" name=\"sm_three_some\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n\n    <node pkg=\"keyboard_client\" type=\"keyboard_server_node.py\" name=\"keyboard_server_node\" launch-prefix=\"$(arg server_nodes_xterms)\" />\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_three_some</name>\n    <version>1.4.16</version>\n  <description>The sm_three_some package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_three_some</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>std_msgs</depend>\n\n  <depend>ros_timer_client</depend>\n  <depend>ros_publisher_client</depend>\n  <depend>keyboard_client</depend>\n  <depend>xterm</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_three_some/src/sm_three_some_node.cpp",
    "content": "#include <sm_three_some/sm_three_some.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"three_some\");\n    smacc::run<sm_three_some::SmThreeSome>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_update_loop\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* More CbTimer Updating\n* cbtimer cleanup\n* Merge branch 'master' into melodic-devel\n* sm_update_loop renaming\n* Contributors: Brett Aldrich, Unknown, brettpac, pablo.inigo.blasco\n\n* Merge branch 'master' into melodic-devel\n* adding xterm dependency to examples\n* More CbTimer Updating\n* cbtimer cleanup\n* Merge branch 'master' into melodic-devel\n* sm_update_loop renaming\n* Contributors: Brett Aldrich, Unknown, brettpac, pablo.inigo.blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_update_loop)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_update_loop\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_update_loop.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_update_loop_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_update_loop.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_update_loop/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_update_loop sm_update_loop.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/config/sm_update_loop_config.yaml",
    "content": "SmUpdateLoop:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/include/sm_update_loop/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_update_loop\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_update_loop\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/include/sm_update_loop/sm_update_loop.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_update_loop/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_update_loop\n{\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmUpdateLoop\n    : public smacc::SmaccStateMachineBase<SmUpdateLoop, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrTimer>();\n    }\n};\n\n} // namespace sm_update_loop\n\n#include <sm_update_loop/states/st_state_1.h>\n#include <sm_update_loop/states/st_state_2.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/include/sm_update_loop/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_update_loop\n{\nusing namespace cl_ros_timer;\nusing namespace smacc::default_transition_tags;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmUpdateLoop>, ISmaccUpdatable\n{\n    using SmaccState::SmaccState;\n\n// TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State2, SUCCESS>\n\n    >reactions;\n\n// STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownLoop>(3); // EvTimer triggers each 3 client ticks\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Run-Time Configure\");\n    }\n\n    virtual void update() override\n    {\n        ROS_INFO(\"STATE 1 UPDATE!\");\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n} // namespace sm_update_loop\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/include/sm_update_loop/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_update_loop\n{\n// STATE DECLARATION\nstruct State2 : smacc::SmaccState<State2, SmUpdateLoop>, ISmaccUpdatable\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n    Transition<EvTimer<CbTimerCountdownOnce, OrTimer>, State1, SUCCESS>\n\n    >reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n        configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5); // EvTimer triggers once at 10 client ticks\n    }\n\n    void runtimeConfigure()\n    {\n        ROS_INFO(\"Entering State2\");\n\n        this->setUpdatePeriod(ros::Duration(1));\n    }\n\n    virtual void update() override\n    {\n        ROS_INFO(\"STATE 2 UPDATE\");\n    }\n\n    void onEntry()\n    {\n        ROS_INFO(\"On Entry!\");\n    }\n\n    void onExit()\n    {\n        ROS_INFO(\"On Exit!\");\n    }\n\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/launch/sm_update_loop.launch",
    "content": "<launch>\n    <!-- launch-prefix=\"valgrind tool=callgrind log-file='valgrind.log'\" -->\n    <rosparam command=\"load\" file=\"$(find sm_update_loop)/config/sm_update_loop_config.yaml\" />\n    <node pkg=\"sm_update_loop\" type=\"sm_update_loop_node\" name=\"sm_update_loop\" output=\"screen\">\n        <param name=\"signal_detector_loop_freq\" value=\"500\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_update_loop</name>\n    <version>1.4.16</version>\n  <description>The sm_update_loop package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_update_loop</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n  <depend>xterm</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_update_loop/src/sm_update_loop_node.cpp",
    "content": "#include <sm_update_loop/sm_update_loop.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_update_loop\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_update_loop::SmUpdateLoop>();\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_viewer_sim\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_viewer_sim)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc roscpp move_base_z_client_plugin multirole_sensor_client tf sr_all_events_go)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n#  LIBRARIES sm_viewer_sim\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\nadd_executable(${PROJECT_NAME} src/sm_viewer_sim.cpp)\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\ninstall(PROGRAMS\n   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\ninstall(TARGETS\n  ${PROJECT_NAME}\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n install(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\n install(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n#install(FILES\n#   launch/sm_viewer_sim.launch\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n# )\n\ninstall(DIRECTORY\n    config/\n    DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sim_viewer.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/README.md",
    "content": "  <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_viewer_sim/docs/smacc_state_machine_20200222-181448.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n\n<h2>Description</h2> A state machine example used for testing and debugging the SMACC viewer. Not recommended for normal SMACC users.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__viewer__sim.html\">Doxygen Namespace & Class Reference</a>\n\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_viewer_sim sm_viewer_sim.launch\n\n```\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/config/sm_viewer_sim_config.yaml",
    "content": "SmViewerSim:\n   signal_detector_loop_freq: 20\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/modestates/ms_recovery_mode.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_viewer_sim\n{\nstruct MsRecoveryMode : SmaccState<MsRecoveryMode, SmViewerSim>\n{\n    typedef mpl::list<\n    Transition<EvToDeep, sc::deep_history<MsRunMode::LastDeepState>, SUCCESS>>\n\n    reactions;\n\n    using SmaccState::SmaccState;\n    void onEntry()\n    {\n        ROS_INFO(\"Recovery\");\n        delayedPostEvent<EvToDeep>(this, 3);\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/modestates/ms_run_mode.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_viewer_sim\n{\nstruct MsRunMode : SmaccState<MsRunMode, SmViewerSim, St1>\n{\n    using SmaccState::SmaccState;\n    void onEntry()\n    {\n        ROS_INFO(\"MS RUN MODE\");\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/orthogonals/or_navigation.h",
    "content": "#include <smacc/smacc.h>\n#include <move_base_z_client_plugin/move_base_z_client_plugin.h>\n#include <move_base_z_client_plugin/components/pose/cp_pose.h>\n\nnamespace sm_viewer_sim\n{\nusing namespace cl_move_base_z;\n\nclass OrNavigation : public smacc::Orthogonal<OrNavigation>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto movebaseClient = this->createClient<ClMoveBaseZ>();\n        movebaseClient->createComponent<cl_move_base_z::Pose>();\n\n        movebaseClient->initialize();\n    }\n};\n} // namespace sm_viewer_sim\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/sm_viewer_sim.h",
    "content": "\n#include <thread>\n#include <future>\n\n#include <smacc/smacc.h>\n\n// CLIENT BEHAVIORS\n// - no client behavior in this example -\n\n// ORTHOGONALS\n#include <sm_viewer_sim/orthogonals/or_navigation.h>\n\nusing namespace smacc;\n\nnamespace sm_viewer_sim\n{\nstruct MsRecoveryMode;\nstruct MsRunMode;\nstruct St1;\nstruct St2;\nstruct St3;\n\nstruct EvToDeep : sc::event<EvToDeep>\n{\n};\n\nstruct EvFail : sc::event<EvFail>\n{\n};\n\n\nstruct Ev1 : sc::event<Ev1>\n{\n};\nstruct Ev2 : sc::event<Ev2>\n{\n};\nstruct Ev3 : sc::event<Ev3>\n{\n};\n\ntemplate <typename TEv>\nvoid delayedPostEvent(smacc::ISmaccState *sm, int delayseconds)\n{\n    std::async(std::launch::async, [=]() {\n        std::this_thread::sleep_for(std::chrono::seconds(delayseconds));\n        sm->postEvent(new TEv());\n    });\n}\n\nstruct SmViewerSim : smacc::SmaccStateMachineBase<SmViewerSim, MsRunMode>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        this->createOrthogonal<OrNavigation>();\n        int initialcounterValue = 0;\n        //this->setGlobalSMData(\"St2Attempts\", initialcounterValue);\n    }\n\n    void unconsumed_event(const sc::event_base &)\n    {\n        throw std::runtime_error(\"Event was not consumed!\");\n    }\n};\n} // namespace sm_viewer_sim\n\n// MODE STATES\n#include <sm_viewer_sim/modestates/ms_run_mode.h>\n#include <sm_viewer_sim/modestates/ms_recovery_mode.h>\n\n\n// STATES\n#include <sm_viewer_sim/states/st_st1.h>\n#include <sm_viewer_sim/states/st_st2.h>\n#include <sm_viewer_sim/states/st_st3.h>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/states/st_st1.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_viewer_sim\n{\nusing namespace smacc::default_transition_tags;\nstruct St1 : SmaccState<St1, MsRunMode>\n{\n    typedef mpl::list<\n        Transition<Ev1, St2, SUCCESS>,\n        Transition<EvFail, MsRecoveryMode, ABORT>>\n        reactions;\n\n    using SmaccState::SmaccState;\n    void onEntry()\n    {\n        ROS_INFO(\"St1\");\n        delayedPostEvent<Ev1>(this, 7);\n    }\n};\n} // namespace sm_viewer_sim\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/states/st_st2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_viewer_sim\n{\nstruct St2 : smacc::SmaccState<St2, MsRunMode>\n{\n    static int counter;\n    typedef mpl::list<\n        Transition<Ev2, St3, smacc::SUCCESS>,\n        Transition<EvFail, MsRecoveryMode, smacc::ABORT>>\n        reactions;\n\n    using SmaccState::SmaccState;\n\n    void onEntry()\n    {\n        ROS_INFO(\"St2\");\n\n        ROS_INFO_STREAM(\"counter: \" << counter);\n        if (counter % 2 == 0)\n            delayedPostEvent<EvFail>(this, 3);\n        else\n            delayedPostEvent<Ev2>(this, 3);\n\n        counter++;\n        this->setGlobalSMData(\"St2Attempts\", counter);\n    }\n};\n\nint St2::counter = 0;\n\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/include/sm_viewer_sim/states/st_st3.h",
    "content": "\n#include <smacc/smacc.h>\n\nnamespace sm_viewer_sim\n{\nstruct St3 : SmaccState<St3, MsRunMode>\n{\n    typedef mpl::list<\n        Transition<Ev3, St1, smacc::SUCCESS>,\n        Transition<EvFail, MsRecoveryMode, smacc::ABORT>>\n        reactions;\n\n    using SmaccState::SmaccState;\n    void onEntry()\n    {\n        ROS_INFO(\"St3\");\n        delayedPostEvent<Ev3>(this, 3);\n    }\n};\n}\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/launch/sm_viewer_sim.launch",
    "content": "<launch>\n    <rosparam command=\"load\" file=\"$(find sm_viewer_sim)/config/sm_viewer_sim_config.yaml\" />\n    <node pkg=\"sm_viewer_sim\" type=\"sm_viewer_sim\" name=\"sm_viewer_sim\"/>\n</launch>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sm_viewer_sim</name>\n    <version>1.4.16</version>\n  <description>The sm_viewer_sim package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_viewer_sim</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>move_base_z_client_plugin</depend>\n\n  <depend>multirole_sensor_client</depend>\n  <depend>sr_all_events_go</depend>\n  <depend>tf</depend>\n  <depend>xterm</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_sm_reference_library/sm_viewer_sim/src/sm_viewer_sim.cpp",
    "content": "#include <sm_viewer_sim/sm_viewer_sim.h>\n\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_viewer_sim\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_viewer_sim::SmViewerSim>();\n}\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_all_events_go/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sr_all_events_go\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Initial SMACC version\n* Contributors: Pablo Iñigo Blasco\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_all_events_go/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sr_all_events_go)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES sr_all_events_go\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\ninclude\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\nadd_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/sr_all_events_go.cpp\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/sr_all_events_go_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sr_all_events_go.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_all_events_go/include/sr_all_events_go/sr_all_events_go.h",
    "content": "#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_state_reactor.h>\n#include <map>\n#include <typeinfo>\n#include <boost/statechart/event.hpp>\n\nnamespace smacc\n{\n\nnamespace state_reactors\n{\ntemplate <typename TSource, typename TObjectTag = EmptyObjectTag>\nstruct EvAllGo : sc::event<EvAllGo<TSource, TObjectTag>>\n{\n};\n\nclass SrAllEventsGo : public StateReactor\n{\n    std::map<const std::type_info *, bool> triggeredEvents;\n\npublic:\n    SrAllEventsGo()\n    {\n    }\n\n    virtual void onInitialized() override;\n    virtual void onEventNotified(const std::type_info *eventType) override;\n    virtual bool triggers() override;\n};\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_all_events_go/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sr_all_events_go</name>\n    <version>1.4.16</version>\n  <description>The sr_all_events_go package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Iñigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sr_all_events_go</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <build_depend>smacc</build_depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_all_events_go/src/sr_all_events_go/sr_all_events_go.cpp",
    "content": "\n#include <sr_all_events_go/sr_all_events_go.h>\n#include <smacc/common.h>\n\nnamespace smacc\n{\nnamespace state_reactors\n{\n\nusing namespace smacc::introspection;\nvoid SrAllEventsGo::onInitialized()\n{\n    for (auto type : eventTypes)\n    {\n        triggeredEvents[type] = false;\n    }\n}\n\nvoid SrAllEventsGo::onEventNotified(const std::type_info *eventType)\n{\n    ROS_INFO_STREAM(\"SB ALL RECEIVED EVENT OF TYPE:\" << demangleSymbol(eventType->name()));\n    triggeredEvents[eventType] = true;\n\n    for (auto &entry : triggeredEvents)\n    {\n        ROS_INFO_STREAM(demangleSymbol(entry.first->name()) << \" = \" << entry.second);\n    }\n}\n\nbool SrAllEventsGo::triggers()\n{\n    ROS_INFO(\"SB All TRIGGERS?\");\n    for (auto &entry : triggeredEvents)\n    {\n        if (!entry.second)\n            return false;\n    }\n    ROS_INFO(\"SB ALL TRIGGERED\");\n    return true;\n}\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_conditional/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sr_conditional\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n\n* Renamed sr_conditional & eg_random_generator\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_conditional/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sr_conditional)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system )\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   smacc_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES sr_conditional\n#  CATKIN_DEPENDS smacc_msgs\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   src/${PROJECT_NAME}/sr_conditional.cpp\n )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/sr_conditional_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n install(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n )\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sr_conditional.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_conditional/include/sr_conditional/sr_conditional.h",
    "content": "#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_state_reactor.h>\n#include <map>\n#include <typeinfo>\n#include <boost/statechart/event.hpp>\n\nnamespace smacc\n{\nnamespace state_reactors\n{\ntemplate <typename TSource, typename TObjectTag = EmptyObjectTag>\nstruct Evsr_conditionalTrue : sc::event<Evsr_conditionalTrue<TSource, TObjectTag>>\n{\n};\n\n//-----------------------------------------------------------------------\nclass Srsr_conditional : public StateReactor\n{\nprivate:\n    std::map<const std::type_info *, bool> triggeredEvents;\n    bool conditionFlag;\n\npublic:\n    template <typename TEv>\n    Srsr_conditional(std::function<bool(TEv *)> sr_conditionalFunction)\n    {\n        std::function<void(TEv *)> callback =\n            [=](TEv *ev) {\n                bool condition = sr_conditionalFunction(ev);\n                this->conditionFlag = condition;\n            };\n\n        this->createEventCallback(callback);\n    }\n\n    ~Srsr_conditional();\n\n    virtual bool triggers() override;\n};\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_conditional/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>sr_conditional</name>\n    <version>1.4.16</version>\n  <description>The sr_conditional package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sr_conditional</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>smacc</depend>\n\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_conditional/src/sr_conditional/sr_conditional.cpp",
    "content": "#include <sr_conditional/sr_conditional.h>\n\nnamespace smacc\n{\nnamespace state_reactors\n{\nSrsr_conditional::~Srsr_conditional()\n{\n}\n\nbool Srsr_conditional::triggers()\n{\n    return this->conditionFlag;\n}\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_event_countdown/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sr_event_countdown\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* Renamed event_countdown to sr_event_countdown\n* Contributors: Brett Aldrich\n\n* Renamed event_countdown to sr_event_countdown\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_event_countdown/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sr_event_countdown)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED smacc)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n  INCLUDE_DIRS include\n  LIBRARIES sr_event_countdown\n  #CATKIN_DEPENDS smacc\n  #DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nSET(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n add_library(${PROJECT_NAME}\n   #src/${PROJECT_NAME}/sr_event_countdown.cpp\n   src/sr_event_countdown/sr_event_countdown.cpp\n )\n\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\nadd_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/sr_event_countdown_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n# install(TARGETS ${PROJECT_NAME}_node\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\ninstall(TARGETS ${PROJECT_NAME}\n   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n)\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n   FILES_MATCHING PATTERN \"*.h\"\n   PATTERN \".svn\" EXCLUDE\n)\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sr_event_countdown.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_event_countdown/include/sr_event_countdown/sr_event_countdown.h",
    "content": "#pragma once\n#include <smacc/common.h>\n#include <smacc/smacc_state_reactor.h>\n#include <map>\n#include <typeinfo>\n#include <boost/statechart/event.hpp>\n\nnamespace smacc\n{\n\nnamespace state_reactors\n{\ntemplate <typename TSource, typename TObjectTag = EmptyObjectTag>\nstruct EvCountdownEnd : sc::event<EvCountdownEnd<TSource, TObjectTag>>\n{\n};\n\n//-----------------------------------------------------------------------\nclass SrEventCountdown : public StateReactor\n{\nprivate:\n    std::map<const std::type_info *, bool> triggeredEvents;\n    int eventCount_;\n\npublic:\n    SrEventCountdown(int eventCount);\n\n    virtual void onInitialized() override;\n\n    virtual void onEventNotified(const std::type_info *eventType) override;\n\n    virtual bool triggers() override;\n};\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_event_countdown/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sr_event_countdown</name>\n    <version>1.4.16</version>\n  <description>The sr_event_countdown package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sr_event_countdown</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>catkin</depend>\n  <depend>smacc</depend>\n\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "smacc_state_reactor_library/sr_event_countdown/src/sr_event_countdown/sr_event_countdown.cpp",
    "content": "\n#include <smacc/common.h>\n#include <sr_event_countdown/sr_event_countdown.h>\n#include <memory>\n\nnamespace smacc\n{\nnamespace state_reactors\n{\nusing namespace smacc::introspection;\nSrEventCountdown::SrEventCountdown(int eventCount)\n    : eventCount_(eventCount)\n{\n}\n\nvoid SrEventCountdown::onInitialized()\n{\n    for (auto type : eventTypes)\n    {\n        triggeredEvents[type] = false;\n    }\n}\n\nvoid SrEventCountdown::onEventNotified(const std::type_info *eventType)\n{\n    eventCount_--;\n    ROS_INFO_STREAM(\"SB COUNTDOWN (\" << eventCount_ << \") RECEIVED EVENT OF TYPE:\" << demangleSymbol(eventType->name()));\n\n    // ROS_INFO_STREAM(\"SB ALL RECEIVED EVENT OF TYPE:\" << demangleSymbol(eventType->name()));\n    // triggeredEvents[eventType] = true;\n\n    // for (auto &entry : triggeredEvents)\n    // {\n    //     ROS_INFO_STREAM(demangleSymbol(entry.first->name()) << \" = \" << entry.second);\n    // }\n}\n\nbool SrEventCountdown::triggers()\n{\n    if (eventCount_ == 0)\n    {\n        ROS_INFO_STREAM(\"SB COUNTDOWN (\" << eventCount_ << \") TRIGGERS!\");\n        return true;\n    }\n    else\n    {\n        return false;\n    }\n\n    // ROS_INFO(\"SB All TRIGGERS?\");\n    // for (auto &entry : triggeredEvents)\n    // {\n    //     if (!entry.second)\n    //         return false;\n    // }\n    // ROS_INFO(\"SB ALL TRIGGERED\");\n    // return true;\n}\n\n} // namespace state_reactors\n} // namespace smacc\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_coretest_transition_speed_1\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_coretest_transition_speed_1)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_coretest_transition_speed_1\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_coretest_transition_speed_1.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_coretest_transition_speed_1_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_coretest_transition_speed_1.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(FILES\n   config/rosconsole.config\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_coretest_transition_speed_1/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_coretest_transition_speed_1 sm_coretest_transition_speed_1.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.smacc=WARN\nlog4j.logger.ros.sm_coretest_transition_speed_1=WARN\n\nlog4j.rootLogger=DEBUG, A1\nlog4j.appender.A1=org.apache.log4j.ConsoleAppender\nlog4j.appender.A1.layout=org.apache.log4j.PatternLayout\n\n# Print the date in ISO 8601 format\nlog4j.appender.A1.layout.ConversionPattern=%d [%t] %-5p %c - %m%n\n\n# https://logging.apache.org/log4cxx/latest_stable/usage.html\n# https://logging.apache.org/log4j/1.2/apidocs/org/apache/log4j/PatternLayout.html\n# http://wiki.ros.org/rosconsole\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/include/sm_coretest_transition_speed_1/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_coretest_transition_speed_1\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_coretest_transition_speed_1\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/include/sm_coretest_transition_speed_1/sm_coretest_transition_speed_1.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_coretest_transition_speed_1/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_coretest_transition_speed_1\n{\n\nstruct AutomaticTransitionEvent: sc::event<AutomaticTransitionEvent>\n{\n\n};\n\nstatic int counter = 0;\nros::Time startTime;\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmCoreTestTransistionSpeed1\n    : public smacc::SmaccStateMachineBase<SmCoreTestTransistionSpeed1, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        startTime=ros::Time::now();\n    }\n};\n\n} // namespace sm_coretest_transition_speed_1\n\n#include <sm_coretest_transition_speed_1/states/st_state_1.h>\n#include <sm_coretest_transition_speed_1/states/st_state_2.h>\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/include/sm_coretest_transition_speed_1/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n#define iterationCheck  10000\n\nnamespace sm_coretest_transition_speed_1\n{\n\nextern int counter;\nextern ros::Time startTime;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmCoreTestTransistionSpeed1>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State2, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n\n        if (counter > iterationCheck )\n        {\n            ROS_ERROR(\"ey\");\n            auto now = ros::Time::now();;\n            auto elapsed =  now - startTime ;\n            auto freqHz = iterationCheck / elapsed.toSec();\n\n            startTime = now;\n            while(ros::ok())\n            {\n                ros::Duration(0.2).sleep();\n                ROS_ERROR(\"A %d iterations in %lf seconds. Ferquency: %lf Hz\", iterationCheck,  elapsed.toSec(), freqHz);\n            }\n        }\n\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n} // namespace sm_coretest_transition_speed_1\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/include/sm_coretest_transition_speed_1/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_coretest_transition_speed_1\n{\n// STATE DECLARATION\n\nextern int counter;\n\nstruct State2 : smacc::SmaccState<State2, SmCoreTestTransistionSpeed1>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State1, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n}\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/launch/sm_coretest_transition_speed_1.launch",
    "content": "<launch>\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_coretest_transition_speed_1)/config/rosconsole.config\" />\n    <node pkg=\"sm_coretest_transition_speed_1\" type=\"sm_coretest_transition_speed_1_node\" name=\"sm_coretest_transition_speed_1\" output=\"screen\"/>\n</launch>\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_coretest_transition_speed_1</name>\n  <version>1.4.16</version>\n  <description>The sm_coretest_transition_speed_1 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_coretest_transition_speed_1</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "test/sm_coretest_transition_speed_1/src/sm_coretest_transition_speed_1_node.cpp",
    "content": "#include <sm_coretest_transition_speed_1/sm_coretest_transition_speed_1.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_coretest_transition_speed_1\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_coretest_transition_speed_1::SmCoreTestTransistionSpeed1>();\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_coretest_x_y_1\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_coretest_x_y_1)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_coretest_x_y_1\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_coretest_x_y_1.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_coretest_x_y_1_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_coretest_x_y_1.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(FILES\n   config/rosconsole.config\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_coretest_x_y_1/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_coretest_x_y_1 sm_coretest_x_y_1.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.smacc=WARN\nlog4j.logger.ros.sm_coretest_x_y_1=WARN\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/include/sm_coretest_x_y_1/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_coretest_x_y_1\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_coretest_x_y_1\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/include/sm_coretest_x_y_1/sm_coretest_x_y_1.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_coretest_x_y_1/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_coretest_x_y_1\n{\n\nstruct AutomaticTransitionEvent: sc::event<AutomaticTransitionEvent>\n{\n\n};\n\nstatic int counter = 0;\nros::Time startTime;\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmCoreTestXY1\n    : public smacc::SmaccStateMachineBase<SmCoreTestXY1, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        startTime=ros::Time::now();\n    }\n};\n\n} // namespace sm_coretest_x_y_1\n\n#include <sm_coretest_x_y_1/states/st_state_1.h>\n#include <sm_coretest_x_y_1/states/st_state_2.h>\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/include/sm_coretest_x_y_1/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n#define iterationCheck  10000\n\nnamespace sm_coretest_x_y_1\n{\n\nextern int counter;\nextern ros::Time startTime;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmCoreTestXY1>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State2, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n\n        if (counter > iterationCheck )\n        {\n            ROS_ERROR(\"ey\");\n            auto now = ros::Time::now();;\n            auto elapsed =  now - startTime ;\n            auto freqHz = iterationCheck / elapsed.toSec();\n\n            startTime = now;\n            while(ros::ok())\n            {\n                ros::Duration(0.2).sleep();\n                ROS_ERROR(\"A %d iterations in %lf seconds. Ferquency: %lf Hz\", iterationCheck,  elapsed.toSec(), freqHz);\n            }\n        }\n\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n} // namespace sm_coretest_x_y_1\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/include/sm_coretest_x_y_1/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_coretest_x_y_1\n{\n// STATE DECLARATION\n\nextern int counter;\n\nstruct State2 : smacc::SmaccState<State2, SmCoreTestXY1>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State1, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/launch/sm_coretest_x_y_1.launch",
    "content": "<launch>\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_coretest_x_y_1)/config/rosconsole.config\" />\n    <node pkg=\"sm_coretest_x_y_1\" type=\"sm_coretest_x_y_1_node\" name=\"sm_coretest_x_y_1\" output=\"screen\"/>\n</launch>\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_coretest_x_y_1</name>\n    <version>1.4.16</version>\n  <description>The sm_coretest_x_y_1 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_coretest_x_y_1</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "test/sm_coretest_x_y_1/src/sm_coretest_x_y_1_node.cpp",
    "content": "#include <sm_coretest_x_y_1/sm_coretest_x_y_1.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_coretest_x_y_1\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_coretest_x_y_1::SmCoreTestXY1>();\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_coretest_x_y_2\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_coretest_x_y_2)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_coretest_x_y_2\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_coretest_x_y_2.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_coretest_x_y_2_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_coretest_x_y_2.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(FILES\n   config/rosconsole.config\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_coretest_x_y_2/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_coretest_x_y_2 sm_coretest_x_y_2.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.smacc=WARN\nlog4j.logger.ros.sm_coretest_x_y_2=WARN\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/include/sm_coretest_x_y_2/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_coretest_x_y_2\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_coretest_x_y_2\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/include/sm_coretest_x_y_2/sm_coretest_x_y_2.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_coretest_x_y_2/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_coretest_x_y_2\n{\n\nstruct AutomaticTransitionEvent: sc::event<AutomaticTransitionEvent>\n{\n\n};\n\nstatic int counter = 0;\nros::Time startTime;\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmCoreTestXY2\n    : public smacc::SmaccStateMachineBase<SmCoreTestXY2, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        startTime=ros::Time::now();\n    }\n};\n\n} // namespace sm_coretest_x_y_2\n\n#include <sm_coretest_x_y_2/states/st_state_1.h>\n#include <sm_coretest_x_y_2/states/st_state_2.h>\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/include/sm_coretest_x_y_2/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n#define iterationCheck  10000\n\nnamespace sm_coretest_x_y_2\n{\n\nextern int counter;\nextern ros::Time startTime;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmCoreTestXY2>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State2, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n\n        if (counter > iterationCheck )\n        {\n            ROS_ERROR(\"ey\");\n            auto now = ros::Time::now();;\n            auto elapsed =  now - startTime ;\n            auto freqHz = iterationCheck / elapsed.toSec();\n\n            startTime = now;\n            while(ros::ok())\n            {\n                ros::Duration(0.2).sleep();\n                ROS_ERROR(\"A %d iterations in %lf seconds. Ferquency: %lf Hz\", iterationCheck,  elapsed.toSec(), freqHz);\n            }\n        }\n\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n} // namespace sm_coretest_x_y_2\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/include/sm_coretest_x_y_2/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_coretest_x_y_2\n{\n// STATE DECLARATION\n\nextern int counter;\n\nstruct State2 : smacc::SmaccState<State2, SmCoreTestXY2>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State1, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/launch/sm_coretest_x_y_2.launch",
    "content": "<launch>\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_coretest_x_y_2)/config/rosconsole.config\" />\n    <node pkg=\"sm_coretest_x_y_2\" type=\"sm_coretest_x_y_2_node\" name=\"sm_coretest_x_y_2\" output=\"screen\"/>\n</launch>\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_coretest_x_y_2</name>\n    <version>1.4.16</version>\n  <description>The sm_coretest_x_y_2 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_coretest_x_y_2</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "test/sm_coretest_x_y_2/src/sm_coretest_x_y_2_node.cpp",
    "content": "#include <sm_coretest_x_y_2/sm_coretest_x_y_2.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_coretest_x_y_2\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_coretest_x_y_2::SmCoreTestXY2>();\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package sm_coretest_x_y_3\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nForthcoming\n-----------\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n\n* moved /test folder to top-level\n* Contributors: Brett Aldrich\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(sm_coretest_x_y_3)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\n\nfind_package(catkin REQUIRED smacc ros_timer_client)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a exec_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a exec_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES sm_coretest_x_y_3\n#  CATKIN_DEPENDS other_catkin_pkg\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\nset(CMAKE_CXX_STANDARD 14)\nadd_compile_options(-std=c++11) #workaround for ubuntu 16.04, to extinguish\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/sm_coretest_x_y_3.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\nadd_executable(${PROJECT_NAME}_node src/sm_coretest_x_y_3_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html\n install(TARGETS ${PROJECT_NAME}_node\n   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n )\n\n## Mark libraries for installation\n## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html\n# install(TARGETS ${PROJECT_NAME}\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\ninstall(FILES\n   launch/sm_coretest_x_y_3.launch\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n)\n\ninstall(FILES\n   config/rosconsole.config\n   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_sm_atomic.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/README.md",
    "content": " <h2>State Machine Diagram</h2>\n <img src=\"https://github.com/robosoft-ai/SMACC/blob/master/smacc_sm_reference_library/sm_coretest_x_y_3/docs/smacc_state_machine_20200207-004740.dot.svg\" width=\"950\" align=\"center\" border=\"10\"/>\n\n <h2>Description</h2> A completely minimal state machine example.<br></br>\n<a href=\"https://robosoft-ai.github.io/smacc_doxygen/master/html/namespacesm__atomic.html\">Doxygen Namespace & Class Reference</a>\n\n <h2>Build Instructions</h2>\nBefore you build, make sure you've installed all the dependencies...\n\n```\nrosdep install --from-paths src --ignore-src -r -y\n```\n\nThen you build with either catkin build or catkin make...\n\n```\ncatkin build\n```\n<h2>Operating Instructions</h2>\nAfter you build, remember to source the proper devel folder...\n\n```\nsource ~/catkin_ws/devel/setup.bash\n```\n\nAnd then run the launch file...\n\n```\nroslaunch sm_coretest_x_y_3 sm_coretest_x_y_3.launch\n```\n\n <h2>Viewer Instructions</h2>\nIf you have the SMACC Viewer installed then type...\n\n```\nrosrun smacc_viewer smacc_viewer_node.py\n```\n\nIf you don't have the SMACC Viewer installed, click <a href=\"http://smacc.ninja/smacc-viewer/\">here</a> for instructions.\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/config/rosconsole.config",
    "content": "log4j.logger.ros=INFO\nlog4j.logger.ros.roscpp.superdebug=WARN\nlog4j.logger.ros.smacc=WARN\nlog4j.logger.ros.sm_coretest_x_y_3=WARN\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/include/sm_coretest_x_y_3/orthogonals/or_timer.h",
    "content": "#include <smacc/smacc.h>\n#include <ros_timer_client/cl_ros_timer.h>\n\nnamespace sm_coretest_x_y_3\n{\nclass OrTimer : public smacc::Orthogonal<OrTimer>\n{\npublic:\n    virtual void onInitialize() override\n    {\n        auto client = this->createClient<cl_ros_timer::ClRosTimer>(ros::Duration(1));\n        client->initialize();\n    }\n};\n} // namespace sm_coretest_x_y_3\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/include/sm_coretest_x_y_3/sm_coretest_x_y_3.h",
    "content": "#include <smacc/smacc.h>\n\n// CLIENTS\n#include <ros_timer_client/cl_ros_timer.h>\n\n// ORTHOGONALS\n#include <sm_coretest_x_y_3/orthogonals/or_timer.h>\n\n//CLIENT BEHAVIORS\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_loop.h>\n#include <ros_timer_client/client_behaviors/cb_timer_countdown_once.h>\n\nusing namespace boost;\nusing namespace smacc;\n\nnamespace sm_coretest_x_y_3\n{\n\nstruct AutomaticTransitionEvent: sc::event<AutomaticTransitionEvent>\n{\n\n};\n\nstatic int counter = 0;\nros::Time startTime;\n\n//STATE\nclass State1;\nclass State2;\n\n//--------------------------------------------------------------------\n//STATE_MACHINE\nstruct SmCoreTestXY3\n    : public smacc::SmaccStateMachineBase<SmCoreTestXY3, State1>\n{\n    using SmaccStateMachineBase::SmaccStateMachineBase;\n\n    virtual void onInitialize() override\n    {\n        startTime=ros::Time::now();\n    }\n};\n\n} // namespace sm_coretest_x_y_3\n\n#include <sm_coretest_x_y_3/states/st_state_1.h>\n#include <sm_coretest_x_y_3/states/st_state_2.h>\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/include/sm_coretest_x_y_3/states/st_state_1.h",
    "content": "#include <smacc/smacc.h>\n#define iterationCheck  10000\n\nnamespace sm_coretest_x_y_3\n{\n\nextern int counter;\nextern ros::Time startTime;\n\n// STATE DECLARATION\nstruct State1 : smacc::SmaccState<State1, SmCoreTestXY3>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State2, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n\n        if (counter > iterationCheck )\n        {\n            ROS_ERROR(\"ey\");\n            auto now = ros::Time::now();;\n            auto elapsed =  now - startTime ;\n            auto freqHz = iterationCheck / elapsed.toSec();\n\n            startTime = now;\n            while(ros::ok())\n            {\n                ros::Duration(0.2).sleep();\n                ROS_ERROR(\"A %d iterations in %lf seconds. Ferquency: %lf Hz\", iterationCheck,  elapsed.toSec(), freqHz);\n            }\n        }\n\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n} // namespace sm_coretest_x_y_3\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/include/sm_coretest_x_y_3/states/st_state_2.h",
    "content": "#include <smacc/smacc.h>\n\nnamespace sm_coretest_x_y_3\n{\n// STATE DECLARATION\n\nextern int counter;\n\nstruct State2 : smacc::SmaccState<State2, SmCoreTestXY3>\n{\n    using SmaccState::SmaccState;\n\n    // TRANSITION TABLE\n    typedef mpl::list<\n\n        Transition<AutomaticTransitionEvent, State1, SUCCESS>>\n        reactions;\n\n    // STATE FUNCTIONS\n    static void staticConfigure()\n    {\n    }\n\n    void onEntry()\n    {\n        counter++;\n        this->postEvent<AutomaticTransitionEvent>();\n    }\n};\n}\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/launch/sm_coretest_x_y_3.launch",
    "content": "<launch>\n    <env name=\"ROSCONSOLE_CONFIG_FILE\" value=\"$(find sm_coretest_x_y_3)/config/rosconsole.config\" />\n    <node pkg=\"sm_coretest_x_y_3\" type=\"sm_coretest_x_y_3_node\" name=\"sm_coretest_x_y_3\" output=\"screen\"/>\n</launch>\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/package.xml",
    "content": "<?xml version=\"1.0\" ?>\n<package format=\"2\">\n  <name>sm_coretest_x_y_3</name>\n    <version>1.4.16</version>\n  <description>The sm_coretest_x_y_3 package</description>\n\n\n  <maintainer email=\"pablo@ibrobotics.com\">Pablo Inigo Blasco</maintainer>\n\n\n\n  <license>BSD-3</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/sm_coretest_x_y_3</url> -->\n\n\n\n\n\n\n  <buildtool_depend>catkin</buildtool_depend>\n  <depend>roscpp</depend>\n  <depend>smacc</depend>\n  <depend>ros_timer_client</depend>\n\n\n  <export>\n\n\n  </export>\n</package>\n"
  },
  {
    "path": "test/sm_coretest_x_y_3/src/sm_coretest_x_y_3_node.cpp",
    "content": "#include <sm_coretest_x_y_3/sm_coretest_x_y_3.h>\n\n//--------------------------------------------------------------------\nint main(int argc, char **argv)\n{\n    ros::init(argc, argv, \"sm_coretest_x_y_3\");\n    ros::NodeHandle nh;\n\n    smacc::run<sm_coretest_x_y_3::SmCoreTestXY3>();\n}\n"
  }
]