[
  {
    "path": ".github/workflows/ci-docs2.yml",
    "content": "name: Docs\n\non:\n  push:\n    branches: [ main ]\n  pull_request:\n    branches: [ main ]\n\njobs:\n  build:\n    runs-on: ubuntu-latest\n    steps:\n\n    - name: Checkout\n      uses: actions/checkout@v2\n\n    # Handle dependencies here instead of conda_env.yaml\n    # because some packages are conda-forge only,\n    # which makes the env build much more slowly.\n\n    - name: Install dependencies\n      run: |\n        sudo apt update\n        sudo apt install texlive-latex-extra dvipng\n        sudo pip3 install -U setuptools\n        sudo pip3 install -U -r docs2/requirements.txt --ignore-installed PyYAML\n\n    - name: Build Docs\n      run: |\n        cd docs2\n        make html\n\n    - name: Disable github Jekyll\n      run: |\n        touch docs2/_build/html/.nojekyll\n\n    - name: Deploy\n      if: github.ref == 'refs/heads/main'\n      uses: JamesIves/github-pages-deploy-action@v4\n      with:\n        folder: docs2/_build/html # The folder the action should deploy.\n"
  },
  {
    "path": ".github/workflows/ci-ros2-mac.yml",
    "content": "name: ROS2 (Mac)\n\n# Disable for now\non:\n  push:\n    branches-ignore:\n      - '**'\n# on:\n#   push:\n#     branches: [ main ]\n#   pull_request:\n#     branches: [ main ]\n\njobs:\n  build: # Docker is not supported on macOS and Windows.\n    runs-on: macOS-latest\n    steps:\n      - uses: ros-tooling/setup-ros@v0.2\n        with:\n          required-ros-distributions: galactic\n\n      # There is a bug in vcstools, where submodules are not pulled recursively\n      # See https://github.com/dirk-thomas/vcstool/issues/205\n      # This is fixed in master, but not in the latest release\n      # Pull the latest version here\n      - name: install dependencies\n        run: |\n          sudo pip3 install git+https://github.com/dirk-thomas/vcstool.git@7d1329f296cef4b767bf7ba0bf53a29dd3d3019c\n\n      - name: Install dependencies\n        run: |\n          brew install libusb\n\n      - name: build and test ROS 2\n        uses: ros-tooling/action-ros-ci@v0.2\n        with:\n          package-name: crazyflie crazyflie_interfaces\n          target-ros2-distro: galactic\n          colcon-defaults: |\n                  {\n                    \"build\": {\n                      \"packages-select\": [\n                          \"crazyflie\",\n                          \"crazyflie_interfaces\"\n                      ]\n                    }\n                  }"
  },
  {
    "path": ".github/workflows/ci-ros2-win.yml",
    "content": "name: ROS2 (Windows)\n\n# Disable for now\non:\n  push:\n    branches-ignore:\n      - '**'\n# on:\n#   push:\n#     branches: [ main ]\n#   pull_request:\n#     branches: [ main ]\n\njobs:\n  build: # Docker is not supported on macOS and Windows.\n    runs-on: windows-latest\n    steps:\n      - uses: ros-tooling/setup-ros@v0.2\n        with:\n          required-ros-distributions: galactic\n\n      # # There is a bug in vcstools, where submodules are not pulled recursively\n      # # See https://github.com/dirk-thomas/vcstool/issues/205\n      # # This is fixed in master, but not in the latest release\n      # # Pull the latest version here\n      # - name: install dependencies\n      #   run: |\n      #     pip3 install git+https://github.com/dirk-thomas/vcstool.git@7d1329f296cef4b767bf7ba0bf53a29dd3d3019c\n\n      # - name: Install dependencies\n      #   run: |\n      #     brew install libusb\n\n      - name: build and test ROS 2\n        uses: ros-tooling/action-ros-ci@v0.2\n        with:\n          package-name: crazyflie crazyflie_interfaces\n          target-ros2-distro: galactic\n          colcon-defaults: |\n                  {\n                    \"build\": {\n                      \"packages-select\": [\n                          \"crazyflie\",\n                          \"crazyflie_interfaces\"\n                      ]\n                    }\n                  }"
  },
  {
    "path": ".github/workflows/ci-ros2.yml",
    "content": "name: ROS2 (Ubuntu)\n\non:\n  push:\n    branches: [ main ]\n  pull_request:\n    branches: [ main ]\n\n# Based on example provided at https://github.com/ros-tooling/setup-ros\n\njobs:\n  build_docker: # On Linux, use docker\n    runs-on: ubuntu-latest\n    strategy:\n      fail-fast: False\n      matrix:\n        ros_distribution:\n          - humble\n          - jazzy\n          - rolling\n\n        # Define the Docker image(s) associated with each ROS distribution.\n        include:\n          # Humble Hawksbill (May 2022 - May 2027)\n          - docker_image: rostooling/setup-ros-docker:ubuntu-jammy-ros-humble-ros-base-latest\n            ros_distribution: humble\n            ros_version: 2\n\n          # Jazzy Jalisco (May 2024 - May 2029)\n          - docker_image: rostooling/setup-ros-docker:ubuntu-noble-ros-jazzy-ros-base-latest\n            ros_distribution: jazzy\n            ros_version: 2\n\n          # Rolling Ridley  (June 2020 - Present)\n          - docker_image: rostooling/setup-ros-docker:ubuntu-noble-ros-rolling-ros-base-latest\n            ros_distribution: rolling\n            ros_version: 2\n\n    container:\n      image: ${{ matrix.docker_image }}\n    steps:\n      - name: install dependencies\n        run: |\n          sudo apt update\n          sudo apt install -y libboost-program-options-dev libusb-1.0-0-dev\n\n      - name: install pip dependencies\n          # TODO: would be better to follow https://answers.ros.org/question/370666/how-to-declare-an-external-python-dependency-in-ros2/\n          # but this requires some upstream changes\n\n          # colcon still does not seem to properly support venv, so we use a workaround to install\n          # a python package globally by disabling the externally managed flag that is default on Ubuntu 24.04\n        run: |\n          sudo rm -f /usr/lib/python3.12/EXTERNALLY-MANAGED\n          pip install rowan\n\n      - uses: actions/checkout@v2\n      - name: build and test ROS 2\n        uses: ros-tooling/action-ros-ci@v0.3\n        with:\n          package-name: |\n            crazyflie\n            crazyflie_examples\n            crazyflie_interfaces\n            crazyflie_py\n            crazyflie_sim\n          target-ros2-distro: ${{ matrix.ros_distribution }}\n          vcs-repo-file-url: rosinstall\n"
  },
  {
    "path": ".github/workflows/systemtests.yml",
    "content": "name: System Tests\n\non:\n  push:\n    branches: [ \"feature-systemtests-better\" ]\n  # manual trigger\n  workflow_dispatch:\n\njobs:\n  build:\n    runs-on: threadripper\n    steps:\n      - name: Create workspace\n        id: step1\n        run: |\n          cd ros2_ws/src || mkdir -p ros2_ws/src\n      - name: Checkout motion capture package\n        id: step2\n        run: |\n          cd ros2_ws/src\n          ls motion_capture_tracking || git clone --branch ros2 --recursive https://github.com/IMRCLab/motion_capture_tracking.git\n      - name: Checkout Crazyswarm2\n        id: step3\n        uses: actions/checkout@v4\n        with:\n          path: ros2_ws/src/crazyswarm2\n          submodules: 'recursive'\n      - name: Build workspace\n        id: step4\n        run: |\n          source /opt/ros/humble/setup.bash\n          cd ros2_ws\n          colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release\n\n      - name: Flight test\n        id: step5\n        run: |\n          cd ros2_ws\n          source /opt/ros/humble/setup.bash\n          . install/local_setup.bash\n          export ROS_LOCALHOST_ONLY=1\n          export ROS_DOMAIN_ID=99\n          python3 src/crazyswarm2/systemtests/test_flights.py\n\n      - name: Upload files\n        id: step6\n        if: '!cancelled()'\n        uses: actions/upload-artifact@v3\n        with:\n          name: pdf_rosbags_and_logs\n          path: |\n            ros2_ws/results\n          \n\n\n\n      \n\n      # - name: build and test ROS 2\n      #   uses: ros-tooling/action-ros-ci@v0.3\n      #   with:\n      #     package-name: |\n      #       crazyflie\n      #       crazyflie_examples\n      #       crazyflie_interfaces\n      #       crazyflie_py\n      #       crazyflie_sim\n      #     target-ros2-distro: humble\n      #     vcs-repo-file-url: rosinstall"
  },
  {
    "path": ".github/workflows/systemtests_sim.yml",
    "content": "name: System Tests Simulation \n\non:\n  push:\n    branches: [ main ]\n  pull_request:\n    branches: [ main ]\n  # manual trigger\n  workflow_dispatch:\n\njobs:\n  build:\n    runs-on: threadripper\n    steps:\n      - name: Build firmware\n        id: step1\n        run: |\n          ls crazyflie-firmware || git clone --recursive https://github.com/bitcraze/crazyflie-firmware.git\n          cd crazyflie-firmware\n          git pull\n          git submodule sync\n          git submodule update --init --recursive\n          make cf2_defconfig\n          make bindings_python  \n          cd build\n          python3 setup.py install --user   \n      - name: Create workspace\n        id: step2\n        run: |\n          cd ros2_ws/src || mkdir -p ros2_ws/src\n      - name: Checkout motion capture package\n        id: step3\n        run: |\n          cd ros2_ws/src\n          ls motion_capture_tracking || git clone --branch ros2 --recursive https://github.com/IMRCLab/motion_capture_tracking.git\n          cd motion_capture_tracking\n          git pull\n          git submodule sync\n          git submodule update --recursive --init\n      - name: Checkout Crazyswarm2\n        id: step4\n        uses: actions/checkout@v4\n        with:\n          path: ros2_ws/src/crazyswarm2\n          submodules: 'recursive'\n      - name: Build workspace\n        id: step5\n        run: |\n          source /opt/ros/humble/setup.bash\n          cd ros2_ws\n          colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release\n\n      - name: Flight test\n        id: step6\n        run: |\n          cd ros2_ws\n          source /opt/ros/humble/setup.bash\n          . install/local_setup.bash\n          export PYTHONPATH=\"${PYTHONPATH}:/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/crazyflie-firmware/build/\"\n          export ROS_LOCALHOST_ONLY=1\n          export ROS_DOMAIN_ID=99\n          python3 src/crazyswarm2/systemtests/test_flights.py --sim -v    #-v is verbose argument of unittest\n\n      - name: Upload files\n        id: step7\n        if: '!cancelled()'\n        uses: actions/upload-artifact@v4\n        with:\n          name: pdf_rosbags_and_logs\n          path: |\n            ros2_ws/results\n            \n\n\n\n            \n          \n"
  },
  {
    "path": ".gitignore",
    "content": ".DS_Store\ncrazyswarm2_sim_webots/\n*.pyc\n*.o\n*~\n"
  },
  {
    "path": ".gitmodules",
    "content": "[submodule \"crazyflie/deps/crazyflie_tools\"]\n\tpath = crazyflie/deps/crazyflie_tools\n\turl = https://github.com/whoenig/crazyflie_tools.git\n"
  },
  {
    "path": "LICENSE",
    "content": "The MIT License (MIT)\n\nCopyright (c) 2014 whoenig\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n\n"
  },
  {
    "path": "README.md",
    "content": "* Local CI: [![ROS 2](https://github.com/IMRCLab/crazyswarm2/actions/workflows/ci-ros2.yml/badge.svg)](https://github.com/IMRCLab/crazyswarm2/actions/workflows/ci-ros2.yml)\n* Rolling Dev CI : [![Build Status](https://build.ros2.org/job/Rdev__crazyflie__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Rdev__crazyflie__ubuntu_noble_amd64/)\n* Jazzy Dev CI: [![Build Status](https://build.ros2.org/job/Jdev__crazyswarm2__ubuntu_noble_amd64/badge/icon)](https://build.ros2.org/job/Jdev__crazyswarm2__ubuntu_noble_amd64/)\n* Humble Dev CI: [![Build Status](https://build.ros2.org/job/Hdev__crazyswarm2__ubuntu_jammy_amd64/badge/icon)](https://build.ros2.org/job/Hdev__crazyswarm2__ubuntu_jammy_amd64/)\n\n\n# Crazyswarm2\nA ROS 2-based stack for Bitcraze Crazyflie multirotor robots.\n\nThe documentation is available here: https://imrclab.github.io/crazyswarm2/.\n\n## Troubleshooting\nPlease start a [Discussion](https://github.com/IMRCLab/crazyswarm2/discussions) for...\n\n- Getting Crazyswarm2 to work with your hardware setup.\n- Advice on how to use it to achieve your goals.\n- Rough ideas for a new feature.\n\nPlease open an [Issue](https://github.com/IMRCLab/crazyswarm2/issues) if you believe that fixing your problem will involve a **change in the Crazyswarm2 source code**, rather than your own configuration files. For example...\n\n- Bug reports.\n- New feature proposals with details.\n"
  },
  {
    "path": "crazyflie/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package crazyflie\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.0.3 (2025-07-09)\n------------------\n* Improve package.xml (separate maintainer tags, update year)\n* Contributors: Kimberly N. McGuire\n\n1.0.2 (2025-07-02)\n------------------\n\n1.0.1 (2025-06-30)\n------------------\n* Fix build errors and dependencies on ROS Build Farm\n* Contributors: Kimberly N. McGuire, Wolfgang Hönig\n\n1.0.0 (2025-06-21)\n------------------\n* First official release.\n* Contributors: Christian Llanes, Julien Thevenoz, Khaled Wahba, Kimberly N. McGuire, Pablo, Wolfgang Hönig, Zach Williams, ben-jarvis, nan cai, phanfeld, torobo\n"
  },
  {
    "path": "crazyflie/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(crazyflie)\n\n#if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n#  add_compile_options(-Wall -Wextra -Wpedantic)\n#endif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_python REQUIRED)\nfind_package(rclcpp REQUIRED)\nfind_package(tf2_ros REQUIRED)\nfind_package(rclpy REQUIRED)\nfind_package(std_srvs REQUIRED)\nfind_package(nav_msgs REQUIRED)\nfind_package(sensor_msgs REQUIRED)\nfind_package(crazyflie_interfaces REQUIRED)\nfind_package(geometry_msgs REQUIRED)\nfind_package(motion_capture_tracking_interfaces REQUIRED)\nfind_package(Eigen3 REQUIRED)\nfind_package(ros_environment REQUIRED)\n\nif (DEFINED ENV{ROS_DISTRO})\n  set(ROS_DISTRO_VALUE \"$ENV{ROS_DISTRO}\")\nelse()\n  message(WARNING \"ROS_DISTRO environment variable not set. C++ macro will be empty or default.\")\n  set(ROS_DISTRO_VALUE \"unknown_distro\") # Or an empty string, or \"NO_ROS_DISTRO_SET\"\nendif()\n\n# add dependencies\nadd_subdirectory(deps/crazyflie_tools)\n# add_subdirectory(externalDependencies/libmotioncapture)\n\ninclude_directories(\n  deps/crazyflie_tools/crazyflie_cpp/include\n  deps/crazyflie_tools/crazyflie_cpp/crazyflie-link-cpp/include\n#  externalDependencies/libobjecttracker/include\n#  externalDependencies/libmotioncapture/include\n  ${EIGEN3_INCLUDE_DIRS}\n#  ${PCL_INCLUDE_DIRS}\n)\n\nadd_executable(teleop \n  src/teleop.cpp\n)\nament_target_dependencies(teleop \n  rclcpp\n  sensor_msgs\n  std_srvs\n  crazyflie_interfaces\n  geometry_msgs\n)\n\nadd_executable(crazyflie_server \n  src/crazyflie_server.cpp\n)\ntarget_link_libraries(crazyflie_server\n  crazyflie_cpp\n)\n\nif(\"${ROS_DISTRO_VALUE}\" STREQUAL \"humble\")\n  target_compile_definitions(crazyflie_server PRIVATE ROS_DISTRO_HUMBLE)\nendif()\n\nament_target_dependencies(crazyflie_server\n  rclcpp\n  tf2_ros\n  sensor_msgs\n  nav_msgs\n  std_srvs\n  crazyflie_interfaces\n  motion_capture_tracking_interfaces\n)\n\n# # scan\n# add_executable(scan\n#   src/scan.cpp\n# )\n# target_link_libraries(scan\n#   crazyflie_cpp\n#   ${Boost_LIBRARIES}\n# )\n# target_compile_features(scan PUBLIC c_std_99 cxx_std_17)\n\n#add_executable(motion_capture_tracking_node\n#  src/motion_capture_tracking_node.cpp\n#)\n#target_link_libraries(motion_capture_tracking_node\n#  libobjecttracker\n#  libmotioncapture\n#)\n#ament_target_dependencies(motion_capture_tracking_node\n#  rclcpp\n#)\n#target_include_directories(motion_capture_tracking_node PUBLIC\n#  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>\n#  $<INSTALL_INTERFACE:include>)\n#target_compile_features(motion_capture_tracking_node PUBLIC c_std_99 cxx_std_17)  # Require C99 and C++17\n\n# Install C++ executables\ninstall(TARGETS\n  # crazyflie_tools\n  comCheck\n  scan\n  listParams\n  listLogVariables\n  listMemories\n  reboot\n  battery\n  version\n  console\n  log\n  setParam\n  downloadUSDLogfile\n  #\n  teleop\n  crazyflie_server\n  DESTINATION lib/${PROJECT_NAME})\n\n# Install Python executables\ninstall(PROGRAMS\n  scripts/crazyflie_server.py\n  scripts/chooser.py\n  scripts/vel_mux.py\n  scripts/cfmult.py\n  scripts/simple_mapper_multiranger.py\n  scripts/aideck_streamer.py\n  scripts/gui.py\n  scripts/flash.py\n  DESTINATION lib/${PROJECT_NAME}\n)\n\n# Install launch, config, and urdf files.\ninstall(DIRECTORY\n  launch\n  config\n  urdf\n  DESTINATION share/${PROJECT_NAME}/\n)\n\n# if(BUILD_TESTING)\n#   find_package(ament_lint_auto REQUIRED)\n#   # the following line skips the linter which checks for copyrights\n#   # uncomment the line when a copyright and license is not present in all source files\n#   #set(ament_cmake_copyright_FOUND TRUE)\n#   # the following line skips cpplint (only works in a git repo)\n#   # uncomment the line when this package is not in a git repo\n#   #set(ament_cmake_cpplint_FOUND TRUE)\n#   ament_lint_auto_find_test_dependencies()\n# endif()\n\nament_package()\n"
  },
  {
    "path": "crazyflie/config/aideck_streamer.yaml",
    "content": "image_topic: /camera/image\ncamera_info_topic: /camera/camera_info\ndeck_ip: \"192.168.4.1\"\ndeck_port: 5000\nimage_width: 324\nimage_height: 324\ncamera_name: crazyflie\ncamera_matrix:\n  rows: 3\n  cols: 3\n  data: [181.87464,   0.     , 162.52301,\n           0.     , 182.58129, 160.79418,\n           0.     ,   0.     ,   1.     ]\ndistortion_model: plumb_bob\ndistortion_coefficients:\n  rows: 1\n  cols: 5\n  data: [-0.070366, -0.006434, -0.002691, -0.001983, 0.000000]\nrectification_matrix:\n  rows: 3\n  cols: 3\n  data: [1., 0., 0.,\n         0., 1., 0.,\n         0., 0., 1.]\nprojection_matrix:\n  rows: 3\n  cols: 4\n  data: [169.24555,   0.     , 161.54541,   0.     ,\n           0.     , 169.97813, 159.07974,   0.     ,\n           0.     ,   0.     ,   1.     ,   0.     ]"
  },
  {
    "path": "crazyflie/config/config.rviz",
    "content": "Panels:\n  - Class: rviz_common/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n      Splitter Ratio: 0.5\n    Tree Height: 549\n  - Class: rviz_common/Selection\n    Name: Selection\n  - Class: rviz_common/Tool Properties\n    Expanded:\n      - /2D Goal Pose1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz_common/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz_common/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: \"\"\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz_default_plugins/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Class: rviz_default_plugins/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        cf231:\n          Value: true\n        world:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        world:\n          cf231:\n            {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Class: rviz_default_plugins/RobotModel\n      Collision Enabled: false\n      Description File: \"\"\n      Description Source: Topic\n      Description Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /cf231/robot_description\n      Enabled: true\n      Links:\n        All Links Enabled: true\n        Expand Joint Details: false\n        Expand Link Details: false\n        Expand Tree: false\n        Link Tree Style: Links in Alphabetic Order\n        cf231:\n          Alpha: 1\n          Show Axes: false\n          Show Trail: false\n          Value: true\n      Mass Properties:\n        Inertia: false\n        Mass: false\n      Name: CF231\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: true\n      Visual Enabled: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: world\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz_default_plugins/Interact\n      Hide Inactive Objects: true\n    - Class: rviz_default_plugins/MoveCamera\n    - Class: rviz_default_plugins/Select\n    - Class: rviz_default_plugins/FocusCamera\n    - Class: rviz_default_plugins/Measure\n      Line color: 128; 128; 0\n    - Class: rviz_default_plugins/SetInitialPose\n      Covariance x: 0.25\n      Covariance y: 0.25\n      Covariance yaw: 0.06853891909122467\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /initialpose\n    - Class: rviz_default_plugins/SetGoal\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /goal_pose\n    - Class: rviz_default_plugins/PublishPoint\n      Single click: true\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /clicked_point\n  Transformation:\n    Current:\n      Class: rviz_default_plugins/TF\n  Value: true\n  Views:\n    Current:\n      Class: rviz_default_plugins/Orbit\n      Distance: 3.1647839546203613\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.05999999865889549\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: -0.028163839131593704\n        Y: -0.049007341265678406\n        Z: -0.025782346725463867\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.05000000074505806\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.009999999776482582\n      Pitch: 0.4847976565361023\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 2.9185757637023926\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 846\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1200\n  X: 74\n  Y: 60\n"
  },
  {
    "path": "crazyflie/config/crazyflies.yaml",
    "content": "# named list of all robots\nfileversion: 3\n\nrobots:\n  cf231:\n    enabled: true\n    uri: radio://0/80/2M/E7E7E7E7E7\n    initial_position: [0.0, 0.0, 0.0]\n    type: cf21  # see robot_types\n    # firmware_params:\n    #   kalman:\n    #     pNAcc_xy: 1.0 # default 0.5\n    # firmware_logging:\n    #   enabled: true\n    #   custom_topics:\n    #     topic_name3: \n    #       frequency: 1\n    #       vars: [\"acc.x\", \"acc.y\"]\n    # reference_frame: \"odom_cf231\" # use a custom reference frame if no global coordinate system is available\n\n  cf5:\n    enabled: false\n    uri: radio://0/80/2M/E7E7E7E705\n    initial_position: [0.0, -0.5, 0.0]\n    type: cf21  # see robot_types\n    # firmware_params:\n    #   kalman:\n    #     pNAcc_xy: 1.0 # default 0.5\n    #firmware_logging:\n    #  custom_topics:\n    #    topic_name3: \n    #      frequency: 1\n    #      vars: [\"acc.x\", \"acc.y\", \"acc.z\"]\n    # reference_frame: \"odom_cf5\" \n\n# Definition of the various robot types\nrobot_types:\n  cf21:\n    motion_capture:\n      tracking: \"librigidbodytracker\" # one of \"vendor\", \"librigidbodytracker\"\n      # only if enabled; see motion_capture.yaml\n      marker: default_single_marker\n      dynamics: default\n    big_quad: false\n    battery:\n      voltage_warning: 3.8  # V\n      voltage_critical: 3.7 # V\n    # firmware_params:\n    #   kalman:\n    #     pNAcc_xy: 1.0 # default 0.5\n    #firmware_logging:\n    #   enabled: true\n    #   default_topics:\n    #   pose:\n    #     frequency: 1 # Hz\n    #   custom_topics:\n    #    topic_name3: \n    #      frequency: 1\n    #      vars: [\"acc.x\", \"acc.y\", \"acc.z\"]\n    # reference_frame: \"odom\" \n\n  cf21_mocap_deck:\n    motion_capture:\n      tracking: \"librigidbodytracker\" # one of \"vendor\", \"librigidbodytracker\"\n      # only if enabled; see motion_capture.yaml\n      marker: mocap_deck\n      dynamics: default\n    big_quad: false\n    battery:\n      voltage_warning: 3.8  # V\n      voltage_critical: 3.7 # V\n    # firmware_params:\n    #   kalman:\n    #     pNAcc_xy: 1.0 # default 0.5\n    #firmware_logging:\n    #   enabled: true\n    #   default_topics:\n    #   pose:\n    #     frequency: 1 # Hz\n    #   custom_topics:\n    #    topic_name3: \n    #      frequency: 1\n    #      vars: [\"acc.x\", \"acc.y\", \"acc.z\"]\n    # reference_frame: \"mocap\" \n\n# global settings for all robots\nall:\n  # firmware logging for all drones (use robot_types/type_name to set per type, or\n  # robots/drone_name to set per drone)\n  firmware_logging:\n    enabled: true\n    default_topics:\n     # remove to disable default topic\n      pose:\n        frequency: 10 # Hz\n      status:\n        frequency: 1 # Hz\n    #custom_topics:\n    #  topic_name1:\n    #    frequency: 10 # Hz\n    #    vars: [\"stateEstimateZ.x\", \"stateEstimateZ.y\", \"stateEstimateZ.z\", \"pm.vbat\"]\n    #  topic_name2:\n    #    frequency: 1 # Hz\n    #    vars: [\"stabilizer.roll\", \"stabilizer.pitch\", \"stabilizer.yaw\"]\n  # firmware parameters for all drones (use robot_types/type_name to set per type, or\n  # robots/drone_name to set per drone)\n  firmware_params:\n    commander:\n      enHighLevel: 1\n    stabilizer:\n      estimator: 2 # 1: complementary, 2: kalman\n      controller: 2 # 1: PID, 2: mellinger\n    # ring:\n    #   effect: 16 # 6: double spinner, 7: solid color, 16: packetRate\n    #   solidBlue: 255 # if set to solid color\n    #   solidGreen: 0 # if set to solid color\n    #   solidRed: 0 # if set to solid color\n    #   headlightEnable: 0\n    locSrv:\n      extPosStdDev: 1e-3\n      extQuatStdDev: 0.5e-1\n    # kalman:\n    #   resetEstimation: 1\n  # reference frame for on-board state-estimate of all drones (use robot_types/type_name to set per type, or\n  # robots/drone_name to set per drone)\n  reference_frame: \"world\"\n  broadcasts:\n    num_repeats: 15 # number of times broadcast commands are repeated\n    delay_between_repeats_ms: 1 # delay in milliseconds between individual repeats\n"
  },
  {
    "path": "crazyflie/config/motion_capture.yaml",
    "content": "/motion_capture_tracking:\n  ros__parameters:\n    # one of \"optitrack\", \"optitrack_closed_source\", \"vicon\", \"qualisys\", \"nokov\", \"vrpn\", \"motionanalysis\"\n    type: \"optitrack\"\n    # Specify the hostname or IP of the computer running the motion capture software\n    hostname: \"141.23.110.143\"\n\n    topics:\n      frame_id: \"mocap\"\n      poses:\n        qos:\n          mode: \"sensor\"\n          deadline: 100.0 # Hz\n      tf:\n        child_frame_id: \"{}_mocap\"\n\n    marker_configurations:\n      default: # for standard Crazyflie\n        offset: [0.0, 0.0, 0.0]\n        points:\n          p0: [   0.0,    0.0, 0.022]  # top\n          p1: [-0.042,  0.042, 0.0  ]  # back left   (M3)\n          p2: [-0.042, -0.042, 0.0  ]  # back right  (M2)\n          p3: [ 0.042, -0.042, 0.0  ]  # front right (M1)\n      default_single_marker:\n        offset: [0.0, -0.01, -0.04]\n        points:\n          p0: [0.0177184,0.0139654,0.0557585]\n      mocap_deck:\n        offset: [0.0, 0.0, -0.01]\n        points:\n          p0: [0.03, 0.0, 0.0] # front\n          p1: [0.00, -0.03, 0.0] # right\n          p2: [-0.015, 0.0, 0.0] # back\n          p3: [0.00, 0.03, 0.0] # left\n      medium_frame:\n        offset: [0.0, 0.0, -0.03]\n        points:\n          p0: [-0.00896228,-0.000716753,0.0716129]\n          p1: [-0.0156318,0.0997402,0.0508162]\n          p2: [0.0461693,-0.0881012,0.0380672]\n          p3: [-0.0789959,-0.0269793,0.0461144]\n      big_frame:\n        offset: [0.0, 0.0, -0.06]\n        points:\n          p0: [0.0558163,-0.00196302,0.0945539]\n          p1: [-0.0113941,0.00945842,0.0984811]\n          p2: [-0.0306277,0.0514879,0.0520456]\n          p3: [0.0535816,-0.0400775,0.0432799]\n\n    dynamics_configurations:\n      default:\n        max_velocity: [2, 2, 3] # m/s\n        max_angular_velocity: [20, 20, 10] # rad/s\n        max_roll: 1.4 #rad\n        max_pitch: 1.4 #rad\n        max_fitness_score: 0.001\n\n    # Rigid bodies will be automatically generated by the launch file\n    # rigid_bodies:"
  },
  {
    "path": "crazyflie/config/server.yaml",
    "content": "/crazyflie_server:\n  ros__parameters:\n    warnings:\n      frequency: 1.0 # report/run checks once per second\n      motion_capture:\n        warning_if_rate_outside: [80.0, 120.0]\n      communication:\n        max_unicast_latency: 10.0 # ms\n        min_unicast_ack_rate: 0.9\n        min_unicast_receive_rate: 0.9 # requires status topic to be enabled\n        min_broadcast_receive_rate: 0.9 # requires status topic to be enabled\n        publish_stats: false\n    firmware_params:\n      query_all_values_on_connect: False\n    # simulation related\n    sim:\n      max_dt: 0 #0.1              # artificially limit the step() function (set to 0 to disable)\n      backend: np                 # see backend folder for a list \n      visualizations:             # see visualization folder for a list\n        rviz:\n          enabled: true\n        pdf:\n          enabled: false\n          output_file: \"result.pdf\"\n        record_states:\n          enabled: false\n          output_dir: \"state_info\"\n          logging_time: 0.2  # how many seconds to leave between logs\n          file_formats: [\"csv\", \"np\"] # csv, np\n        blender:\n          enabled: false\n          fps: 1           # frames per second\n          cycle_bg: false  # if true, pictures will cycle through different environemt background images (useful for synthetic image generation). Otherwise a single environment background image will be used\n          cf_cameras:      # names of crazyflies with cameras on them if enabled in `crazyflies.yaml`\n            cf231:\n              calibration:\n                tvec: [0,0,0]\n                rvec: [1.2092,-1.2092,1.2092]   # 0 deg tilt (cameras looks in front of crazyflie)\n            cf5:\n              calibration:\n                tvec: [0,0,0]\n                rvec: [ 0.61394313, -0.61394313,  1.48218982]   # 45 deg tilt\n      controller: mellinger # none, pid, mellinger\n"
  },
  {
    "path": "crazyflie/config/teleop.yaml",
    "content": "/teleop:\n  ros__parameters:\n    frequency: 100  # set to 0, to disable manual flight modes\n    mode: \"high_level\" # one of high_level, cmd_rpy, cmd_vel_world\n    cmd_rpy:\n      roll:\n        axis: 5\n        max: 30.0 # deg\n        deadband: 0.0\n      pitch:\n        axis: 4\n        max: 30.0 # deg\n        deadband: 0.0\n      yawrate:\n        axis: 1\n        max: 200.0 # deg/s\n        deadband: 5.0 # deg/s\n      thrust:\n        axis: 2\n        max: 60000.0 # PWM\n        deadband: 0.0\n    cmd_vel_world:\n      x_velocity:\n        axis: 5\n        max: 0.5 # m/s\n        deadband: 0.1 # m/s\n      y_velocity:\n        axis: 4\n        max: 0.5 # m/s\n        deadband: 0.1 # m/s\n      z_velocity:\n        axis: 2\n        max: 0.5 # m/s\n        deadband: 0.1 # m/s\n      yaw_velocity:\n        axis: 1\n        max: 0.5 # rad/s\n        deadband: 0.1 # rad/s\n      # workspace limits\n      x_limit: [-1.0, 1.0] # m\n      y_limit: [-1.0, 1.0] # m\n      z_limit: [0.0, 2.5] # m\n    initial_position:\n      x: 0.0\n      y: 0.0\n      z: 0.10\n    auto_yaw_rate: 0.0 # rad/s, use 0.0 for manual yaw control\n    takeoff:\n      duration: 2.0\n      height: 0.5\n      button: 7  # 7 start\n    land:\n      button: 6 # 6 back\n    emergency:\n      button: 1 # 1 red\n    arm:\n      button: 3 # yellow\n\n"
  },
  {
    "path": "crazyflie/launch/launch.py",
    "content": "import os\nimport yaml\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument, OpaqueFunction\nfrom launch_ros.actions import Node\nfrom launch.conditions import LaunchConfigurationEquals\nfrom launch.conditions import IfCondition\nfrom launch.substitutions import LaunchConfiguration, PythonExpression\n\ndef parse_yaml(context):\n    # Load the crazyflies YAML file\n    crazyflies_yaml = LaunchConfiguration('crazyflies_yaml_file').perform(context)\n    with open(crazyflies_yaml, 'r') as file:\n        crazyflies = yaml.safe_load(file)\n    # store the fileversion\n    fileversion = 1\n    if \"fileversion\" in crazyflies:\n        fileversion = crazyflies[\"fileversion\"]\n\n    # server params\n    server_yaml = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'server.yaml')\n\n    with open(server_yaml, 'r') as ymlfile:\n        server_yaml_content = yaml.safe_load(ymlfile)\n\n    server_params = [crazyflies] + [server_yaml_content['/crazyflie_server']['ros__parameters']]\n    # robot description\n    urdf = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'urdf',\n        'crazyflie_description.urdf')\n    \n    with open(urdf, 'r') as f:\n        robot_desc = f.read()\n\n    server_params[1]['robot_description'] = robot_desc\n\n    # construct motion_capture_configuration\n    motion_capture_yaml = LaunchConfiguration('motion_capture_yaml_file').perform(context)\n    with open(motion_capture_yaml, 'r') as ymlfile:\n        motion_capture_content = yaml.safe_load(ymlfile)\n\n    motion_capture_params = motion_capture_content['/motion_capture_tracking']['ros__parameters']\n    motion_capture_params['rigid_bodies'] = dict()\n    for key, value in crazyflies['robots'].items():\n        type = crazyflies['robot_types'][value['type']]\n        if value['enabled'] and \\\n            ((fileversion == 1 and type['motion_capture']['enabled']) or \\\n            ((fileversion >= 2 and type['motion_capture']['tracking'] == \"librigidbodytracker\"))):\n            motion_capture_params['rigid_bodies'][key] =  {\n                    'initial_position': value['initial_position'],\n                    'marker': type['motion_capture']['marker'],\n                    'dynamics': type['motion_capture']['dynamics'],\n                }\n\n    # copy relevent settings to server params\n    server_params[1]['poses_qos_deadline'] = motion_capture_params['topics']['poses']['qos']['deadline']\n    \n    return [\n        Node(\n            package='motion_capture_tracking',\n            executable='motion_capture_tracking_node',\n            condition=IfCondition(PythonExpression([\"'\", LaunchConfiguration('backend'), \"' != 'sim' and '\", LaunchConfiguration('mocap'), \"' == 'True'\"])),\n            name='motion_capture_tracking',\n            output='screen',\n            parameters= [motion_capture_params],\n        ),\n        Node(\n            package='crazyflie',\n            executable='crazyflie_server.py',\n            condition=LaunchConfigurationEquals('backend','cflib'),\n            name='crazyflie_server',\n            output='screen',\n            parameters= server_params,\n        ),\n        Node(\n            package='crazyflie',\n            executable='crazyflie_server',\n            condition=LaunchConfigurationEquals('backend','cpp'),\n            name='crazyflie_server',\n            output='screen',\n            parameters= server_params,\n            prefix=PythonExpression(['\"xterm -e gdb -ex run --args\" if ', LaunchConfiguration('debug'), ' else \"\"']),\n        ),\n        Node(\n            package='crazyflie_sim',\n            executable='crazyflie_server',\n            condition=LaunchConfigurationEquals('backend','sim'),\n            name='crazyflie_server',\n            output='screen',\n            emulate_tty=True,\n            parameters= server_params,\n        )]\n\ndef generate_launch_description():\n    default_crazyflies_yaml_path = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'crazyflies.yaml')\n    \n    default_motion_capture_yaml_path = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'motion_capture.yaml')\n\n    default_rviz_config_path = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'config.rviz')\n\n    telop_yaml_path = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'teleop.yaml')\n    \n    return LaunchDescription([\n        DeclareLaunchArgument('crazyflies_yaml_file', \n                              default_value=default_crazyflies_yaml_path),\n        DeclareLaunchArgument('motion_capture_yaml_file', \n                              default_value=default_motion_capture_yaml_path),\n        DeclareLaunchArgument('rviz_config_file', \n                              default_value=default_rviz_config_path),\n        DeclareLaunchArgument('backend', default_value='cpp'),\n        DeclareLaunchArgument('debug', default_value='False'),\n        DeclareLaunchArgument('rviz', default_value='False'),\n        DeclareLaunchArgument('gui', default_value='True'),\n        DeclareLaunchArgument('teleop', default_value='True'),\n        DeclareLaunchArgument('mocap', default_value='True'),\n        DeclareLaunchArgument('teleop_yaml_file', default_value=''),\n        OpaqueFunction(function=parse_yaml),\n        Node(\n            condition=LaunchConfigurationEquals('teleop', 'True'),\n            package='crazyflie',\n            executable='teleop',\n            name='teleop',\n            remappings=[\n                ('emergency', 'all/emergency'),\n                ('arm', 'all/arm'),\n                ('takeoff', 'all/takeoff'),\n                ('land', 'all/land'),\n                # uncomment to manually control (and update teleop.yaml)\n                # ('cmd_vel_legacy', 'cf6/cmd_vel_legacy'),\n                # ('cmd_full_state', 'cf6/cmd_full_state'),\n                # ('notify_setpoints_stop', 'cf6/notify_setpoints_stop'),\n            ],\n            parameters= [PythonExpression([\"'\" + telop_yaml_path +\"' if '\", LaunchConfiguration('teleop_yaml_file'), \"' == '' else '\", LaunchConfiguration('teleop_yaml_file'), \"'\"])],\n        ),\n        Node(\n            condition=LaunchConfigurationEquals('teleop', 'True'),\n            package='joy',\n            executable='joy_node',\n            name='joy_node' # by default id=0\n        ),\n        Node(\n            condition=LaunchConfigurationEquals('rviz', 'True'),\n            package='rviz2',\n            namespace='',\n            executable='rviz2',\n            name='rviz2',\n            arguments=['-d', LaunchConfiguration('rviz_config_file')],\n            parameters=[{\n                \"use_sim_time\": PythonExpression([\"'\", LaunchConfiguration('backend'), \"' == 'sim'\"]),\n            }]\n        ),\n        Node(\n            condition=LaunchConfigurationEquals('gui', 'True'),\n            package='crazyflie',\n            namespace='',\n            executable='gui.py',\n            name='gui',\n            parameters=[{\n                \"use_sim_time\": PythonExpression([\"'\", LaunchConfiguration('backend'), \"' == 'sim'\"]),\n            }]\n        ),\n    ])\n"
  },
  {
    "path": "crazyflie/launch/launch_teleop2.py",
    "content": "import os\nimport yaml\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n    # load crazyflies\n    crazyflies_yaml = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'crazyflies.yaml')\n\n    with open(crazyflies_yaml, 'r') as ymlfile:\n        crazyflies = yaml.safe_load(ymlfile)\n\n    server_params = crazyflies\n\n    # construct motion_capture_configuration\n    motion_capture_yaml = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'motion_capture.yaml')\n\n    with open(motion_capture_yaml, 'r') as ymlfile:\n        motion_capture = yaml.safe_load(ymlfile)\n\n    motion_capture_params = motion_capture[\"/motion_capture_tracking\"][\"ros__parameters\"]\n    motion_capture_params[\"rigid_bodies\"] = dict()\n    for key, value in crazyflies[\"robots\"].items():\n        type = crazyflies[\"robot_types\"][value[\"type\"]]\n        \n        motion_capture_params[\"rigid_bodies\"][key] =  {\n                \"initial_position\": value[\"initial_position\"],\n                \"marker\": type[\"marker\"],\n                \"dynamics\": type[\"dynamics\"],\n            }\n\n    # teleop params\n    teleop_params = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'teleop.yaml')\n    teleop_5_params = os.path.join(\n        get_package_share_directory('crazyflie'),\n        'config',\n        'teleop_5.yaml')\n    \n    return LaunchDescription([\n        Node(\n            package='motion_capture_tracking',\n            executable='motion_capture_tracking_node',\n            name='motion_capture_tracking',\n            output='screen',\n            parameters=[motion_capture_params]\n        ),\n        Node(\n            package='crazyflie',\n            executable='teleop',\n            name='teleop',\n            remappings=[\n                ('takeoff', 'cf231/takeoff'),\n                ('land', 'cf231/land'),\n                ('cmd_vel_legacy', 'cf231/cmd_vel_legacy'),\n                ('cmd_full_state', 'cf231/cmd_full_state'),\n                ('notify_setpoints_stop', 'cf231/notify_setpoints_stop'),\n                ('joy', 'cf231/joy'),\n            ],\n            parameters=[teleop_params]\n        ),\n        Node(\n            package='crazyflie',\n            executable='teleop',\n            name='teleop',\n            remappings=[\n                ('takeoff', 'cf5/takeoff'),\n                ('land', 'cf5/land'),\n                ('cmd_vel_legacy', 'cf5/cmd_vel_legacy'),\n                ('cmd_full_state', 'cf5/cmd_full_state'),\n                ('notify_setpoints_stop', 'cf5/notify_setpoints_stop'),\n                ('joy', 'cf5/joy'),\n            ],\n            parameters=[teleop_5_params]\n        ),\n        Node(\n            package='joy',\n            executable='joy_node',\n            name='joy_node',\n            remappings=[('joy', 'cf231/joy')],\n            output='screen',\n            parameters=[{'device_id':0}] # new joystick\n        ),\n        Node(\n            package='joy',\n            executable='joy_node',\n            name='joy_node',\n            remappings=[('joy', 'cf5/joy')],\n            parameters=[{'device_id':1}] # old\n        ),  \n        Node(\n            package='crazyflie',\n            executable='crazyflie_server',\n            name='crazyflie_server',\n            output='screen',\n            parameters=[server_params]\n        ),\n    ])\n\n"
  },
  {
    "path": "crazyflie/launch/teleop_launch.py",
    "content": "from launch import LaunchDescription\nfrom launch_ros.actions import Node\n\ndef generate_launch_description():\n    return LaunchDescription([\n        Node(\n            package='crazyflie',\n            executable='teleop',\n            name='teleop'\n        ),\n        Node(\n            package='joy',\n            executable='joy_node',\n            name='joy_node'\n        ),\n        Node(\n            package='crazyflie',\n            executable='crazyflie_server',\n            name='crazyflie_server'\n        )\n    ])\n"
  },
  {
    "path": "crazyflie/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>crazyflie</name>\n  <version>1.0.3</version>\n  <description>ROS 2 Package for Bitcraze Crazyflie robots</description>\n  <maintainer email=\"hoenig@tu-berlin.de\">Wolfgang Hönig</maintainer>\n  <maintainer email=\"kimberleymcguire@gmail.com\">Kimberly N. McGuire</maintainer>\n  <license>MIT</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <buildtool_depend>ament_cmake_python</buildtool_depend>\n\n  <depend>rclcpp</depend>\n  <depend>tf2_ros</depend>\n  <depend>std_srvs</depend>\n  <depend>sensor_msgs</depend>\n  <depend>crazyflie_interfaces</depend>\n  <depend>geometry_msgs</depend>\n  <depend>nav_msgs</depend>\n  <depend>motion_capture_tracking_interfaces</depend>\n  <depend>eigen</depend>\n  <depend>boost</depend>\n  <depend>libusb-1.0-dev</depend>\n  <depend>ros_environment</depend>\n\n\n  <exec_depend>tf_transformations</exec_depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n  <test_depend>ament_lint_common</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "crazyflie/scripts/aideck_streamer.py",
    "content": "#!/usr/bin/env python3\nimport socket,os,struct, time\nimport numpy as np\nimport cv2\nimport yaml\nfrom ament_index_python.packages import get_package_share_directory\n\n\nimport rclpy\nfrom rclpy.node import Node\nfrom sensor_msgs.msg import Image, CameraInfo\n\nfrom rcl_interfaces.msg import ParameterDescriptor, ParameterType\n\n\nclass ImageStreamerNode(Node):\n    def __init__(self):\n        super().__init__(\"image_node\")\n\n        # declare config path parameter\n        self.declare_parameter(\n            name=\"config_path\",\n            value=os.path.join(\n                    get_package_share_directory('crazyflie'),\n                    'config',\n                    'aideck_streamer.yaml'\n                )\n        )\n\n        config_path = self.get_parameter(\"config_path\").value\n        with open(config_path) as f:\n            config = yaml.load(f, Loader=yaml.FullLoader)\n\n        # declare topic names\n        self.declare_parameter(\n            name=\"image_topic\",\n            value=config[\"image_topic\"],\n            descriptor=ParameterDescriptor(\n                type=ParameterType.PARAMETER_STRING,\n                description=\"Image topic to publish to.\",\n            ),\n        )\n\n        self.declare_parameter(\n            name=\"camera_info_topic\",\n            value=config[\"camera_info_topic\"],\n            descriptor=ParameterDescriptor(\n                type=ParameterType.PARAMETER_STRING,\n                description=\"Camera info topic to subscribe to.\",\n            ),\n        )\n\n        # declare aideck ip and port\n        self.declare_parameter(\n            name='deck_ip',\n            value=config['deck_ip'],        \n            )\n        \n        self.declare_parameter(\n            name='deck_port',\n            value=config['deck_port'],        \n        )\n\n        # define variables from ros2 parameters\n        image_topic = (\n            self.get_parameter(\"image_topic\").value\n        )\n        self.get_logger().info(f\"Image topic: {image_topic}\")\n\n        info_topic = (\n            self.get_parameter(\"camera_info_topic\").value\n        )\n        self.get_logger().info(f\"Image info topic: {info_topic}\")\n\n\n        # create messages and publishers\n        self.image_msg = Image()\n        self.camera_info_msg = self._construct_from_yaml(config)\n        self.image_publisher = self.create_publisher(Image, image_topic, 10)\n        self.info_publisher = self.create_publisher(CameraInfo, info_topic, 10)\n\n        # set up connection to AI Deck\n        deck_ip = self.get_parameter(\"deck_ip\").value\n        deck_port = int(self.get_parameter(\"deck_port\").value)\n        self.get_logger().info(\"Connecting to socket on {}:{}...\".format(deck_ip, deck_port))\n        self.client_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)\n        self.client_socket.connect((deck_ip, deck_port))\n        self.get_logger().info(\"Socket connected\")\n        self.image = None\n        self.rx_buffer = bytearray()\n\n        # set up timers for callbacks\n        timer_period = 0.01\n        self.rx_timer = self.create_timer(timer_period, self.receive_callback)\n        self.tx_timer = self.create_timer(timer_period, self.publish_callback)\n\n\n    def _construct_from_yaml(self, config):\n        camera_info = CameraInfo()\n\n        camera_info.header.frame_id = config['camera_name']\n        camera_info.header.stamp = self.get_clock().now().to_msg()\n        camera_info.width = int(config['image_width'])\n        camera_info.height = int(config['image_height'])\n        camera_info.distortion_model = config['distortion_model']\n        camera_info.d = config['distortion_coefficients']['data']\n        camera_info.k = config['camera_matrix']['data']\n        camera_info.r = config['rectification_matrix']['data']\n        camera_info.p = config['projection_matrix']['data']\n        return camera_info\n\n    def _rx_bytes(self, size):\n        data = bytearray()\n        while len(data) < size:\n            data.extend(self.client_socket.recv(size-len(data)))\n        return data\n\n    def receive_callback(self):\n        # first get the info\n        packetInfoRaw = self._rx_bytes(4)\n        [length, routing, function] = struct.unpack('<HBB', packetInfoRaw)\n\n        # receive the header\n        imgHeader = self._rx_bytes(length - 2)\n        [magic, width, height, depth, format, size] = struct.unpack('<BHHBBI', imgHeader)\n\n        # if magic is correct, get new image\n        if magic == 0xBC:\n            imgStream = bytearray()\n\n            while len(imgStream) < size:\n                packetInfoRaw = self._rx_bytes(4)\n                [length, dst, src] = struct.unpack('<HBB', packetInfoRaw)\n                #print(\"Chunk size is {} ({:02X}->{:02X})\".format(length, src, dst))\n                chunk = self._rx_bytes(length - 2)\n                imgStream.extend(chunk)\n\n            raw_img = np.frombuffer(imgStream, dtype=np.uint8)\n            raw_img.shape = (width, height)\n            self.image = cv2.cvtColor(raw_img, cv2.COLOR_BayerBG2RGBA)\n\n    def publish_callback(self):\n        if self.image is not None:\n            self.image_msg.header.frame_id = self.camera_info_msg.header.frame_id\n            self.image_msg.header.stamp = self.get_clock().now().to_msg()\n            self.camera_info_msg.header.stamp = self.image_msg.header.stamp\n            width, height, channels = self.image.shape\n            self.image_msg.height = height\n            self.image_msg.width = width\n            self.image_msg.encoding = 'rgba8'\n            self.image_msg.step = width * channels   # number of bytes each row in the array will occupy\n            self.image_msg.is_bigendian = 0 # TODO: implement automatic check depending on system\n            self.image_msg.data = self.image.flatten().data\n\n            self.image_publisher.publish(self.image_msg)\n            self.info_publisher.publish(self.camera_info_msg)\n            self.image = None\n            \n            \n\ndef main(args=None):\n    rclpy.init(args=args)\n    node = ImageStreamerNode()\n    rclpy.spin(node)\n\n    node.destroy_node()\n    rclpy.shutdown()\n\nif __name__ == \"__main__\":\n    main()"
  },
  {
    "path": "crazyflie/scripts/cfmult.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nHelper script to do something to multiple crazyflies on the same channel \nsimultaneously. Specifically, running ``crazyflie`` ROS package scripts\nsuch as *battery*, *reboot*, and *sysoff* for multiple crazyflies instead\nof running them manually for different UID's. \n\nNOTE: this serves a similar pupose to ``chooser.py`` but can be ran from \nthe command line.\n\"\"\"\n\nimport argparse\nfrom pathlib import Path\nimport subprocess\n\nfrom ruamel.yaml import YAML\n\n\nSUBPROC_TIMEOUT = 1\nVALID_SUBCMDS = {\n   \"battery\", \n   \"reboot\", \n   \"sysoff\", \n   \"version\",\n   \"listLogVariables\",\n   \"listParams\", \n   \"listMemories\",\n   \"flash\",\n}\n\n\ndef main():\n    parser = argparse.ArgumentParser(\n        description=\"Wrapper for 'ros2 run crazyflie ...' to multiplex '...' across crazyflies\"\n    )\n    parser.add_argument(\"subcommand\", help=\"Subcommand of crazyflie to be ran\",\n            choices=VALID_SUBCMDS)\n    sub_parser = parser.add_subparsers()\n    man_parser = sub_parser.add_parser(\"manual\", help=\"Manually specify channels and UID's\")\n    man_parser.add_argument(\"-c\", \"--channel\", default=80, \n            help=\"Channel of this Crazyflie(s)\")\n    man_parser.add_argument(\"-u\", \"--uids\", nargs=\"+\", required=True,\n            help=\"Last 1-2 characters of UID's of each of the crazyflies in hex.\")\n    \n    yaml_parser = sub_parser.add_parser(\"yaml\", help=\"Load radio addressed via yaml file\")\n    yaml_parser.add_argument(\"-C\", \"--configpath\",\n\t\tdefault=Path(__file__).parent.parent.resolve() / \"config\",\n\t\thelp=\"Path to the configuration *.yaml files\")\n    \n    parser.add_argument(\"--file_name\", help=\"File name for flashing the crazyflie\",\n            type=str, default=\"\")\n\n    args = parser.parse_args()\n\n    args.subcommand = [args.subcommand]\n    if args.subcommand[0] == \"sysoff\":\n        args.subcommand = [\"reboot\", \"--mode=sysoff\"]\n\n    # Determine which URI's to mess with.\n    if getattr(args, 'configpath', None):\n        uris = _read_yaml_uris(Path(args.configpath).resolve())\n    else:\n        if not all(len(uid) <= 2 for uid in args.uids):\n            raise ValueError(\"UID must be a 1-2 element string\")\n        uris = [f\"radio://0/{args.channel}/2M/E7E7E7E7{uid.zfill(2)}\" for uid in args.uids]\n    \n    # Run for all URI's determined.\n    for uri in uris:\n        if args.subcommand[0] == \"flash\":\n            SUBPROC_TIMEOUT = 20\n            cmd = [\n            \"ros2\", \n            \"run\", \n            \"crazyflie\", \n            \"flash.py\", \n            f\"--uri={uri}\",\n            f\"--file_name={args.file_name}\"\n        ]\n        else:\n            SUBPROC_TIMEOUT = 1\n            cmd = [\n                \"ros2\", \n                \"run\", \n                \"crazyflie\", \n                *args.subcommand, \n                f\"--uri={uri}\",\n            ]\n        print(f\"{' '.join(cmd)}\")\n        subprocess.run(cmd, timeout=SUBPROC_TIMEOUT)\n\n\ndef _read_yaml_uris(configpath):\n    if not configpath.is_dir():\n       raise ValueError(f\"configpath {configpath} input does not exist.\")\n    yamlpath = configpath / \"crazyflies.yaml\"\n    if not yamlpath.is_file():\n        raise FileNotFoundError(f\"{yamlpath} not found in {configpath}.\")\n        \n    yaml = YAML()\n    cfg = yaml.load(yamlpath)\n    \n    return [val['uri'] for val in cfg['robots'].values() if val['enabled']]\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "crazyflie/scripts/chooser.py",
    "content": "#!/usr/bin/env python3\n\nimport argparse\ntry:\n\timport Tkinter\nexcept ImportError:\n\timport tkinter as Tkinter\nfrom ruamel.yaml import YAML\nimport pathlib\nimport os\nimport subprocess\nimport re\nimport time\nimport threading\n\nif __name__ == '__main__':\n\tparser = argparse.ArgumentParser()\n\tparser.add_argument(\n\t\t\"--configpath\",\n\t\ttype=str,\n\t\tdefault=os.path.join(os.path.dirname(os.path.realpath(__file__)), \"../config/crazyflies.yaml\"),\n\t\thelp=\"Path to the configuration .yaml file\")\n\tparser.add_argument(\n\t\t\"--stm32Fw\",\n\t\ttype=str,\n\t\tdefault=os.path.join(os.path.dirname(os.path.realpath(__file__)), \"../../../../crazyflie-firmware/cf2.bin\"),\n\t\thelp=\"Path to cf2.bin\")\n\tparser.add_argument(\n\t\t\"--nrf51Fw\",\n\t\ttype=str,\n\t\tdefault=os.path.join(os.path.dirname(os.path.realpath(__file__)), \"../../../../crazyflie2-nrf-firmware/cf2_nrf.bin\"),\n\t\thelp=\"Path to cf2_nrf.bin\")\n\targs = parser.parse_args()\n\n\tif not os.path.exists(args.configpath):\n\t\tprint(\"ERROR: Could not find yaml configuration file in configpath ({}).\".format(args.configpath))\n\t\texit()\n\n\tif not os.path.exists(args.stm32Fw):\n\t\tprint(\"WARNING: Could not find STM32 firmware ({}).\".format(args.stm32Fw))\n\n\tif not os.path.exists(args.nrf51Fw):\n\t\tprint(\"WARNING: Could not find NRF51 firmware ({}).\".format(args.nrf51Fw))\n\n\tdef selected_cfs():\n\t\tnodes = {name: node for name, node in cfg[\"robots\"].items() if widgets[name].checked.get()}\n\t\treturn nodes\n\n\tdef save():\n\t\tfor name, node in cfg[\"robots\"].items():\n\t\t\tif widgets[name].checked.get():\n\t\t\t\tnode[\"enabled\"] = True\n\t\t\telse:\n\t\t\t\tnode[\"enabled\"] = False\n\t\twith open(args.configpath, 'w') as outfile:\n\t\t\tyaml.dump(cfg, outfile)\n\n\tyaml = YAML()\n\tcfg = yaml.load(pathlib.Path(args.configpath))\n\tcfTypes = cfg[\"robot_types\"]\n\tenabled = [name for name in cfg[\"robots\"].keys() if cfg[\"robots\"][name][\"enabled\"] == True]\n\n\n\t# compute absolute pixel coordinates from the initial positions\n\tpositions = [node[\"initial_position\"] for node in cfg[\"robots\"].values()]\n\tDOWN_DIR = [-1, 0]\n\tRIGHT_DIR = [0, -1]\n\tdef dot(a, b):\n\t\treturn a[0] * b[0] + a[1] * b[1]\n\tpixel_x = [120 * dot(pos, RIGHT_DIR) for pos in positions]\n\tpixel_y = [120 * dot(pos, DOWN_DIR) for pos in positions]\n\txmin, ymin = min(pixel_x), min(pixel_y)\n\txmax, ymax = max(pixel_x), max(pixel_y)\n\n\t# construct the main window\n\ttop = Tkinter.Tk()\n\ttop.title('Crazyflie Chooser')\n\n\t# construct the frame containing the absolute-positioned checkboxes\n\twidth = xmax - xmin + 50 # account for checkbox + text width\n\theight = ymax - ymin + 50 # account for checkbox + text height\n\tframe = Tkinter.Frame(top, width=width, height=height)\n\n\tclass CFWidget(Tkinter.Frame):\n\t\tdef __init__(self, parent, name):\n\t\t\tTkinter.Frame.__init__(self, parent)\n\t\t\tself.checked = Tkinter.BooleanVar()\n\t\t\tcheckbox = Tkinter.Checkbutton(self, variable=self.checked, command=save,\n\t\t\t\tpadx=0, pady=0)\n\t\t\tcheckbox.grid(row=0, column=0, sticky='E')\n\t\t\tnameLabel = Tkinter.Label(self, text=name, padx=0, pady=0)\n\t\t\tnameLabel.grid(row=0, column=1, sticky='W')\n\t\t\tself.batteryLabel = Tkinter.Label(self, text=\"\", fg=\"#999999\", padx=0, pady=0)\n\t\t\tself.batteryLabel.grid(row=1, column=0, columnspan=2, sticky='E')\n\t\t\tself.versionLabel = Tkinter.Label(self, text=\"\", fg=\"#999999\", padx=0, pady=0)\n\t\t\tself.versionLabel.grid(row=2, column=0, columnspan=2, sticky='E')\n\n\t# construct all the checkboxes\n\twidgets = {}\n\tfor (id, node), x, y in zip(cfg[\"robots\"].items(), pixel_x, pixel_y):\n\t\tw = CFWidget(frame, str(id))\n\t\tw.place(x = x - xmin, y = y - ymin)\n\t\tw.checked.set(id in enabled)\n\t\twidgets[id] = w\n\n\t# dragging functionality - TODO alt-drag to deselect\n\tdrag_start = None\n\tdrag_startstate = None\n\n\tdef minmax(a, b):\n\t\treturn min(a, b), max(a, b)\n\n\tdef mouseDown(event):\n\t\tglobal drag_start, drag_startstate\n\t\tdrag_start = (event.x_root, event.y_root)\n\t\tdrag_startstate = [cf.checked.get() for cf in widgets.values()]\n\n\tdef mouseUp(event):\n\t\tsave()\n\n\tdef drag(event, select):\n\t\tx, y = event.x_root, event.y_root\n\t\tdragx0, dragx1 = minmax(drag_start[0], x)\n\t\tdragy0, dragy1 = minmax(drag_start[1], y)\n\n\t\tdef dragcontains(widget):\n\t\t\tx0 = widget.winfo_rootx()\n\t\t\ty0 = widget.winfo_rooty()\n\t\t\tx1 = x0 + widget.winfo_width()\n\t\t\ty1 = y0 + widget.winfo_height()\n\t\t\treturn not (x0 > dragx1 or x1 < dragx0 or y0 > dragy1 or y1 < dragy0)\n\n\t\t# depending on interation over dicts being consistent\n\t\tfor initial, cf in zip(drag_startstate, widgets.values()):\n\t\t\tif dragcontains(cf):\n\t\t\t\tcf.checked.set(select)\n\t\t\telse:\n\t\t\t\tcf.checked.set(initial)\n\n\ttop.bind('<ButtonPress-1>', mouseDown)\n\ttop.bind('<ButtonPress-3>', mouseDown)\n\ttop.bind('<B1-Motion>', lambda event: drag(event, True))\n\ttop.bind('<B3-Motion>', lambda event: drag(event, False))\n\ttop.bind('<ButtonRelease-1>', mouseUp)\n\ttop.bind('<ButtonRelease-3>', mouseUp)\n\n\t# buttons for clearing/filling all checkboxes\n\tdef clear():\n\t\tfor box in widgets.values():\n\t\t\tbox.checked.set(False)\n\t\tsave()\n\n\tdef fill():\n\t\tfor box in widgets.values():\n\t\t\tbox.checked.set(True)\n\t\tsave()\n\n\tdef mkbutton(parent, name, command):\n\t\tbutton = Tkinter.Button(parent, text=name, command=command)\n\t\tbutton.pack(side='left')\n\n\tbuttons = Tkinter.Frame(top)\n\tmkbutton(buttons, \"Clear\", clear)\n\tmkbutton(buttons, \"Fill\", fill)\n\n\t# construct bottom buttons for utility scripts\n\tdef sysOff():\n\t\tnodes = selected_cfs()\n\t\tfor name, crazyflie in nodes.items():\n\t\t\turi = crazyflie[\"uri\"]\n\t\t\tsubprocess.call([\"ros2 run crazyflie reboot --uri \" + uri + \" --mode sysoff\"], shell=True)\n\n\tdef reboot():\n\t\tnodes = selected_cfs()\n\t\tfor name, crazyflie in nodes.items():\n\t\t\turi = crazyflie[\"uri\"]\n\t\t\tprint(name)\n\t\t\tsubprocess.call([\"ros2 run crazyflie reboot --uri \" + uri], shell=True)\n\n\tdef flashSTM():\n\t\tnodes = selected_cfs()\n\t\tfor name, crazyflie in nodes.items():\n\t\t\turi = crazyflie[\"uri\"]\n\t\t\tprint(\"Flash STM32 FW to {}\".format(uri))\n\t\t\tsubprocess.call([\"ros2 run crazyflie flash --uri \" + uri + \" --target stm32 --filename \" + args.stm32Fw], shell=True)\n\n\tdef flashNRF():\n\t\tnodes = selected_cfs()\n\t\tfor name, crazyflie in nodes.items():\n\t\t\turi = crazyflie[\"uri\"]\n\t\t\tprint(\"Flash NRF51 FW to {}\".format(uri))\n\t\t\tsubprocess.call([\"ros2 run crazyflie flash --uri \" + uri + \" --target nrf51 --filename \" + args.nrf51Fw], shell=True)\n\n\tdef checkBattery():\n\t\t# reset color\n\t\tfor id, w in widgets.items():\n\t\t\tw.batteryLabel.config(foreground='#999999')\n\n\t\t# query each CF\n\t\tnodes = selected_cfs()\n\t\tfor name, crazyflie in nodes.items():\n\t\t\turi = crazyflie[\"uri\"]\n\t\t\tcfType = crazyflie[\"type\"]\n\t\t\tbigQuad = cfTypes[cfType][\"big_quad\"]\n\t\t\t\n\t\t\ttry:\n\t\t\t\tif not bigQuad:\n\t\t\t\t\tvoltage = subprocess.check_output([\"ros2 run crazyflie battery --uri \" + uri], shell=True)\n\t\t\t\telse:\n\t\t\t\t\tvoltage = subprocess.check_output([\"ros2 run crazyflie battery --uri \" + uri + \" --external 1\"], shell=True)\n\t\t\texcept subprocess.CalledProcessError:\n\t\t\t\tvoltage = None  # CF not available\n\n\t\t\tcolor = '#000000'\n\t\t\tif voltage is not None:\n\t\t\t\tvoltage = float(voltage)\n\t\t\t\tif voltage < cfTypes[cfType][\"battery\"][\"voltage_warning\"]:\n\t\t\t\t\tcolor = '#FF8800'\n\t\t\t\tif voltage < cfTypes[cfType][\"battery\"][\"voltage_critical\"]:\n\t\t\t\t\tcolor = '#FF0000'\n\t\t\t\twidgetText = \"{:.2f} v\".format(voltage)\n\t\t\telse:\n\t\t\t\twidgetText = \"Err\"\n\n\t\t\twidgets[name].batteryLabel.config(foreground=color, text=widgetText)\n\n\t# def checkVersion():\n\t# \tfor id, w in widgets.items():\n\t# \t\tw.versionLabel.config(foreground='#999999')\n\t# \tproc = subprocess.Popen(\n\t# \t\t['python3', SCRIPTDIR + 'version.py'], stdout=subprocess.PIPE)\n\t# \tversions = dict()\n\t# \tversionsCount = dict()\n\t# \tversionForMost = None\n\t# \tversionForMostCount = 0\n\t# \tfor line in iter(proc.stdout.readline, ''):\n\t# \t\tprint(line)\n\t# \t\tmatch = re.search(\"(\\d+): ([0-9a-fA-F]+),(\\d),([0-9a-fA-F]+)\", line)\n\t# \t\tif match:\n\t# \t\t\taddr = int(match.group(1))\n\t# \t\t\tv1 = match.group(2)\n\t# \t\t\tmodified = int(match.group(3)) == 1\n\t# \t\t\tv2 = match.group(4)\n\t# \t\t\tv = (v1,v2)\n\t# \t\t\tversions[addr] = v\n\t# \t\t\tif v in versionsCount:\n\t# \t\t\t\tversionsCount[v] += 1\n\t# \t\t\telse:\n\t# \t\t\t\tversionsCount[v] = 1\n\t# \t\t\tif versionsCount[v] > versionForMostCount:\n\t# \t\t\t\tversionForMostCount = versionsCount[v]\n\t# \t\t\t\tversionForMost = v\n\t# \tfor addr, v in versions.items():\n\t# \t\tcolor = '#000000'\n\t# \t\tif v != versionForMost:\n\t# \t\t\tcolor = '#FF0000'\n\t# \t\twidgets[addr].versionLabel.config(foreground=color, text=str(v[0])[0:3] + \",\" + str(v[1])[0:3])\n\n\tscriptButtons = Tkinter.Frame(top)\n\tmkbutton(scriptButtons, \"battery\", checkBattery)\n\t# currently not supported\n\t# mkbutton(scriptButtons, \"version\", checkVersion)\n\tmkbutton(scriptButtons, \"sysOff\", sysOff)\n\tmkbutton(scriptButtons, \"reboot\", reboot)\n\t# mkbutton(scriptButtons, \"flash (STM)\", flashSTM)\n\t# mkbutton(scriptButtons, \"flash (NRF)\", flashNRF)\n\n\t# start background threads\n\tdef checkBatteryLoop():\n\t\twhile True:\n\t\t\t# rely on GIL\n\t\t\tcheckBattery()\n\t\t\ttime.sleep(10.0) # seconds\n\t# checkBatteryThread = threading.Thread(target=checkBatteryLoop)\n\t# checkBatteryThread.daemon = True # so it exits when the main thread exit\n\t# checkBatteryThread.start()\n\n\t# place the widgets in the window and start\n\tbuttons.pack()\n\tframe.pack(padx=10, pady=10)\n\tscriptButtons.pack()\n\ttop.mainloop()\n"
  },
  {
    "path": "crazyflie/scripts/crazyflie_server.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nA crazyflie server for communicating with several crazyflies\n    based on the official crazyflie python library from\n    Bitcraze AB\n\n\n    2022 - K. N. McGuire (Bitcraze AB)\n\"\"\"\n\nimport rclpy\nfrom rclpy.node import Node\nfrom rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSHistoryPolicy\nfrom rclpy.duration import Duration\n\nimport time\n\nimport cflib.crtp\nfrom cflib.crazyflie.swarm import CachedCfFactory\nfrom cflib.crazyflie.swarm import Swarm\nfrom cflib.crazyflie.log import LogConfig\nfrom cflib.crazyflie.mem import MemoryElement\nfrom cflib.crazyflie.mem import Poly4D\n\nfrom crazyflie_interfaces.srv import Takeoff, Land, GoTo, RemoveLogging, AddLogging\nfrom crazyflie_interfaces.srv import UploadTrajectory, StartTrajectory, NotifySetpointsStop\nfrom crazyflie_interfaces.srv import Arm\nfrom rcl_interfaces.msg import ParameterDescriptor, SetParametersResult, ParameterType\nfrom crazyflie_interfaces.msg import Position, Status, Hover, LogDataGeneric, FullState, VelocityWorld\nfrom motion_capture_tracking_interfaces.msg import NamedPoseArray\n\nfrom std_srvs.srv import Empty\nfrom std_msgs.msg import String\nfrom geometry_msgs.msg import Twist\nfrom geometry_msgs.msg import PoseStamped, TransformStamped\nfrom sensor_msgs.msg import LaserScan\nfrom nav_msgs.msg import Odometry\n\nimport tf_transformations\nfrom tf2_ros import TransformBroadcaster\n\nfrom functools import partial\nfrom math import degrees, radians, pi, isnan\n\ntype_cf_param_to_ros_param = {\n    \"uint8_t\": ParameterType.PARAMETER_INTEGER,\n    \"uint16_t\": ParameterType.PARAMETER_INTEGER,\n    \"uint32_t\": ParameterType.PARAMETER_INTEGER,\n    \"int8_t\": ParameterType.PARAMETER_INTEGER,\n    \"int16_t\": ParameterType.PARAMETER_INTEGER,\n    \"int32_t\": ParameterType.PARAMETER_INTEGER,\n    \"FP16\": ParameterType.PARAMETER_DOUBLE,\n    \"float\": ParameterType.PARAMETER_DOUBLE,\n    \"double\": ParameterType.PARAMETER_DOUBLE,\n}\n\ntype_cf_param_to_index = {\n    'uint8_t': 0x08,\n    'uint16_t': 0x09,\n    'uint32_t': 0x0A,\n    'uint64_t': 0x0B,\n    'int8_t': 0x00,\n    'int16_t': 0x01,\n    'int32_t': 0x02,\n    'int64_t': 0x03,\n    'FP16': 0x05,\n    'float': 0x06,\n    'double': 0x07\n}\n\n\nclass CrazyflieServer(Node):\n    def __init__(self):\n        super().__init__(\n            \"crazyflie_server\",\n            allow_undeclared_parameters=True,\n            automatically_declare_parameters_from_overrides=True,\n        )\n\n        # Turn ROS parameters into a dictionary\n        self._ros_parameters = self._param_to_dict(self._parameters)\n\n        self.uris = []\n        # for logging, assign a all -> all mapping\n        self.cf_dict = {\n            'all': 'all'\n        }\n        self.uri_dict = {}\n        self.type_dict = {}\n\n        # Assign default topic types, variables and callbacks\n        self.default_log_type = {\"pose\": PoseStamped,\n                                 \"scan\": LaserScan,\n                                 \"odom\": Odometry,\n                                 \"status\": Status}\n        self.default_log_vars = {\"pose\": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z',\n                                          'stabilizer.roll', 'stabilizer.pitch', 'stabilizer.yaw'],\n                                 \"scan\": ['range.front', 'range.left', 'range.back', 'range.right'],\n                                 \"odom\": ['stateEstimate.x', 'stateEstimate.y', 'stateEstimate.z',\n                                          'stabilizer.yaw', 'stabilizer.roll', 'stabilizer.pitch',\n                                          'kalman.statePX', 'kalman.statePY', 'kalman.statePZ',\n                                          'gyro.z', 'gyro.x', 'gyro.y'],\n                                 \"status\": ['supervisor.info', 'pm.vbatMV', 'pm.state',\n                                          'radio.rssi']}\n        self.default_log_fnc = {\"pose\": self._log_pose_data_callback,\n                                \"scan\": self._log_scan_data_callback,\n                                \"odom\": self._log_odom_data_callback,\n                                \"status\": self._log_status_data_callback}\n\n        world_tf_name = \"world\"\n        robot_yaml_version = 0\n\n        try:\n            robot_yaml_version = self._ros_parameters[\"fileversion\"]\n        except KeyError:\n            self.get_logger().info(\"No fileversion found in crazyflies.yaml, assuming version 0\")\n        \n        # Check if the Crazyflie library is initialized\n        robot_data = self._ros_parameters[\"robots\"]\n\n        # Init a transform broadcaster\n        self.tfbr = TransformBroadcaster(self)\n\n        # Create easy lookup tables for uri, name and types\n        for crazyflie in robot_data:\n            if robot_data[crazyflie][\"enabled\"]:\n                type_cf = robot_data[crazyflie][\"type\"]\n                # do not include virtual objects\n                connection = self._ros_parameters['robot_types'][type_cf].get(\n                    \"connection\", \"crazyflie\")\n                if connection == \"crazyflie\":\n                    uri = robot_data[crazyflie][\"uri\"]\n                    self.uris.append(uri)\n                    self.cf_dict[uri] = crazyflie\n                    self.uri_dict[crazyflie] = uri\n                    self.type_dict[uri] = type_cf\n\n        # Setup Swarm class cflib with connection callbacks and open the links\n        factory = CachedCfFactory(rw_cache=\"./cache\")\n        self.swarm = Swarm(self.uris, factory=factory)\n        self.swarm.fully_connected_crazyflie_cnt = 0\n        self.swarm.connected_crazyflie_cnt = 0\n\n        # Check if parameter values needs to be uploaded and put on ROS 2 params\n        self.swarm.query_all_values_on_connect = self._ros_parameters[\"firmware_params\"][\"query_all_values_on_connect\"]\n\n        # Initialize logging, services and parameters for each crazyflie\n        for link_uri in self.uris:\n\n            # Connect callbacks for different connection states of the crazyflie\n            self.swarm._cfs[link_uri].cf.fully_connected.add_callback(\n                self._fully_connected)\n            self.swarm._cfs[link_uri].cf.connected.add_callback(\n                self._connected)\n            self.swarm._cfs[link_uri].cf.disconnected.add_callback(\n                self._disconnected)\n            self.swarm._cfs[link_uri].cf.connection_failed.add_callback(\n                self._connection_failed\n            )\n\n            # link statistics from CFlib\n            self.swarm._cfs[link_uri].status = {}\n            self.swarm._cfs[link_uri].status[\"latency\"] = 0.0\n            self.swarm._cfs[link_uri].cf.link_statistics.latency_updated.add_callback(partial(self._latency_callback, uri=link_uri))\n            self.swarm._cfs[link_uri].status[\"num_rx_unicast\"] = 0.0\n            self.swarm._cfs[link_uri].cf.link_statistics.uplink_rate_updated.add_callback(partial(self._uplink_rate_callback, uri=link_uri))\n            self.swarm._cfs[link_uri].status[\"num_tx_unicast\"] = 0.0\n            self.swarm._cfs[link_uri].cf.link_statistics.downlink_rate_updated.add_callback(partial(self._downlink_rate_callback, uri=link_uri))\n\n            # check if logging is enabled at startup\n            self.swarm._cfs[link_uri].logging = {}\n\n            cf_name = self.cf_dict[link_uri]\n            cf_type = self.type_dict[link_uri]\n\n            logging_enabled = False\n            try:\n                logging_enabled = self._ros_parameters['all'][\"firmware_logging\"][\"enabled\"]\n            except KeyError:\n                pass\n            try:\n                logging_enabled = self._ros_parameters['robot_types'][cf_type][\"firmware_logging\"][\"enabled\"]\n            except KeyError:\n                pass\n            try:\n                logging_enabled = self._ros_parameters['robots'][cf_name][\"firmware_logging\"][\"enabled\"]\n            except KeyError:\n                pass\n\n            self.swarm._cfs[link_uri].logging[\"enabled\"] = logging_enabled\n\n            # check if predefine log blocks can be logged and setup crazyflie logblocks and ROS 2 publishers\n            for default_log_name in self.default_log_type:\n                prefix = default_log_name\n                topic_type = self.default_log_type[default_log_name]\n                list_logvar = self.default_log_vars[default_log_name]\n                self._init_default_logblocks(\n                    prefix, link_uri, list_logvar, logging_enabled, topic_type)\n\n            # Check for any custom_log topics\n            custom_logging_enabled = False\n            custom_log_topics = {}\n\n            try:\n                custom_log_topics = self._ros_parameters['all'][\"firmware_logging\"][\"custom_topics\"]\n                custom_logging_enabled = True\n            except KeyError:\n                pass\n            try:\n                custom_log_topics.update(\n                    self._ros_parameters['robot_types'][cf_type][\"firmware_logging\"][\"custom_topics\"])\n                custom_logging_enabled = True\n            except KeyError:\n                pass\n            try:\n                custom_log_topics.update(\n                    self._ros_parameters['robots'][cf_name][\"firmware_logging\"][\"custom_topics\"])\n                custom_logging_enabled = True\n            except KeyError:\n                pass\n\n            self.swarm._cfs[link_uri].logging[\"custom_log_topics\"] = {}\n            self.swarm._cfs[link_uri].logging[\"custom_log_groups\"] = {}\n            self.swarm._cfs[link_uri].logging[\"custom_log_publisher\"] = {}\n\n            # Setup log blocks for each custom log and ROS 2 publisher topics\n            if custom_logging_enabled:\n                for log_group_name in custom_log_topics:\n                    frequency = custom_log_topics[log_group_name][\"frequency\"]\n                    lg_custom = LogConfig(\n                        name=log_group_name, period_in_ms=1000 / frequency)\n                    for log_name in custom_log_topics[log_group_name][\"vars\"]:\n                        lg_custom.add_variable(log_name)\n                        # Don't know which type this needs to be in until we get the full toc\n                    self.swarm._cfs[link_uri].logging[\"custom_log_publisher\"][log_group_name] = \"empty publisher\"\n                    self.swarm._cfs[link_uri].logging[\"custom_log_groups\"][log_group_name] = {\n                    }\n                    self.swarm._cfs[link_uri].logging[\"custom_log_groups\"][log_group_name][\"log_config\"] = lg_custom\n                    self.swarm._cfs[link_uri].logging[\"custom_log_groups\"][log_group_name][\"vars\"] = custom_log_topics[log_group_name][\"vars\"]\n                    self.swarm._cfs[link_uri].logging[\"custom_log_groups\"][log_group_name][\n                        \"frequency\"] = custom_log_topics[log_group_name][\"frequency\"]\n\n            reference_frame = world_tf_name\n               # if larger then 3, then the reference frame is not set in the yaml file\n            if robot_yaml_version >= 3: \n                try:\n                    reference_frame =self._ros_parameters['all'][\"reference_frame\"]\n                except KeyError:\n                    pass\n                try:\n                    reference_frame =self._ros_parameters['robot_types'][robot_data[cf_name]['type']][\"reference_frame\"]\n                except KeyError:\n                    pass\n                try:\n                    reference_frame =self._ros_parameters['robots'][cf_name][\"reference_frame\"]\n                except KeyError:\n                    pass\n            self.swarm._cfs[link_uri].reference_frame = reference_frame\n\n        # Now all crazyflies are initialized, open links!\n        try:\n            self.time_open_link = self.get_clock().now().nanoseconds * 1e-9\n            self.swarm.open_links()\n        except Exception as e:\n            # Close node if one of the Crazyflies can not be found\n            self.get_logger().info(\"Error!: One or more Crazyflies can not be found. \")\n            self.get_logger().info(\"Check if you got the right URIs, if they are turned on\" +\n                                   \" or if your script have proper access to a Crazyradio PA\")\n            exit()\n    \n    def _init_topics_and_services(self):\n\n        # Create services for the entire swarm and each individual crazyflie\n        for uri in self.cf_dict:\n            if uri == \"all\":\n                continue\n\n            name = self.cf_dict[uri]\n\n            pub = self.create_publisher(String, name + '/robot_description',\n            rclpy.qos.QoSProfile(\n                depth=1,\n                durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL))\n\n            msg = String()\n            msg.data = self._ros_parameters['robot_description'].replace(\"$NAME\", name)\n            pub.publish(msg)\n\n            self.create_service(\n                Empty, name +\n                \"/emergency\", partial(self._emergency_callback, uri=uri)\n            )\n            self.create_service(\n                Arm, name +\n                \"/arm\", partial(self._arm_callback, uri=uri)\n            )\n            self.create_service(\n                Takeoff, name +\n                \"/takeoff\", partial(self._takeoff_callback, uri=uri)\n            )\n            self.create_service(\n                Land, name + \"/land\", partial(self._land_callback, uri=uri)\n            )\n            self.create_service(\n                GoTo, name + \"/go_to\", partial(self._go_to_callback, uri=uri)\n            )\n            self.create_service(\n                StartTrajectory, name +\n                \"/start_trajectory\", partial(\n                    self._start_trajectory_callback, uri=uri)\n            )\n            self.create_service(\n                UploadTrajectory, name +\n                \"/upload_trajectory\", partial(\n                    self._upload_trajectory_callback, uri=uri)\n            )\n            self.create_service(\n                NotifySetpointsStop, name +\n                \"/notify_setpoints_stop\", partial(\n                    self._notify_setpoints_stop_callback, uri=uri)\n            )\n            self.create_subscription(\n                Twist, name +\n                \"/cmd_vel_legacy\", partial(self._cmd_vel_legacy_changed,\n                                           uri=uri), 10\n            )\n            self.create_subscription(\n                Position, name +\n                \"/cmd_position\", partial(self._cmd_position_changed, uri=uri), 10\n            )\n\n            self.create_subscription(\n                VelocityWorld, name +\n                \"/cmd_velocity_world\", partial(self._cmd_velocity_world_changed, uri=uri),  10\n            )\n\n            self.create_subscription(\n                Hover, name +\n                \"/cmd_hover\", partial(self._cmd_hover_changed, uri=uri), 10\n            )\n\n            self.create_subscription(\n                FullState, name +\n                \"/cmd_full_state\", partial(self._cmd_full_state_changed, uri=uri), 10\n            )\n            qos_profile = QoSProfile(reliability =QoSReliabilityPolicy.BEST_EFFORT,\n                history=QoSHistoryPolicy.KEEP_LAST,\n                depth=1,\n                deadline = Duration(seconds=0, nanoseconds=1e9/100.0))\n\n            self.create_subscription(\n                NamedPoseArray, \"/poses\",\n                self._poses_changed, qos_profile\n            )\n\n        self.create_service(Arm, \"all/arm\", self._arm_callback)\n        self.create_service(Takeoff, \"all/takeoff\", self._takeoff_callback)\n        self.create_service(Land, \"all/land\", self._land_callback)\n        self.create_service(GoTo, \"all/go_to\", self._go_to_callback)\n        self.create_service(\n            StartTrajectory, \"all/start_trajectory\", self._start_trajectory_callback)\n\n        # This is the last service to announce and can be used to check if the server is fully available\n        self.create_service(Empty, \"all/emergency\", self._emergency_callback)\n\n    def _init_default_logblocks(self, prefix, link_uri, list_logvar, global_logging_enabled, topic_type):\n        \"\"\"\n        Prepare default logblocks as defined in crazyflies.yaml\n        \"\"\"\n        cf_name = self.cf_dict[link_uri]\n        cf_type = self.type_dict[link_uri]\n\n        logging_enabled = False\n        logging_freq = 10\n        try:\n            logging_freq = self._ros_parameters['all'][\n                \"firmware_logging\"][\"default_topics\"][prefix][\"frequency\"]\n            logging_enabled = True\n        except KeyError:\n            pass\n        try:\n            logging_freq = self._ros_parameters['robot_types'][cf_type][\n                \"firmware_logging\"][\"default_topics\"][prefix][\"frequency\"]\n            logging_enabled = True\n        except KeyError:\n            pass\n        try:\n            logging_freq = self._ros_parameters['robots'][cf_name][\n                \"firmware_logging\"][\"default_topics\"][prefix][\"frequency\"]\n            logging_enabled = True\n        except KeyError:\n            pass\n\n        lg = LogConfig(\n            name=prefix, period_in_ms=1000 / logging_freq)\n        for logvar in list_logvar:\n            if prefix == \"odom\":\n                lg.add_variable(logvar, \"FP16\")\n            else:\n                lg.add_variable(logvar)\n\n        self.swarm._cfs[link_uri].logging[prefix +\n                                          \"_logging_enabled\"] = logging_enabled\n        self.swarm._cfs[link_uri].logging[prefix +\n                                          \"_logging_freq\"] = logging_freq\n        self.swarm._cfs[link_uri].logging[prefix + \"_log_config\"] = lg\n        if logging_enabled and global_logging_enabled:\n            self.swarm._cfs[link_uri].logging[prefix + \"_publisher\"] = self.create_publisher(\n                topic_type, self.cf_dict[link_uri] + \"/\" + prefix, 10)\n        else:\n            self.swarm._cfs[link_uri].logging[prefix + \"_publisher\"] = \"empty\"\n\n    def _param_to_dict(self, param_ros):\n        \"\"\"\n        Turn ROS 2 parameters from the node into a dict\n        \"\"\"\n        tree = {}\n        for item in param_ros:\n            t = tree\n            for part in item.split('.'):\n                if part == item.split('.')[-1]:\n                    t = t.setdefault(part, param_ros[item].value)\n                else:\n                    t = t.setdefault(part, {})\n        return tree\n\n    def _latency_callback(self, latency, uri=\"\"):\n        \"\"\"\n        Called when the latency of the Crazyflie is updated\n        \"\"\"\n        self.swarm._cfs[uri].status[\"latency\"] = latency\n\n    def _uplink_rate_callback(self, uplink_rate, uri=\"\"):\n        \"\"\"\n        Called when the uplink rate of the Crazyflie is updated\n        \"\"\"\n        self.swarm._cfs[uri].status[\"num_rx_unicast\"] = uplink_rate\n\n    def _downlink_rate_callback(self, downlink_rate, uri=\"\"):\n        \"\"\"\n        Called when the uplink rate of the Crazyflie is updated\n        \"\"\"\n        self.swarm._cfs[uri].status[\"num_tx_unicast\"] = downlink_rate\n\n    def _connected(self, link_uri):\n        \"\"\"\n        Called when the toc of the parameters and\n         logs has been received of the Crazyflie\n        \"\"\"\n        self.get_logger().info(f\"[{self.cf_dict[link_uri]}] is connected!\")\n        self.swarm.connected_crazyflie_cnt += 1\n\n        if self.swarm.connected_crazyflie_cnt == len(self.cf_dict) - 1:\n            self.time_all_crazyflie_connected = self.get_clock().now().nanoseconds * 1e-9\n            self.get_logger().info(f\"All Crazyflies are connected! It took {self.time_all_crazyflie_connected - self.time_open_link} seconds\")\n            self._init_topics_and_services()\n            self._init_logging()\n            if not self.swarm.query_all_values_on_connect:\n                self._init_parameters()\n                self.add_on_set_parameters_callback(self._parameters_callback)\n\n        else:\n            return\n\n\n    def _fully_connected(self, link_uri):\n        \"\"\"\n        Called the full log toc and parameter +  values\n          has been received from the Crazyflie\n        \"\"\"\n        self.get_logger().info(f\"[{self.cf_dict[link_uri]}] is fully connected!\")\n\n        self.swarm.fully_connected_crazyflie_cnt += 1\n\n        # use len(self.cf_dict) - 1, since cf_dict contains \"all\" as well\n        if self.swarm.fully_connected_crazyflie_cnt == len(self.cf_dict) - 1:\n            self.time_all_crazyflie_connected = self.get_clock().now().nanoseconds * 1e-9\n            self.get_logger().info(f\"All Crazyflies are fully connected! It took {self.time_all_crazyflie_connected - self.time_open_link} seconds\")\n            if self.swarm.query_all_values_on_connect:\n                self._init_parameters()\n                self.add_on_set_parameters_callback(self._parameters_callback)\n\n        else:\n            return\n\n    def _disconnected(self, link_uri):\n        self.get_logger().info(f\"[{self.cf_dict[link_uri]}] is disconnected!\")\n\n    def _connection_failed(self, link_uri, msg):\n        self.get_logger().info(f\"[{self.cf_dict[link_uri]}] connection Failed\")\n        self.swarm.close_links()\n\n    def _init_logging(self):\n        \"\"\"\n        Sets up all the log blocks for the crazyflie and\n           all the ROS 2 publisher and parameters for logging\n           at startup\n        \"\"\"\n        for link_uri in self.uris:\n            cf_handle = self.swarm._cfs[link_uri]\n            cf = cf_handle.cf\n\n            # Start logging for predefined logging\n            for default_log_name in self.default_log_type:\n                prefix = default_log_name\n                if cf_handle.logging[prefix + \"_logging_enabled\"] and cf_handle.logging[\"enabled\"]:\n                    callback_fnc = self.default_log_fnc[prefix]\n                    self._init_default_logging(prefix, link_uri, callback_fnc)\n\n            # Start logging for costum logging blocks\n            cf_handle.l_toc = cf.log.toc.toc\n            if len(cf_handle.logging[\"custom_log_groups\"]) != 0 and cf_handle.logging[\"enabled\"]:\n\n                for log_group_name, log_group_dict in cf_handle.logging[\"custom_log_groups\"].items():\n                    self.swarm._cfs[link_uri].logging[\"custom_log_publisher\"][log_group_name] = self.create_publisher(\n                        LogDataGeneric, self.cf_dict[link_uri] + \"/\" + log_group_name, 10)\n                    lg_custom = log_group_dict['log_config']\n                    try:\n                        cf.log.add_config(lg_custom)\n                        lg_custom.data_received_cb.add_callback(\n                            partial(self._log_custom_data_callback, uri=link_uri))\n                        lg_custom.error_cb.add_callback(\n                            self._log_error_callback)\n                        lg_custom.start()\n                    except KeyError as e:\n                        self.get_logger().info(f'[{self.cf_dict[link_uri]}] Could not start log configuration,'\n                                               '{} not found in TOC'.format(str(e)))\n                    except AttributeError:\n                        self.get_logger().info(\n                            f'[{self.cf_dict[link_uri]}] Could not add log config, bad configuration.')\n\n                self.get_logger().info(f\"[{self.cf_dict[link_uri]}] setup custom logging\")\n\n            self.create_service(\n                RemoveLogging, self.cf_dict[link_uri] + \"/remove_logging\", partial(self._remove_logging, uri=link_uri))\n            self.create_service(\n                AddLogging, self.cf_dict[link_uri] + \"/add_logging\", partial(self._add_logging, uri=link_uri))\n\n        self.get_logger().info(\"All Crazyflies logging are initialized.\")\n\n    def _init_default_logging(self, prefix, link_uri, callback_fnc):\n        \"\"\"\n        Sets up all the default log blocks and ROS 2 publishers for the crazyflie\n        \"\"\"\n        cf_handle = self.swarm._cfs[link_uri]\n        cf = cf_handle.cf\n        lg = cf_handle.logging[prefix + \"_log_config\"]\n        try:\n            cf.log.add_config(lg)\n            lg.data_received_cb.add_callback(\n                partial(callback_fnc, uri=link_uri))\n            lg.error_cb.add_callback(self._log_error_callback)\n            lg.start()\n            frequency = cf_handle.logging[prefix + \"_logging_freq\"]\n            self.declare_parameter(\n                self.cf_dict[link_uri] + \".logs.\" + prefix + \".frequency.\", frequency)\n            self.get_logger().info(\n                f\"[{self.cf_dict[link_uri]}] setup logging for {prefix} at freq {frequency}\")\n        except KeyError as e:\n            self.get_logger().error(f'[{self.cf_dict[link_uri]}] Could not start log configuration,'\n                                   '{} not found in TOC'.format(str(e)))\n        except AttributeError:\n            self.get_logger().error(\n                f'[{self.cf_dict[link_uri]}] Could not add log config, bad configuration.')\n\n    def _log_scan_data_callback(self, timestamp, data, logconf, uri):\n        \"\"\"\n        Once multiranger range is retrieved from the Crazyflie,\n            send out the ROS 2 topic for Scan\n        \"\"\"\n        cf_name = self.cf_dict[uri]\n        max_range = 3.49\n        front_range = float(data.get('range.front'))/1000.0\n        left_range = float(data.get('range.left'))/1000.0\n        back_range = float(data.get('range.back'))/1000.0\n        right_range = float(data.get('range.right'))/1000.0\n        if front_range > max_range:\n            front_range = float(\"inf\")\n        if left_range > max_range:\n            left_range = float(\"inf\")\n        if right_range > max_range:\n            right_range = float(\"inf\")\n        if back_range > max_range:\n            back_range = float(\"inf\")\n        self.ranges = [back_range, right_range, front_range, left_range]\n\n        msg = LaserScan()\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.header.frame_id = cf_name\n        msg.range_min = 0.01\n        msg.range_max = 3.49\n        msg.ranges = self.ranges\n        msg.angle_min = -0.5 * 2 * pi\n        msg.angle_max = 0.25 * 2 * pi\n        msg.angle_increment = 1.0 * pi/2\n        try:\n            self.swarm._cfs[uri].logging[\"scan_publisher\"].publish(msg)\n        except:\n            self.get_logger().info(\"Could not publish scan message, stopping scan log\")\n            self.swarm._cfs[uri].logging[\"scan_log_config\"].stop()\n\n    def _log_pose_data_callback(self, timestamp, data, logconf, uri):\n        \"\"\"\n        Once pose data is retrieved from the Crazyflie,\n            send out the ROS 2 topic for Pose\n        \"\"\"\n\n        cf_name = self.cf_dict[uri]\n\n        x = data.get('stateEstimate.x')\n        y = data.get('stateEstimate.y')\n        z = data.get('stateEstimate.z')\n        roll = radians(data.get('stabilizer.roll'))\n        pitch = radians(-1.0 * data.get('stabilizer.pitch'))\n        yaw = radians(data.get('stabilizer.yaw'))\n        q = tf_transformations.quaternion_from_euler(roll, pitch, yaw)\n\n        msg = PoseStamped()\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.header.frame_id = self.swarm._cfs[uri].reference_frame\n        msg.pose.position.x = x\n        msg.pose.position.y = y\n        msg.pose.position.z = z\n        msg.pose.orientation.x = q[0]\n        msg.pose.orientation.y = q[1]\n        msg.pose.orientation.z = q[2]\n        msg.pose.orientation.w = q[3]\n        try:\n            self.swarm._cfs[uri].logging[\"pose_publisher\"].publish(msg)\n        except:\n            self.get_logger().info(\"Could not publish pose message, stopping pose log\")\n            self.swarm._cfs[uri].logging[\"pose_log_config\"].stop()\n\n        t_base = TransformStamped()\n        t_base.header.stamp = self.get_clock().now().to_msg()\n        t_base.header.frame_id = self.swarm._cfs[uri].reference_frame\n        t_base.child_frame_id = cf_name\n        t_base.transform.translation.x = x\n        t_base.transform.translation.y = y\n        t_base.transform.translation.z = z\n        t_base.transform.rotation.x = q[0]\n        t_base.transform.rotation.y = q[1]\n        t_base.transform.rotation.z = q[2]\n        t_base.transform.rotation.w = q[3]\n        try:\n            self.tfbr.sendTransform(t_base)\n        except:\n            self.get_logger().info(\"Could not publish pose tf\")\n\n    def _log_odom_data_callback(self, timestamp, data, logconf, uri):\n        \"\"\"\n        Once pose and velocity data is retrieved from the Crazyflie,\n            send out the ROS 2 topic for Odometry in 2D (no z-axis)\n        \"\"\"\n        cf_name = self.cf_dict[uri]\n\n        x = data.get('stateEstimate.x')\n        y = data.get('stateEstimate.y')\n        z = data.get('stateEstimate.z')\n        yaw = radians(data.get('stabilizer.yaw'))\n        roll = radians(data.get('stabilizer.roll'))\n        pitch = radians(data.get('stabilizer.pitch'))\n        vx = data.get('kalman.statePX')\n        vy = data.get('kalman.statePY')\n        vz = data.get('kalman.statePZ')\n        yawrate = data.get('gyro.z')\n        rollrate = data.get('gyro.x')\n        pitchrate = data.get('gyro.y')\n\n        q = tf_transformations.quaternion_from_euler(roll, pitch, yaw)\n        msg = Odometry()\n        msg.child_frame_id = cf_name\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.header.frame_id = self.swarm._cfs[uri].reference_frame\n        msg.pose.pose.position.x = x\n        msg.pose.pose.position.y = y\n        msg.pose.pose.position.z = z\n        msg.pose.pose.orientation.x = q[0]\n        msg.pose.pose.orientation.y = q[1]\n        msg.pose.pose.orientation.z = q[2]\n        msg.pose.pose.orientation.w = q[3]\n        msg.twist.twist.linear.x = vx\n        msg.twist.twist.linear.y = vy\n        msg.twist.twist.linear.z = vz\n        msg.twist.twist.angular.z = yawrate\n        msg.twist.twist.angular.y = pitchrate\n        msg.twist.twist.angular.x = rollrate\n\n        try:\n            self.swarm._cfs[uri].logging[\"odom_publisher\"].publish(msg)\n        except:\n            self.get_logger().info(\"Could not publish odom message, stopping odom log\")\n            self.swarm._cfs[uri].logging[\"odom_log_config\"].stop()\n\n        t_base = TransformStamped()\n        t_base.header.stamp = self.get_clock().now().to_msg()\n        t_base.header.frame_id = self.swarm._cfs[uri].reference_frame\n        t_base.child_frame_id = cf_name\n        t_base.transform.translation.x = x\n        t_base.transform.translation.y = y\n        t_base.transform.translation.z = z\n        t_base.transform.rotation.x = q[0]\n        t_base.transform.rotation.y = q[1]\n        t_base.transform.rotation.z = q[2]\n        t_base.transform.rotation.w = q[3]\n\n        try:\n            self.tfbr.sendTransform(t_base)\n        except:\n            self.get_logger().info(\"Could not publish odom tf\")\n\n    def _log_status_data_callback(self, timestamp, data, logconf, uri):\n        \"\"\"\n        Send out the ROS 2 status topic\n        \"\"\"\n\n        msg = Status()\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.header.frame_id = self.swarm._cfs[uri].reference_frame\n\n        # From logging statistics\n        msg.supervisor_info = data.get('supervisor.info')\n        msg.battery_voltage = data.get('pm.vbatMV') / 1000.0\n        msg.pm_state = data.get('pm.state')\n        msg.rssi = data.get('radio.rssi')\n\n        # From link statistics class\n        msg.latency_unicast  = int(self.swarm._cfs[uri].status[\"latency\"])\n        msg.num_rx_unicast = int(self.swarm._cfs[uri].status[\"num_rx_unicast\"])\n        msg.num_tx_unicast = int(self.swarm._cfs[uri].status[\"num_tx_unicast\"])\n\n        try:\n            self.swarm._cfs[uri].logging[\"status_publisher\"].publish(msg)\n        except:\n            self.get_logger().info(\"Could not publish status message, stopping status log\")\n            self.swarm._cfs[uri].logging[\"status_log_config\"].stop()\n\n    def _log_custom_data_callback(self, timestamp, data, logconf, uri):\n        \"\"\"\n        Once custom log block is retrieved from the Crazyflie,\n            send out the ROS 2 topic for that same type of log\n        \"\"\"\n        msg = LogDataGeneric()\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.timestamp = timestamp\n        for log_name in data:\n            msg.values.append(data.get(log_name))\n\n        try:\n            self.swarm._cfs[uri].logging[\"custom_log_publisher\"][logconf.name].publish(\n            msg)\n        except:\n            self.get_logger().info(\"Could not publish custom {logconf.name} message, stopping custom log\")\n            self.swarm._cfs[uri].logging[\"custom_log_groups\"][logconf.name][\"log_config\"].stop()\n\n    def _log_error_callback(self, logconf, msg):\n        print('Error when logging %s: %s' % (logconf.name, msg))\n\n    def _init_parameters(self):\n        \"\"\"\n        Once custom log block is retrieved from the Crazyflie,\n            send out the ROS 2 topic for that same type of log\n        \"\"\"\n        set_param_to_ROS = self.swarm.query_all_values_on_connect\n        for link_uri in self.uris:\n            cf = self.swarm._cfs[link_uri].cf\n\n            p_toc = cf.param.toc.toc\n\n            for group in sorted(p_toc.keys()):\n                for param in sorted(p_toc[group].keys()):\n                    name = group + \".\" + param\n\n                    # Check the parameter type\n                    elem = p_toc[group][param]\n                    type_cf_param = elem.ctype\n                    parameter_descriptor = ParameterDescriptor(\n                        type=type_cf_param_to_ros_param[type_cf_param])\n\n                    # Check ros parameters if an parameter should be set\n                    #   Parameter sets for individual robots has priority,\n                    #   then robot types, then all (all robots)\n                    param_value = None\n                    try:\n                        param_value = self._ros_parameters[\"all\"][\"firmware_params\"][group][param]\n                    except KeyError:\n                        pass\n                    try:\n                        param_value = self._ros_parameters[\"robot_types\"][self.cf_dict[link_uri]\n                                                                              ][\"firmware_params\"][group][param]\n                    except KeyError:\n                        pass\n                    try:\n                        param_value = self._ros_parameters[\"robots\"][self.cf_dict[link_uri]\n                                                                         ][\"firmware_params\"][group][param]\n                    except KeyError:\n                        pass\n\n                    if param_value is not None:\n                        # If value is found in initial parameters,\n                        # set crazyflie firmware value and declare value in ROS 2 parameter\n                        # Note: currently this is not possible to get the most recent from the\n                        #       crazyflie with get_value due to threading.\n                        cf.param.set_value_raw(name, type_cf_param_to_index[type_cf_param], param_value)\n                        self.get_logger().info(\n                            f\"[{self.cf_dict[link_uri]}] {name} is set to {param_value}\"\n                        )\n                        if set_param_to_ROS:\n                            self.declare_parameter(\n                                self.cf_dict[link_uri] +\n                                \".params.\" + group + \".\" + param,\n                                value=param_value,\n                                descriptor=parameter_descriptor,\n                            )\n\n                    else:\n                        # If value is not found in initial parameter set\n                        # get crazyflie paramter value and declare that value in ROS 2 parameter\n                        # Only do this if this has been indicated by the user\n                        if set_param_to_ROS is True:\n\n                            if type_cf_param_to_ros_param[type_cf_param] is ParameterType.PARAMETER_INTEGER:\n                                cf_param_value = int(cf.param.get_value(name))\n                            elif type_cf_param_to_ros_param[type_cf_param] is ParameterType.PARAMETER_DOUBLE:\n                                cf_param_value = float(cf.param.get_value(name))\n\n                            self.declare_parameter(\n                                self.cf_dict[link_uri] +\n                                \".params.\" + group + \".\" + param,\n                                value=cf_param_value,\n                                descriptor=parameter_descriptor,\n                                )\n                            # Based on the parameters from the last Crazyflie, set params for all\n                            # Warning: if any of the other crazyflies have different parameters\n                            #                this will result in an error\n                            try:\n                                self.declare_parameter(\n                                    \"all.params.\" + group + \".\" + param,\n                                    value=cf_param_value,\n                                    descriptor=parameter_descriptor,\n                                    )\n                            except Exception as e:\n                                continue\n\n\n        self.get_logger().info(\"All Crazyflies parameters are initialized.\")\n\n    def _parameters_callback(self, params):\n        \"\"\"\n        Sets up all the parameters for the crazyflie and\n           translates it to ROS 2 paraemeters at startup\n        \"\"\"\n        for param in params:\n            param_split = param.name.split(\".\")\n\n            if param_split[0] == \"all\":\n                if param_split[1] == \"params\":\n                    name_param = param_split[2] + \".\" + param_split[3]\n                    try:\n                        for link_uri in self.uris:\n                            cf = self.swarm._cfs[link_uri].cf.param.set_value(\n                                name_param, param.value\n                            )\n                        self.get_logger().info(\n                            f\"[{self.cf_dict[link_uri]}] {name_param} is set to {param.value}\"\n                        )\n                        return SetParametersResult(successful=True)\n                    except Exception as e:\n                        self.get_logger().info(str(e))\n                        return SetParametersResult(successful=False)\n            elif param_split[0] in self.cf_dict.values():\n                cf_name = param_split[0]\n                if param_split[1] == \"params\":\n                    name_param = param_split[2] + \".\" + param_split[3]\n                    try:\n                        self.swarm._cfs[self.uri_dict[cf_name]].cf.param.set_value(\n                            name_param, param.value\n                        )\n                        self.get_logger().info(\n                            f\"[{self.uri_dict[cf_name]}] {name_param} is set to {param.value}\"\n                        )\n                        return SetParametersResult(successful=True)\n                    except Exception as e:\n                        self.get_logger().info(str(e))\n                        return SetParametersResult(successful=False)\n                if param_split[1] == \"logs\":\n                    return SetParametersResult(successful=True)\n\n\n        return SetParametersResult(successful=False)\n\n    def _emergency_callback(self, request, response, uri=\"all\"):\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.loc.send_emergency_stop()\n        else:\n            self.swarm._cfs[uri].cf.loc.send_emergency_stop()\n\n        return response\n\n    def _arm_callback(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to arm or disarm the Crazyflie\n        \"\"\"\n\n        arm_bool = request.arm\n\n        self.get_logger().info(\n            f\"[{self.cf_dict[uri]}] Arm request is {arm_bool} \"\n        )\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.platform.send_arming_request(\n                    arm_bool\n                )\n        else:\n            self.swarm._cfs[uri].cf.platform.send_arming_request(\n                    arm_bool\n                )\n\n        return response\n\n    def _takeoff_callback(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to take the crazyflie land to\n            a certain height in high level commander\n        \"\"\"\n\n\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n        self.get_logger().info(\n            f\"[{self.cf_dict[uri]}] takeoff(height={request.height} m,\"\n            + f\"duration={duration} s,\"\n            + f\"group_mask={request.group_mask})\"\n        )\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.high_level_commander.takeoff(\n                    request.height, duration\n                )\n        else:\n            self.swarm._cfs[uri].cf.high_level_commander.takeoff(\n                request.height, duration\n            )\n\n        return response\n\n    def _land_callback(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to make the crazyflie land to\n            a certain height in high level commander\n        \"\"\"\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n        self.get_logger().info(\n            f\"[{self.cf_dict[uri]}] land(height={request.height} m,\"\n            + f\"duration={duration} s,\"\n            + f\"group_mask={request.group_mask})\"\n        )\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.high_level_commander.land(\n                    request.height, duration, group_mask=request.group_mask\n                )\n        else:\n            self.swarm._cfs[uri].cf.high_level_commander.land(\n                request.height, duration, group_mask=request.group_mask\n            )\n\n        return response\n\n    def _go_to_callback(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to have the crazyflie go to\n            a certain position in high level commander\n        \"\"\"\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n\n        self.get_logger().info(\n            \"[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)\"\n            % (\n                self.cf_dict[uri],\n                request.goal.x,\n                request.goal.y,\n                request.goal.z,\n                request.yaw,\n                duration,\n                request.relative,\n                request.group_mask,\n            )\n        )\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.high_level_commander.go_to(\n                    request.goal.x,\n                    request.goal.y,\n                    request.goal.z,\n                    request.yaw,\n                    duration,\n                    relative=request.relative,\n                    group_mask=request.group_mask,\n                )\n        else:\n            self.swarm._cfs[uri].cf.high_level_commander.go_to(\n                request.goal.x,\n                request.goal.y,\n                request.goal.z,\n                request.yaw,\n                duration,\n                relative=request.relative,\n                group_mask=request.group_mask,\n            )\n        return response\n\n    def _notify_setpoints_stop_callback(self, request, response, uri=\"all\"):\n\n        self.get_logger().info(f\"[{self.cf_dict[uri]}] Received notify setpoint stop\")\n\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.commander.send_notify_setpoint_stop()\n        else:\n            self.swarm._cfs[uri].cf.commander.send_notify_setpoint_stop()\n\n        return response\n\n    def _upload_trajectory_callback(self, request, response, uri=\"all\"):\n\n        id = request.trajectory_id\n        offset = request.piece_offset\n        lenght = len(request.pieces)\n        total_duration = 0\n        self.get_logger().info(\"[%s] upload_trajectory(id=%d,offset=%d, lenght=%d)\" % (\n            self.cf_dict[uri],\n            id,\n            offset,\n            lenght,\n        ))\n\n        trajectory = []\n        for i in range(lenght):\n            piece = request.pieces[i]\n            px = Poly4D.Poly(piece.poly_x)\n            py = Poly4D.Poly(piece.poly_y)\n            pz = Poly4D.Poly(piece.poly_z)\n            pyaw = Poly4D.Poly(piece.poly_yaw)\n            duration = float(piece.duration.sec) + \\\n                float(piece.duration.nanosec)/1e9\n            trajectory.append(Poly4D(duration, px, py, pz, pyaw))\n            total_duration = total_duration + duration\n\n        if uri == \"all\":\n            upload_success_all = True\n            for link_uri in self.uris:\n                trajectory_mem = self.swarm._cfs[link_uri].cf.mem.get_mems(\n                    MemoryElement.TYPE_TRAJ)[0]\n                trajectory_mem.trajectory = trajectory\n                upload_result = trajectory_mem.write_data_sync()\n                if not upload_result:\n                    self.get_logger().info(f\"[{self.cf_dict[uri]}] Upload failed\")\n                    upload_success_all = False\n                else:\n                    self.swarm._cfs[link_uri].cf.high_level_commander.define_trajectory(\n                        id, offset, len(trajectory))\n            if upload_success_all is False:\n                response.success = False\n                return response\n        else:\n            trajectory_mem = self.swarm._cfs[uri].cf.mem.get_mems(\n                MemoryElement.TYPE_TRAJ)[0]\n            trajectory_mem.trajectory = trajectory\n            upload_result = trajectory_mem.write_data_sync()\n            if not upload_result:\n                self.get_logger().info(f\"[{self.cf_dict[uri]}] Upload failed\")\n                response.success = False\n                return response\n            self.swarm._cfs[uri].cf.high_level_commander.define_trajectory(\n                id, offset, len(trajectory))\n\n        return response\n\n    def _start_trajectory_callback(self, request, response, uri=\"all\"):\n\n        id = request.trajectory_id\n        ts = request.timescale\n        rel = request.relative\n        rev = request.reversed\n        gm = request.group_mask\n\n        self.get_logger().info(\"[%s] start_trajectory(id=%d,timescale=%f,relative=%d, reversed=%d, group_mask=%d)\" % (\n            self.cf_dict[uri],\n            id,\n            ts,\n            rel,\n            rev,\n            gm\n        ))\n        if uri == \"all\":\n            for link_uri in self.uris:\n                self.swarm._cfs[link_uri].cf.high_level_commander.start_trajectory(\n                    id, ts, rel, rev, gm)\n        else:\n            self.swarm._cfs[uri].cf.high_level_commander.start_trajectory(\n                id, ts, rel, rev, gm)\n\n        return response\n\n    def _poses_changed(self, msg):\n        \"\"\"\n        Topic update callback to the motion capture lib's\n           poses topic to send through the external position\n           to the crazyflie\n        \"\"\"\n\n        poses = msg.poses\n        for pose in poses:\n            name = pose.name\n            x = pose.pose.position.x\n            y = pose.pose.position.y\n            z = pose.pose.position.z\n            quat = pose.pose.orientation\n\n            if name in self.uri_dict.keys():\n                uri = self.uri_dict[name]\n                # self.get_logger().info(f\"{uri}: send extpos {x}, {y}, {z} to {name}\")\n                if isnan(quat.x):\n                    self.swarm._cfs[uri].cf.extpos.send_extpos(\n                        x, y, z)\n                else:\n                    self.swarm._cfs[uri].cf.extpos.send_extpose(\n                        x, y, z, quat.x, quat.y, quat.z, quat.w)\n\n    def _cmd_vel_legacy_changed(self, msg, uri=\"\"):\n        \"\"\"\n        Topic update callback to control the attitude and thrust\n            of the crazyflie with teleop\n        \"\"\"\n        if not hasattr(self.swarm._cfs[uri], 'legacy_initialized'):\n            self.swarm._cfs[uri].cf.commander.send_setpoint(0.0, 0.0, 0.0, 0)\n            time.sleep(0.01)\n            self.swarm._cfs[uri].legacy_initialized = True\n\n        roll = msg.linear.y\n        pitch = -msg.linear.x\n        yawrate = msg.angular.z\n        thrust = int(min(max(msg.linear.z, 0), 60000))\n        self.swarm._cfs[uri].cf.commander.send_setpoint(\n            roll, pitch, yawrate, thrust)\n\n    def _cmd_position_changed(self, msg, uri=\"\"):\n        \"\"\"\n        Topic update callback to control the position command\n            of the crazyflie \n        \"\"\"\n        x = msg.x\n        y = msg.y\n        z = msg.z\n        yaw = msg.yaw\n        self.swarm._cfs[uri].cf.commander.send_position_setpoint(\n            x, y, z, yaw)\n        \n    def _cmd_velocity_world_changed(self, msg, uri=\"\"):\n        \"\"\"\n        Topic update callback to control the world velocity command\n            of the crazyflie\n        \"\"\"\n        vel = msg.vel\n        vx = vel.x\n        vy = vel.y\n        vz = vel.z\n        yaw_rate = msg.yaw_rate\n        self.swarm._cfs[uri].cf.commander.send_velocity_world_setpoint(\n            vx, vy, vz, yaw_rate)\n\n    def _cmd_hover_changed(self, msg, uri=\"\"):\n        \"\"\"\n        Topic update callback to control the hover command\n            of the crazyflie from the velocity multiplexer (vel_mux)\n        \"\"\"\n        vx = msg.vx\n        vy = msg.vy\n        z = msg.z_distance\n        yawrate = -1.0*degrees(msg.yaw_rate)\n        self.swarm._cfs[uri].cf.commander.send_hover_setpoint(\n            vx, vy, yawrate, z)\n\n    def _cmd_full_state_changed(self, msg, uri=\"\"):\n        \"\"\"\n        Topic update callback to full state cmd topic\n        \"\"\"\n        pos = [msg.pose.position.x, msg.pose.position.y, msg.pose.position.z]\n        vel = [msg.twist.linear.x, msg.twist.linear.y, msg.twist.linear.z]\n        acc = [msg.acc.x, msg.acc.y, msg.acc.z]\n        q = [msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z, msg.pose.orientation.w]\n        roll_rate = msg.twist.angular.x\n        pitch_rate =  msg.twist.angular.y\n        yaw_rate = msg.twist.angular.z\n        self.swarm._cfs[uri].cf.commander.send_full_state_setpoint(pos, vel, acc, q, roll_rate, pitch_rate, yaw_rate)\n\n    def _remove_logging(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to remove logging blocks of the crazyflie\n        \"\"\"\n        topic_name = request.topic_name\n        if topic_name in self.default_log_type.keys():\n            try:\n                self.undeclare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".frequency.\")\n                self.swarm._cfs[uri].logging[topic_name + \"_log_config\"].stop()\n                self.destroy_publisher(\n                    self.swarm._cfs[uri].logging[topic_name + \"_publisher\"])\n                self.get_logger().info(f\"[{self.cf_dict[uri]}] Remove {topic_name} logging\")\n            except rclpy.exceptions.ParameterNotDeclaredException:\n                self.get_logger().info(\n                    f\"[{self.cf_dict[uri]}] No logblock of {topic_name} has been found \")\n                response.success = False\n                return response\n        else:\n            try:\n                self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name][\"log_config\"].stop(\n                )\n                for log_name in self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name][\"vars\"]:\n                    self.destroy_publisher(\n                        self.swarm._cfs[uri].logging[\"custom_log_publisher\"][topic_name])\n                self.get_logger().info(f\"[{self.cf_dict[uri]}] Remove {topic_name} logging\")\n            except rclpy.exceptions.ParameterNotDeclaredException:\n                self.get_logger().info(\n                    f\"[{self.cf_dict[uri]}] No logblock of {topic_name} has been found \")\n                response.success = False\n                return response\n\n        response.success = True\n        return response\n\n    def _add_logging(self, request, response, uri=\"all\"):\n        \"\"\"\n        Service callback to add logging blocks of the crazyflie\n        \"\"\"\n        topic_name = request.topic_name\n        frequency = request.frequency\n        variables = request.vars\n        if topic_name in self.default_log_type.keys():\n            try:\n                self.declare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".frequency.\", frequency)\n                self.swarm._cfs[uri].logging[topic_name + \"_publisher\"] = self.create_publisher(\n                    self.default_log_type[topic_name], self.cf_dict[uri] + \"/\" + topic_name, 10)\n                self.swarm._cfs[uri].logging[topic_name +\n                                             \"_log_config\"].period_in_ms = 1000 / frequency\n                self.swarm._cfs[uri].logging[topic_name +\n                                             \"_log_config\"].start()\n                self.get_logger().info(f\"[{self.cf_dict[uri]}] Add {topic_name} logging\")\n            except rclpy.exceptions.ParameterAlreadyDeclaredException:\n                self.get_logger().info(\n                    f\"[{self.cf_dict[uri]}] The content the logging of {topic_name} has already started \")\n                response.success = False\n                return response\n        else:\n            try:\n                self.declare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".frequency.\", frequency)\n                self.declare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".vars.\", variables)\n                lg_custom = LogConfig(\n                    name=topic_name, period_in_ms=1000 / frequency)\n                for log_name in variables:\n                    lg_custom.add_variable(log_name)\n                self.swarm._cfs[uri].logging[\"custom_log_publisher\"][topic_name] = self.create_publisher(\n                    LogDataGeneric, self.cf_dict[uri] + \"/\" + topic_name, 10)\n\n                self.swarm._cfs[uri].cf.log.add_config(lg_custom)\n\n                lg_custom.data_received_cb.add_callback(\n                    partial(self._log_custom_data_callback, uri=uri))\n                lg_custom.error_cb.add_callback(self._log_error_callback)\n                lg_custom.start()\n\n                self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name] = {}\n                self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name][\"log_config\"] = lg_custom\n                self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name][\"vars\"] = variables\n                self.swarm._cfs[uri].logging[\"custom_log_groups\"][topic_name][\"frequency\"] = frequency\n\n                self.get_logger().info(f\"[{self.cf_dict[uri]}] Add {topic_name} logging\")\n            except KeyError as e:\n                self.get_logger().error(\n                    f\"[{self.cf_dict[uri]}] Failed to add {topic_name} logging\")\n                self.get_logger().error(str(e) + \"is not in TOC\")\n                self.undeclare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".frequency.\")\n                self.undeclare_parameter(\n                    self.cf_dict[uri] + \".logs.\" + topic_name + \".vars.\")\n                response.success = False\n                return response\n            except rclpy.exceptions.ParameterAlreadyDeclaredException:\n                self.get_logger().error(\n                    f\"[{self.cf_dict[uri]}] The content or part of the logging of {topic_name} has already started \")\n                response.success = False\n                return response\n\n        response.success = True\n        return response\n\n\ndef main(args=None):\n\n    cflib.crtp.init_drivers()\n    rclpy.init(args=args)\n    crazyflie_server = CrazyflieServer()\n\n    rclpy.spin(crazyflie_server)\n\n    crazyflie_server.destroy_node()\n    rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "crazyflie/scripts/flash.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nA flash utility script to flash crazyflies with the latest or custom firmware\n\n    2024 - K. N. McGuire (Bitcraze AB)\n\"\"\"\n\nimport rclpy\nfrom rclpy.node import Node\nimport cflib.crtp  # noqa\nfrom cflib.bootloader import Bootloader, Target\nfrom cflib.bootloader.boottypes import BootVersion\nimport argparse\nimport os\n\nclass Flash(Node):\n    def __init__(self, uri, file_name):\n        super().__init__('flash')\n    \n        self.get_logger().info(f\"Flashing {uri} with {file_name}\")\n\n        base_file_name = os.path.basename(file_name)\n\n        if base_file_name.endswith(\"zip\") and base_file_name.startswith(\"firmware-cf2\"):\n            targets = []\n        elif base_file_name.endswith(\"bin\") and base_file_name.startswith(\"cf2\"):\n            targets = [Target(\"cf2\", 'stm32', 'fw', [], [])]\n        else:\n            self.get_logger().error(f\"Unsupported file type or name. Only cf2*.bin or firmware-cf2*.zip supported\")\n            return\n\n        bl = Bootloader(uri)\n        try:\n            bl.flash_full(None, file_name, True, targets)\n        except Exception as e:\n            self.get_logger().error(f\"Failed to flash, Error {str(e)}\")\n        finally:\n            if bl:\n                bl.close()\n\n        return\n\ndef main(args=None):\n    cflib.crtp.init_drivers()\n    rclpy.init(args=args)\n    parser = argparse.ArgumentParser(description=\"This is a sample script\")\n    parser.add_argument('--uri', type=str, default=\"radio://0/80/2M/E7E7E7E7E7\", help='unique resource identifier')\n    parser.add_argument('--file_name', type=str, default=\"cf2.bin\", help='')\n\n    # Parse the arguments\n    args = parser.parse_args()\n\n    print(\"URI: \", args.uri)\n    flash_node = Flash(args.uri, args.file_name)\n\n    flash_node.destroy_node()\n    rclpy.shutdown()\n\nif __name__ == '__main__':\n    main()"
  },
  {
    "path": "crazyflie/scripts/gui.py",
    "content": "#!/usr/bin/env python3\n\nimport threading\nimport time\nfrom pathlib import Path\nfrom functools import partial\n\nimport rclpy\nfrom std_srvs.srv import Empty\nfrom geometry_msgs.msg import Twist\nfrom rcl_interfaces.msg import Log\nfrom rclpy.executors import ExternalShutdownException\nfrom rclpy.node import Node\n\n# from tf2_ros import TransformException\nfrom tf2_ros.buffer import Buffer\nfrom tf2_ros.transform_listener import TransformListener\n\nfrom crazyflie_interfaces.msg import Status\nimport rowan\n\nfrom nicegui import Client, app, events, ui, ui_run, Tailwind\n\n\nclass NiceGuiNode(Node):\n\n    def __init__(self) -> None:\n        super().__init__('nicegui')\n\n        # wait until the crazyflie_server is up and running\n        self.emergencyService = self.create_client(Empty, 'all/emergency')\n        self.emergencyService.wait_for_service()\n\n        # find all crazyflies\n        self.cfnames = []\n        for srv_name, srv_types in self.get_service_names_and_types():\n            if 'crazyflie_interfaces/srv/StartTrajectory' in srv_types:\n                # remove '/' and '/start_trajectory'\n                cfname = srv_name[1:-17]\n                if cfname != 'all':\n                    self.cfnames.append(cfname)\n\n        self.tf_buffer = Buffer()\n        self.tf_listener = TransformListener(self.tf_buffer, self)\n\n        self.cmd_vel_publisher = self.create_publisher(Twist, 'cmd_vel', 1)\n        self.sub_log = self.create_subscription(Log, 'rosout', self.on_rosout, rclpy.qos.QoSProfile(\n                        depth=1000,\n                        durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL))\n\n        self.logs = dict()\n        self.supervisor_labels = dict()\n        self.battery_labels = dict()\n        self.radio_labels = dict()\n        self.robotmodels = dict()\n\n        self.normal_style = Tailwind().text_color('black').font_weight('normal')\n        self.red_style = Tailwind().text_color('red-600').font_weight('bold')\n\n        with Client.auto_index_client:\n\n            with ui.row().classes('items-stretch'):\n                with ui.card().classes('w-full h-full'):\n                    ui.label('Visualization').classes('text-2xl')\n                    with ui.scene(800, 400, on_click=self.on_vis_click) as scene:\n                        for name in self.cfnames:\n                            robot = scene.stl('/urdf/cf2_assembly.stl').scale(1.0).material('#ff0000').with_name(name)\n                            self.robotmodels[name] = robot\n                            # augment with some additional fields\n                            robot.status_ok = False\n                            robot.battery_ok = False\n                            robot.status_watchdog = time.time()\n                            robot.supervisor_text = \"\"\n                            robot.battery_text = \"\"\n                            robot.radio_text = \"\"\n                    scene.camera.x = 0\n                    scene.camera.y = -1\n                    scene.camera.z = 2\n                    scene.camera.look_at_x = 0\n                    scene.camera.look_at_y = 0\n                    scene.camera.look_at_z = 0\n\n            with ui.row().classes('w-full h-lvh'):\n                with ui.tabs().classes('w-full') as tabs:\n                    self.tabs = []\n                    for name in [\"all\"] + self.cfnames:\n                        self.tabs.append(ui.tab(name))\n                with ui.tab_panels(tabs, value=self.tabs[0], on_change=self.on_tab_change).classes('w-full') as self.tabpanels:\n                    for name, tab in zip([\"all\"] + self.cfnames, self.tabs):\n                        with ui.tab_panel(tab):\n                            self.logs[name] = ui.log().classes('w-full h-96 no-wrap')\n                            self.supervisor_labels[name] = ui.label(\"\")\n                            self.battery_labels[name] = ui.label(\"\")\n                            self.radio_labels[name] = ui.label(\"\")\n\n            for name in self.cfnames:\n                self.create_subscription(Status, name + '/status', partial(self.on_status, name=name), 1)\n\n            # Call on_timer function\n            update_rate = 30 # Hz\n            self.timer = self.create_timer(\n                1.0/update_rate, \n                self.on_timer,\n                clock=rclpy.clock.Clock(clock_type=rclpy.clock.ClockType.SYSTEM_TIME))\n\n    def on_rosout(self, msg: Log) -> None:\n        # filter by crazyflie and add to the correct log\n        if msg.name == \"crazyflie_server\":\n            if msg.msg.startswith(\"[\"):\n                idx = msg.msg.find(\"]\")\n                name = msg.msg[1:idx]\n                # if it was an \"all\" category, add only to CFs\n                if name == 'all':\n                    for logname ,log in self.logs.items():\n                        if logname != \"all\":\n                            log.push(msg.msg)\n                elif name in self.logs:\n                    self.logs[name].push(msg.msg[idx+2:])\n\n        # add all possible messages to the 'all' tab\n        self.logs['all'].push(msg.msg)\n\n    def on_timer(self) -> None:\n        for name, robotmodel in self.robotmodels.items():\n            ros_time = rclpy.time.Time() # get the latest\n            robot_status_ok = robotmodel.status_ok and robotmodel.battery_ok\n            robot_status_text = \"\"\n            if self.tf_buffer.can_transform(\"world\", name, ros_time):\n                t = self.tf_buffer.lookup_transform(\n                                \"world\",\n                                name,\n                                ros_time)\n                transform_time = rclpy.time.Time.from_msg(t.header.stamp)\n                transform_age = self.get_clock().now() - transform_time\n                # latest transform is older than a second indicates a problem\n                if transform_age.nanoseconds * 1e-9 > 1:\n                    robot_status_ok = False\n                    robot_status_text += \"old transform; \"\n                else:\n                    pos = t.transform.translation\n                    robotmodel.move(pos.x, pos.y, pos.z)\n                    robotmodel.rotate(*rowan.to_euler([\n                        t.transform.rotation.w,\n                        t.transform.rotation.x,\n                        t.transform.rotation.y,\n                        t.transform.rotation.z], \"xyz\"))\n            else:\n                # no available transform indicates a problem\n                robot_status_ok = False\n                robot_status_text += \"unavailable transform; \"\n\n            # no status update for a while, indicate a problem\n            if time.time() - robotmodel.status_watchdog > 2.0:\n                robot_status_ok = False\n                robot_status_text += \"no recent status update; \"\n\n                self.supervisor_labels[name].set_text(robot_status_text)\n                self.battery_labels[name].set_text(\"N.A.\")\n                self.radio_labels[name].set_text(\"N.A.\")\n            else:\n                self.supervisor_labels[name].set_text(robot_status_text + robotmodel.supervisor_text)\n                self.battery_labels[name].set_text(robotmodel.battery_text)\n                self.radio_labels[name].set_text(robotmodel.radio_text)\n\n            # any issues detected -> mark red, otherwise green\n            if robot_status_ok:\n                robotmodel.material('#00ff00')\n            else:\n                robotmodel.material('#ff0000')\n\n            if robotmodel.battery_ok:\n                self.normal_style.apply(self.battery_labels[name])\n            else:\n                self.red_style.apply(self.battery_labels[name])\n\n    def on_vis_click(self, e: events.SceneClickEventArguments):\n        hit = e.hits[0]\n        name = hit.object_name or hit.object_id\n        ui.notify(f'You clicked on the {name}')\n        if name == 'ground':\n            self.tabpanels.value = 'all'\n        else:\n            self.tabpanels.value = name\n\n    def on_status(self, msg, name) -> None:\n        status_ok = True\n        is_flying = False\n        supervisor_text = \"\"\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_BE_ARMED:\n            supervisor_text += \"can be armed; \"\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_ARMED:\n            supervisor_text += \"is armed; \"\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_AUTO_ARM:\n            supervisor_text += \"auto-arm; \"\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_CAN_FLY:\n            supervisor_text += \"can fly; \"\n        else:\n            status_ok = False\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_FLYING:\n            supervisor_text += \"is flying; \"\n            is_flying = True\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_TUMBLED:\n            supervisor_text += \"is tumbled; \"\n            status_ok = False\n        if msg.supervisor_info & Status.SUPERVISOR_INFO_IS_LOCKED:\n            supervisor_text += \"is locked; \"\n            status_ok = False\n        self.robotmodels[name].supervisor_text = supervisor_text\n\n        battery_text = f'{msg.battery_voltage:.2f} V'\n        battery_ok = True\n        # TODO (WH): We could read the voltage limits from the firmware (parameter) or crazyflies.yaml\n        #            In the firmware, anything below 3.2 is warning, anything below 3.0 is critical\n        if (is_flying and msg.battery_voltage < 3.2) or (not is_flying and msg.battery_voltage < 3.8):\n            battery_ok = False\n        if msg.pm_state == Status.PM_STATE_BATTERY:\n            battery_text += \" (on battery)\"\n        elif msg.pm_state == Status.PM_STATE_CHARGING:\n            battery_text += \" (charging)\"\n        elif msg.pm_state == Status.PM_STATE_CHARGED:\n            battery_text += \" (charged)\"\n        elif msg.pm_state == Status.PM_STATE_LOW_POWER:\n            battery_text += \" (low power)\"\n            battery_ok = False\n        elif msg.pm_state == Status.PM_STATE_SHUTDOWN:\n            battery_text += \" (shutdown)\"\n            battery_ok = False\n        self.robotmodels[name].battery_text = battery_text\n        \n        radio_text = f'{msg.rssi} dBm; Unicast: {msg.num_rx_unicast} / {msg.num_tx_unicast}; Broadcast: {msg.num_rx_broadcast} / {msg.num_tx_broadcast}; Latency: {msg.latency_unicast} ms'\n        self.robotmodels[name].radio_text = radio_text\n\n        # save status here\n        self.robotmodels[name].status_ok = status_ok\n        self.robotmodels[name].battery_ok = battery_ok\n\n        # store the time when we last received any status\n        self.robotmodels[name].status_watchdog = time.time()\n\n    def on_tab_change(self, arg):\n        for name, robotmodel in self.robotmodels.items():\n            if name != arg.value:\n                robotmodel.scale(1)\n        if arg.value in self.robotmodels:\n            self.robotmodels[arg.value].scale(2)\n\n\ndef main() -> None:\n    # NOTE: This function is defined as the ROS entry point in setup.py, but it's empty to enable NiceGUI auto-reloading\n    pass\n\n\ndef ros_main() -> None:\n    rclpy.init()\n    node = NiceGuiNode()\n    try:\n        rclpy.spin(node)\n    except ExternalShutdownException:\n        pass\n\n\napp.add_static_files(\"/urdf\",\n                     str((Path(__file__).parent.parent.parent / \"share\" / \"crazyflie\" / \"urdf\").resolve()),\n                     follow_symlink=True)\napp.on_startup(lambda: threading.Thread(target=ros_main).start())\nui_run.APP_IMPORT_STRING = f'{__name__}:app'  # ROS2 uses a non-standard module name, so we need to specify it here\nui.run(uvicorn_reload_dirs=str(Path(__file__).parent.resolve()), favicon='🤖')\n"
  },
  {
    "path": "crazyflie/scripts/simple_mapper_multiranger.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\" This simple mapper is loosely based on both the bitcraze cflib point cloud example \n https://github.com/bitcraze/crazyflie-lib-python/blob/master/examples/multiranger/multiranger_pointcloud.py\n and the webots epuck simple mapper example:\n https://github.com/cyberbotics/webots_ros2\n\n Originally from https://github.com/knmcguire/crazyflie_ros2_experimental/\n \"\"\"\n\nimport rclpy\nfrom rclpy.node import Node\nfrom rclpy.qos import DurabilityPolicy, HistoryPolicy, QoSProfile\n\nfrom nav_msgs.msg import Odometry\nfrom sensor_msgs.msg import LaserScan\nfrom nav_msgs.msg import OccupancyGrid\nfrom geometry_msgs.msg import TransformStamped\nfrom tf2_ros import StaticTransformBroadcaster\n\nimport tf_transformations\nimport math\nimport numpy as np\nfrom bresenham import bresenham\n\nGLOBAL_SIZE_X = 20.0\nGLOBAL_SIZE_Y = 20.0\nMAP_RES = 0.1\n\n\nclass SimpleMapperMultiranger(Node):\n    def __init__(self):\n        super().__init__('simple_mapper_multiranger')\n        self.declare_parameter('robot_prefix', '/cf231')\n        robot_prefix = self.get_parameter('robot_prefix').value\n\n        self.odom_subscriber = self.create_subscription(\n            Odometry, robot_prefix + '/odom', self.odom_subscribe_callback, 10)\n        self.ranges_subscriber = self.create_subscription(\n            LaserScan, robot_prefix + '/scan', self.scan_subscribe_callback, 10)\n        self.position = [0.0, 0.0, 0.0]\n        self.angles = [0.0, 0.0, 0.0]\n        self.ranges = [0.0, 0.0, 0.0, 0.0]\n        self.range_max = 3.5\n\n        self.tfbr = StaticTransformBroadcaster(self)\n        t_map = TransformStamped()\n        t_map.header.stamp = self.get_clock().now().to_msg()\n        t_map.header.frame_id = 'map'\n        t_map.child_frame_id = robot_prefix + '/odom'\n        t_map.transform.translation.x = 0.0\n        t_map.transform.translation.y = 0.0\n        t_map.transform.translation.z = 0.0\n        self.tfbr.sendTransform(t_map)\n\n        self.position_update = False\n\n        self.map = [-1] * int(GLOBAL_SIZE_X / MAP_RES) * \\\n            int(GLOBAL_SIZE_Y / MAP_RES)\n        self.map_publisher = self.create_publisher(OccupancyGrid, robot_prefix + '/map',\n                                                   qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST,))\n\n        self.get_logger().info(f\"Simple mapper set for crazyflie \" + robot_prefix +\n                               f\" using the odom and scan topic\")\n\n    def odom_subscribe_callback(self, msg):\n        self.position[0] = msg.pose.pose.position.x\n        self.position[1] = msg.pose.pose.position.y\n        self.position[2] = msg.pose.pose.position.z\n        q = msg.pose.pose.orientation\n        euler = tf_transformations.euler_from_quaternion([q.x, q.y, q.z, q.w])\n        self.angles[0] = euler[0]\n        self.angles[1] = euler[1]\n        self.angles[2] = euler[2]\n        self.position_update = True\n\n    def scan_subscribe_callback(self, msg):\n        self.ranges = msg.ranges\n        self.range_max = msg.range_max\n        data = self.rotate_and_create_points()\n\n        points_x = []\n        points_y = []\n        #\n        if self.position_update is False:\n            return\n        for i in range(len(data)):\n            point_x = int((data[i][0] - GLOBAL_SIZE_X / 2.0) / MAP_RES)\n            point_y = int((data[i][1] - GLOBAL_SIZE_Y / 2.0) / MAP_RES)\n            points_x.append(point_x)\n            points_y.append(point_y)\n            position_x_map = int(\n                (self.position[0] - GLOBAL_SIZE_X / 2.0) / MAP_RES)\n            position_y_map = int(\n                (self.position[1] - GLOBAL_SIZE_Y / 2.0) / MAP_RES)\n            for line_x, line_y in bresenham(position_x_map, position_y_map, point_x, point_y):\n                self.map[line_y * int(GLOBAL_SIZE_X / MAP_RES) + line_x] = 0\n            self.map[point_y * int(GLOBAL_SIZE_X / MAP_RES) + point_x] = 100\n\n        msg = OccupancyGrid()\n        msg.header.stamp = self.get_clock().now().to_msg()\n        msg.header.frame_id = 'map'\n        msg.info.resolution = MAP_RES\n        msg.info.width = int(GLOBAL_SIZE_X / MAP_RES)\n        msg.info.height = int(GLOBAL_SIZE_Y / MAP_RES)\n        msg.info.origin.position.x = - GLOBAL_SIZE_X / 2.0\n        msg.info.origin.position.y = - GLOBAL_SIZE_Y / 2.0\n        msg.data = self.map\n        self.map_publisher.publish(msg)\n\n    def rotate_and_create_points(self):\n        data = []\n        o = self.position\n        roll = self.angles[0]\n        pitch = self.angles[1]\n        yaw = self.angles[2]\n        r_back = self.ranges[0]\n        r_right = self.ranges[1]\n        r_front = self.ranges[2]\n        r_left = self.ranges[3]\n\n        if (r_left < self.range_max and r_left != 0.0):\n            left = [o[0], o[1] + r_left, o[2]]\n            data.append(self.rot(roll, pitch, yaw, o, left))\n\n        if (r_right < self.range_max and r_right != 0.0):\n            right = [o[0], o[1] - r_right, o[2]]\n            data.append(self.rot(roll, pitch, yaw, o, right))\n\n        if (r_front < self.range_max and r_front != 0.0):\n            front = [o[0] + r_front, o[1], o[2]]\n            data.append(self.rot(roll, pitch, yaw, o, front))\n\n        if (r_back < self.range_max and r_back != 0.0):\n            back = [o[0] - r_back, o[1], o[2]]\n            data.append(self.rot(roll, pitch, yaw, o, back))\n\n        return data\n\n    def rot(self, roll, pitch, yaw, origin, point):\n        cosr = math.cos((roll))\n        cosp = math.cos((pitch))\n        cosy = math.cos((yaw))\n\n        sinr = math.sin((roll))\n        sinp = math.sin((pitch))\n        siny = math.sin((yaw))\n\n        roty = np.array([[cosy, -siny, 0],\n                        [siny, cosy, 0],\n                        [0, 0,    1]])\n\n        rotp = np.array([[cosp, 0, sinp],\n                        [0, 1, 0],\n                        [-sinp, 0, cosp]])\n\n        rotr = np.array([[1, 0,   0],\n                        [0, cosr, -sinr],\n                        [0, sinr,  cosr]])\n\n        rotFirst = np.dot(rotr, rotp)\n\n        rot = np.array(np.dot(rotFirst, roty))\n\n        tmp = np.subtract(point, origin)\n        tmp2 = np.dot(rot, tmp)\n        return np.add(tmp2, origin)\n\n\ndef main(args=None):\n\n    rclpy.init(args=args)\n    simple_mapper_multiranger = SimpleMapperMultiranger()\n    rclpy.spin(simple_mapper_multiranger)\n    rclpy.destroy_node()\n    rclpy.shutdown()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie/scripts/vel_mux.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nA Twist message handler that get incoming twist messages from \n    external packages and handles proper takeoff, landing and\n    hover commands of connected crazyflie in the crazyflie_server\n    node\n\n    2022 - K. N. McGuire (Bitcraze AB)\n\"\"\"\nimport rclpy\nfrom rclpy.node import Node\n\nfrom geometry_msgs.msg import Twist\nfrom crazyflie_interfaces.srv import Takeoff, Land, NotifySetpointsStop\nfrom crazyflie_interfaces.msg import Hover\nimport time\n\nclass VelMux(Node):\n    def __init__(self):\n        super().__init__('vel_mux')\n        self.declare_parameter('hover_height', 0.5)\n        self.declare_parameter('robot_prefix', '/cf')\n        self.declare_parameter('incoming_twist_topic', '/cmd_vel')\n\n        self.hover_height  = self.get_parameter('hover_height').value\n        robot_prefix  = self.get_parameter('robot_prefix').value\n        incoming_twist_topic  = self.get_parameter('incoming_twist_topic').value\n        \n        self.subscription = self.create_subscription(\n            Twist,\n            incoming_twist_topic,\n            self.cmd_vel_callback,\n            10)\n        self.msg_cmd_vel = Twist()\n        self.received_first_cmd_vel = False\n        timer_period = 0.1\n        self.timer = self.create_timer(timer_period, self.timer_callback)\n        self.takeoff_client = self.create_client(Takeoff, robot_prefix + '/takeoff')\n        self.publisher_hover = self.create_publisher(Hover, robot_prefix + '/cmd_hover', 10)\n        self.land_client = self.create_client(Land, robot_prefix + '/land')\n        self.notify_client = self.create_client(NotifySetpointsStop, robot_prefix + '/notify_setpoints_stop')\n        self.cf_has_taken_off = False\n\n        self.takeoff_client.wait_for_service()\n        self.land_client.wait_for_service()\n\n        self.get_logger().info(f\"Velocity Multiplexer set for {robot_prefix}\"+\n                               f\" with height {self.hover_height} m using the {incoming_twist_topic} topic\")\n\n    def cmd_vel_callback(self, msg):\n        self.msg_cmd_vel = msg\n        # This is to handle the zero twist messages from teleop twist keyboard closing\n        # or else the crazyflie would constantly take off again.\n        msg_is_zero = msg.linear.x == 0.0 and msg.linear.y == 0.0 and msg.angular.z == 0.0 and msg.linear.z == 0.0\n        if  msg_is_zero is False and self.received_first_cmd_vel is False and msg.linear.z >= 0.0:\n            self.received_first_cmd_vel = True\n\n    def timer_callback(self):\n        if self.received_first_cmd_vel and self.cf_has_taken_off is False:\n            req = Takeoff.Request()\n            req.height = self.hover_height\n            req.duration = rclpy.duration.Duration(seconds=2.0).to_msg()\n            self.takeoff_client.call_async(req)\n            self.cf_has_taken_off = True\n            time.sleep(2.0)        \n        if self.received_first_cmd_vel and self.cf_has_taken_off:\n            if self.msg_cmd_vel.linear.z >= 0:\n                msg = Hover()\n                msg.vx = self.msg_cmd_vel.linear.x\n                msg.vy = self.msg_cmd_vel.linear.y\n                msg.yaw_rate = self.msg_cmd_vel.angular.z\n                msg.z_distance = self.hover_height\n                self.publisher_hover.publish(msg)\n            else:\n                req = NotifySetpointsStop.Request()\n                self.notify_client.call_async(req)\n                req = Land.Request()\n                req.height = 0.1\n                req.duration = rclpy.duration.Duration(seconds=2.0).to_msg()\n                self.land_client.call_async(req)\n                time.sleep(2.0)        \n                self.cf_has_taken_off = False\n                self.received_first_cmd_vel = False\n\ndef main(args=None):\n    rclpy.init(args=args)\n\n    vel_mux = VelMux()\n\n    rclpy.spin(vel_mux)\n\n    vel_mux.destroy_node()\n    rclpy.shutdown()\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie/src/crazyflie_server.cpp",
    "content": "#include <memory>\n#include <vector>\n#include <regex>\n\n#include <crazyflie_cpp/Crazyflie.h>\n\n#include <rclcpp/rclcpp.hpp>\n#include <tf2_ros/transform_broadcaster.h>\n#include \"std_srvs/srv/empty.hpp\"\n#include \"crazyflie_interfaces/srv/start_trajectory.hpp\"\n#include \"crazyflie_interfaces/srv/takeoff.hpp\"\n#include \"crazyflie_interfaces/srv/land.hpp\"\n#include \"crazyflie_interfaces/srv/go_to.hpp\"\n#include \"crazyflie_interfaces/srv/notify_setpoints_stop.hpp\"\n#include \"crazyflie_interfaces/srv/arm.hpp\"\n#include \"std_msgs/msg/string.hpp\"\n#include \"geometry_msgs/msg/twist.hpp\"\n#include \"geometry_msgs/msg/pose_stamped.hpp\"\n#include \"geometry_msgs/msg/transform_stamped.hpp\"\n#include \"sensor_msgs/msg/laser_scan.hpp\"\n#include \"nav_msgs/msg/odometry.hpp\"\n#include \"crazyflie_interfaces/srv/upload_trajectory.hpp\"\n#include \"motion_capture_tracking_interfaces/msg/named_pose_array.hpp\"\n#include \"crazyflie_interfaces/msg/full_state.hpp\"\n#include \"crazyflie_interfaces/msg/position.hpp\"\n#include \"crazyflie_interfaces/msg/velocity_world.hpp\"\n#include \"crazyflie_interfaces/msg/hover.hpp\"\n#include \"crazyflie_interfaces/msg/status.hpp\"\n#include \"crazyflie_interfaces/msg/log_data_generic.hpp\"\n#include \"crazyflie_interfaces/msg/connection_statistics_array.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\n\nusing crazyflie_interfaces::srv::StartTrajectory;\nusing crazyflie_interfaces::srv::Takeoff;\nusing crazyflie_interfaces::srv::Land;\nusing crazyflie_interfaces::srv::GoTo;\nusing crazyflie_interfaces::srv::UploadTrajectory;\nusing crazyflie_interfaces::srv::NotifySetpointsStop;\nusing crazyflie_interfaces::srv::Arm;\nusing std_srvs::srv::Empty;\n\nusing motion_capture_tracking_interfaces::msg::NamedPoseArray;\nusing crazyflie_interfaces::msg::FullState;\n\n#ifdef ROS_DISTRO_HUMBLE\ninline auto get_service_qos() { return rmw_qos_profile_services_default; }\n#else\ninline auto get_service_qos() { return rclcpp::ServicesQoS(); }\n#endif\n\n// Note on logging: we use a single logger with string prefixes\n// A better way would be to use named child loggers, but these do not\n// report to /rosout in humble, see https://github.com/ros2/rclpy/issues/1131\n// Once we do not support humble anymore, consider switching to child loggers\n\n// Helper class to convert crazyflie_cpp logging messages to ROS logging messages\nclass CrazyflieLogger : public Logger\n{\npublic:\n  CrazyflieLogger(rclcpp::Logger logger, const std::string& prefix)\n      : Logger()\n      , logger_(logger)\n      , prefix_(prefix)\n  {\n  }\n\n  virtual ~CrazyflieLogger() {}\n\n  virtual void info(const std::string &msg)\n  {\n    RCLCPP_INFO(logger_, \"%s %s\", prefix_.c_str(), msg.c_str());\n  }\n\n  virtual void warning(const std::string &msg)\n  {\n    RCLCPP_WARN(logger_, \"%s %s\", prefix_.c_str(),  msg.c_str());\n  }\n\n  virtual void error(const std::string &msg)\n  {\n    RCLCPP_ERROR(logger_, \"%s %s\", prefix_.c_str(), msg.c_str());\n  }\nprivate:\n  rclcpp::Logger logger_;\n  std::string prefix_;\n};\n\nstd::set<std::string> extract_names(\n    const std::map<std::string, rclcpp::ParameterValue> &parameter_overrides,\n    const std::string &pattern)\n{\n  std::set<std::string> result;\n  for (const auto &i : parameter_overrides)\n  {\n    if (i.first.find(pattern) == 0)\n    {\n      size_t start = pattern.size() + 1;\n      size_t end = i.first.find(\".\", start);\n      result.insert(i.first.substr(start, end - start));\n    }\n  }\n  return result;\n}\n\n// ROS wrapper for a single Crazyflie object\nclass CrazyflieROS\n{\nprivate:\n  struct logPose {\n    float x;\n    float y;\n    float z;\n    int32_t quatCompressed;\n  } __attribute__((packed));\n\n  struct logScan {\n    uint16_t front;\n    uint16_t left;\n    uint16_t back;\n    uint16_t right;\n  } __attribute__((packed));\n\n  struct logOdom {\n    int16_t x;\n    int16_t y;\n    int16_t z;\n    int32_t quatCompressed;\n    int16_t vx;\n    int16_t vy;\n    int16_t vz;\n    //int16_t rateRoll;  \n    //int16_t ratePitch;\n    //int16_t rateYaw;\n  } __attribute__((packed));\n\n\n  struct logStatus {\n    // general status\n    uint16_t supervisorInfo; // supervisor.info\n    // battery related\n    // Note that using BQ-deck/Bolt one can actually have two batteries at the same time.\n    // vbat refers to the battery directly connected to the CF board and might not reflect\n    // the \"external\" battery on BQ/Bolt builds\n    uint16_t vbatMV;  // pm.vbatMV\n    uint8_t pmState;  // pm.state\n    // radio related\n    uint8_t rssi;     // radio.rssi\n    uint16_t numRxBc; // radio.numRxBc\n    uint16_t numRxUc; // radio.numRxUc\n  } __attribute__((packed));\n\npublic:\n  CrazyflieROS(\n    const std::string& link_uri,\n    const std::string& cf_type,\n    const std::string& name,\n    rclcpp::Node* node,\n    rclcpp::CallbackGroup::SharedPtr callback_group_cf_cmd,\n    rclcpp::CallbackGroup::SharedPtr callback_group_cf_srv,\n    const CrazyflieBroadcaster* cfbc,\n    bool enable_parameters = true)\n    : logger_(node->get_logger())\n    , cf_logger_(logger_, \"[\" + name + \"]\")\n    , cf_(\n      link_uri,\n      cf_logger_,\n      std::bind(&CrazyflieROS::on_console, this, std::placeholders::_1))\n    , name_(name)\n    , node_(node)\n    , tf_broadcaster_(node)\n    , last_on_latency_(std::chrono::steady_clock::now())\n    , cfbc_(cfbc)\n  {\n    auto sub_opt_cf_cmd = rclcpp::SubscriptionOptions();\n    sub_opt_cf_cmd.callback_group = callback_group_cf_cmd;\n\n    // Services\n    auto service_qos = rmw_qos_profile_services_default;\n\n\n    service_emergency_ = node->create_service<Empty>(name + \"/emergency\", std::bind(&CrazyflieROS::emergency, this, _1, _2),  get_service_qos(), callback_group_cf_srv);\n    service_start_trajectory_ = node->create_service<StartTrajectory>(name + \"/start_trajectory\", std::bind(&CrazyflieROS::start_trajectory, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_takeoff_ = node->create_service<Takeoff>(name + \"/takeoff\", std::bind(&CrazyflieROS::takeoff, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_land_ = node->create_service<Land>(name + \"/land\", std::bind(&CrazyflieROS::land, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_go_to_ = node->create_service<GoTo>(name + \"/go_to\", std::bind(&CrazyflieROS::go_to, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_upload_trajectory_ = node->create_service<UploadTrajectory>(name + \"/upload_trajectory\", std::bind(&CrazyflieROS::upload_trajectory, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_notify_setpoints_stop_ = node->create_service<NotifySetpointsStop>(name + \"/notify_setpoints_stop\", std::bind(&CrazyflieROS::notify_setpoints_stop, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n    service_arm_ = node->create_service<Arm>(name + \"/arm\", std::bind(&CrazyflieROS::arm, this, _1, _2), get_service_qos(), callback_group_cf_srv);\n\n    // Topics\n\n    subscription_cmd_vel_legacy_ = node->create_subscription<geometry_msgs::msg::Twist>(name + \"/cmd_vel_legacy\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_vel_legacy_changed, this, _1), sub_opt_cf_cmd);\n    subscription_cmd_full_state_ = node->create_subscription<crazyflie_interfaces::msg::FullState>(name + \"/cmd_full_state\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_full_state_changed, this, _1), sub_opt_cf_cmd);\n    subscription_cmd_position_ = node->create_subscription<crazyflie_interfaces::msg::Position>(name + \"/cmd_position\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_position_changed, this, _1), sub_opt_cf_cmd);\n    subscription_cmd_velocity_world_ = node->create_subscription<crazyflie_interfaces::msg::VelocityWorld>(name + \"/cmd_velocity_world\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_velocity_world_changed, this, _1), sub_opt_cf_cmd);\n    subscription_cmd_hover_ = node->create_subscription<crazyflie_interfaces::msg::Hover>(name + \"/cmd_hover\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_hover_changed, this, _1), sub_opt_cf_cmd);\n\n    publisher_robot_description_ = node->create_publisher<std_msgs::msg::String>(name + \"/robot_description\",\n      rclcpp::QoS(1).transient_local());\n    {\n      auto msg = std::make_unique<std_msgs::msg::String>();\n      auto robot_desc = node->get_parameter(\"robot_description\").get_parameter_value().get<std::string>();\n      msg->data = std::regex_replace(robot_desc, std::regex(\"\\\\$NAME\"), name);\n      publisher_robot_description_->publish(std::move(msg));\n    }\n\n    // spinning timer\n    // used to process all incoming radio messages\n    spin_timer_ =\n      node->create_wall_timer(\n      std::chrono::milliseconds(1),\n      std::bind(&CrazyflieROS::spin_once, this), callback_group_cf_srv);\n\n    // link statistics\n    warning_freq_ = node->get_parameter(\"warnings.frequency\").get_parameter_value().get<float>();\n    max_latency_ = node->get_parameter(\"warnings.communication.max_unicast_latency\").get_parameter_value().get<float>();\n    min_ack_rate_ = node->get_parameter(\"warnings.communication.min_unicast_ack_rate\").get_parameter_value().get<float>();\n    min_unicast_receive_rate_ = node->get_parameter(\"warnings.communication.min_unicast_receive_rate\").get_parameter_value().get<float>();\n    min_broadcast_receive_rate_ = node->get_parameter(\"warnings.communication.min_broadcast_receive_rate\").get_parameter_value().get<float>();\n    publish_stats_ = node->get_parameter(\"warnings.communication.publish_stats\").get_parameter_value().get<bool>();\n    if (publish_stats_) {\n      publisher_connection_stats_ = node->create_publisher<crazyflie_interfaces::msg::ConnectionStatisticsArray>(name + \"/connection_statistics\", 10);\n    }\n\n    if (warning_freq_ >= 0.0) {\n      cf_.setLatencyCallback(std::bind(&CrazyflieROS::on_latency, this, std::placeholders::_1));\n      link_statistics_timer_ =\n        node->create_wall_timer(\n        std::chrono::milliseconds((int)(1000.0/warning_freq_)),\n        std::bind(&CrazyflieROS::on_link_statistics_timer, this), callback_group_cf_srv);\n\n    }\n\n    auto start = std::chrono::system_clock::now();\n\n    cf_.logReset();\n\n    auto node_parameters_iface = node->get_node_parameters_interface();\n    const std::map<std::string, rclcpp::ParameterValue> &parameter_overrides =\n        node_parameters_iface->get_parameter_overrides();\n\n    // declares lambda, to be used as local function, which re-declares specified parameters for other nodes to query\n    auto declare_param = [&parameter_overrides, node](const std::string& param)\n    {\n      // rclcpp::ParameterValue value(parameter_overridesparam]);\n      node->declare_parameter(param, parameter_overrides.at(param));\n    };\n    declare_param(\"robots.\" + name + \".uri\");\n    declare_param(\"robots.\" + name + \".initial_position\");\n\n    // declares a lambda, to be used as local function\n    auto update_map = [&parameter_overrides](std::map<std::string, rclcpp::ParameterValue>& map, const std::string& pattern)\n    {\n      for (const auto &i : parameter_overrides) {\n        if (i.first.find(pattern) == 0) {\n          size_t start = pattern.size() + 1;\n          const auto group_and_name = i.first.substr(start);\n          map[group_and_name] = i.second;\n        }\n      }\n    };\n\n    auto update_value = [&parameter_overrides](rclcpp::ParameterValue& value, const std::string& pattern)\n    {\n      for (const auto &i : parameter_overrides) {\n        if (i.first.find(pattern) == 0) {\n          value = i.second;\n        }\n      }\n    };\n\n    if (enable_parameters) {\n      bool query_all_values_on_connect = node->get_parameter(\"firmware_params.query_all_values_on_connect\").get_parameter_value().get<bool>();\n\n      int numParams = 0;\n      RCLCPP_INFO(logger_, \"[%s] Requesting parameters...\", name_.c_str());\n      cf_.requestParamToc(/*forceNoCache*/false, /*requestValues*/query_all_values_on_connect);\n      for (auto iter = cf_.paramsBegin(); iter != cf_.paramsEnd(); ++iter) {\n        auto entry = *iter;\n        std::string paramName = name + \".params.\" + entry.group + \".\" + entry.name;\n        switch (entry.type)\n        {\n        case Crazyflie::ParamTypeUint8:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<uint8_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeInt8:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<int8_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeUint16:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<uint16_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeInt16:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<int16_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeUint32:\n          if (query_all_values_on_connect) {\n            node->declare_parameter<int64_t>(paramName, cf_.getParam<uint32_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeInt32:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<int32_t>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_INTEGER);\n          }\n          break;\n        case Crazyflie::ParamTypeFloat:\n          if (query_all_values_on_connect) {\n            node->declare_parameter(paramName, cf_.getParam<float>(entry.id));\n          } else {\n            node->declare_parameter(paramName, rclcpp::PARAMETER_DOUBLE);\n          }\n          break;\n        default:\n          RCLCPP_WARN(logger_, \"[%s] Unknown param type for %s/%s\", name_.c_str(), entry.group.c_str(), entry.name.c_str());\n          break;\n        }\n        // If there is no such parameter in all, add it\n        std::string allParamName = \"all.params.\" + entry.group + \".\" + entry.name;\n        if (!node->has_parameter(allParamName)) {\n          if (entry.type == Crazyflie::ParamTypeFloat) {\n            node->declare_parameter(allParamName, rclcpp::PARAMETER_DOUBLE);\n          } else {\n            node->declare_parameter(allParamName, rclcpp::PARAMETER_INTEGER);\n          }\n        }\n        ++numParams;\n      }\n      auto end1 = std::chrono::system_clock::now();\n      std::chrono::duration<double> elapsedSeconds1 = end1 - start;\n      RCLCPP_INFO(logger_, \"[%s] reqParamTOC: %f s (%d params)\", name_.c_str(), elapsedSeconds1.count(), numParams);\n      \n      // Set parameters as specified in the configuration files, as in the following order\n      // 1.) check all/firmware_params\n      // 2.) check robot_types/<type_name>/firmware_params\n      // 3.) check robots/<robot_name>/firmware_params\n      // where the higher order is used if defined on multiple levels.\n\n      // <group>.<name> -> value map\n      std::map<std::string, rclcpp::ParameterValue> set_param_map;\n\n      // check global settings/firmware_params\n      update_map(set_param_map, \"all.firmware_params\");\n      // check robot_types/<type_name>/firmware_params\n      update_map(set_param_map, \"robot_types.\" + cf_type + \".firmware_params\");\n      // check robots/<robot_name>/firmware_params\n      update_map(set_param_map, \"robots.\" + name_ + \".firmware_params\");\n\n      // Update parameters\n      for (const auto&i : set_param_map) {\n        std::string paramName = name + \".params.\" + std::regex_replace(i.first, std::regex(\"\\\\.\"), \".\");\n        change_parameter(rclcpp::Parameter(paramName, i.second));\n      }\n    }\n\n    // Reference Frame\n    {\n      rclcpp::ParameterValue reference_frame_value(\"world\");\n\n      // Get logging configuration as specified in the configuration files, as in the following order\n      // 1.) check all/reference_frame\n      // 2.) check robot_types/<type_name>/reference_frame\n      // 3.) check robots/<robot_name>/reference_frame\n      // where the higher order is used if defined on multiple levels.\n      update_value(reference_frame_value, \"all.reference_frame\");\n      // check robot_types/<type_name>/reference_frame\n      update_value(reference_frame_value, \"robot_types.\" + cf_type + \".reference_frame\");\n      // check robots/<robot_name>/reference_frame\n      update_value(reference_frame_value, \"robots.\" + name_ + \".reference_frame\");\n\n      // extract reference frame \n      reference_frame_ = reference_frame_value.get<std::string>();\n     \n      RCLCPP_INFO(logger_, \"[%s] ref frame: %s\", name_.c_str(), reference_frame_.c_str());\n      \n    }\n\n    // Logging\n    {\n      // <group>.<name> -> value map\n      std::map<std::string, rclcpp::ParameterValue> log_config_map;\n\n      // Get logging configuration as specified in the configuration files, as in the following order\n      // 1.) check all/firmware_logging\n      // 2.) check robot_types/<type_name>/firmware_logging\n      // 3.) check robots/<robot_name>/firmware_logging\n      // where the higher order is used if defined on multiple levels.\n      update_map(log_config_map, \"all.firmware_logging\");\n      // check robot_types/<type_name>/firmware_logging\n      update_map(log_config_map, \"robot_types.\" + cf_type + \".firmware_logging\");\n      // check robots/<robot_name>/firmware_logging\n      update_map(log_config_map, \"robots.\" + name_ + \".firmware_logging\");\n\n      // check if logging is enabled for this drone\n      bool logging_enabled = log_config_map[\"enabled\"].get<bool>();\n      if (logging_enabled) {\n        cf_.requestLogToc(/*forceNoCache*/);\n\n        for (const auto&i : log_config_map) {\n          // check if any of the default topics are enabled\n          if (i.first.find(\"default_topics.pose\") == 0) {\n            int freq = log_config_map[\"default_topics.pose.frequency\"].get<int>();\n            RCLCPP_INFO(logger_, \"[%s] Logging to /pose at %d Hz\", name_.c_str(), freq);\n\n            publisher_pose_ = node->create_publisher<geometry_msgs::msg::PoseStamped>(name + \"/pose\", 10);\n\n            std::function<void(uint32_t, const logPose*)> cb = std::bind(&CrazyflieROS::on_logging_pose, this, std::placeholders::_1, std::placeholders::_2);\n\n            log_block_pose_.reset(new LogBlock<logPose>(\n              &cf_,{\n                {\"stateEstimate\", \"x\"},\n                {\"stateEstimate\", \"y\"},\n                {\"stateEstimate\", \"z\"},\n                {\"stateEstimateZ\", \"quat\"}\n              }, cb));\n            log_block_pose_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds\n          }\n          else if (i.first.find(\"default_topics.scan\") == 0) {\n            int freq = log_config_map[\"default_topics.scan.frequency\"].get<int>();\n            RCLCPP_INFO(logger_, \"[%s] Logging to /scan at %d Hz\", name_.c_str(), freq);\n\n            publisher_scan_ = node->create_publisher<sensor_msgs::msg::LaserScan>(name + \"/scan\", 10);\n\n            std::function<void(uint32_t, const logScan*)> cb = std::bind(&CrazyflieROS::on_logging_scan, this, std::placeholders::_1, std::placeholders::_2);\n\n            log_block_scan_.reset(new LogBlock<logScan>(\n              &cf_,{\n                {\"range\", \"front\"},\n                {\"range\", \"left\"},\n                {\"range\", \"back\"},\n                {\"range\", \"right\"}\n              }, cb));\n            log_block_scan_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds\n          }\n          else if (i.first.find(\"default_topics.odom\") == 0) {\n            int freq = log_config_map[\"default_topics.odom.frequency\"].get<int>();\n            RCLCPP_INFO(logger_, \"[%s] Logging to /odom at %d Hz\", name_.c_str(), freq);\n\n            publisher_odom_ = node->create_publisher<nav_msgs::msg::Odometry>(name + \"/odom\", 10);\n\n            std::function<void(uint32_t, const logOdom*)> cb = std::bind(&CrazyflieROS::on_logging_odom, this, std::placeholders::_1, std::placeholders::_2);\n\n            log_block_odom_.reset(new LogBlock<logOdom>(\n              &cf_,{\n                {\"stateEstimateZ\", \"x\"},\n                {\"stateEstimateZ\", \"y\"},\n                {\"stateEstimateZ\", \"z\"},\n                {\"stateEstimateZ\", \"quat\"},\n                {\"stateEstimateZ\", \"vx\"},\n                {\"stateEstimateZ\", \"vy\"},\n                {\"stateEstimateZ\", \"vz\"},\n                //{\"stateEstimateZ\", \"rateRoll\"},\n                //{\"stateEstimateZ\", \"ratePitch\"},\n                //{\"stateEstimateZ\", \"rateYaw\"}\n              }, cb));\n            log_block_odom_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds\n            \n          }\n          else if (i.first.find(\"default_topics.status\") == 0) {\n            int freq = log_config_map[\"default_topics.status.frequency\"].get<int>();\n            RCLCPP_INFO(logger_, \"[%s] Logging to /status at %d Hz\", name_.c_str(), freq);\n\n            publisher_status_ = node->create_publisher<crazyflie_interfaces::msg::Status>(name + \"/status\", 10);\n\n            std::function<void(uint32_t, const logStatus*)> cb = std::bind(&CrazyflieROS::on_logging_status, this, std::placeholders::_1, std::placeholders::_2);\n\n            std::list<std::pair<std::string, std::string> > logvars({\n              // general status\n              {\"supervisor\", \"info\"},\n              // battery related\n              {\"pm\", \"vbatMV\"},\n              {\"pm\", \"state\"},\n              // radio related\n              {\"radio\", \"rssi\"}\n            });\n\n            // check if this firmware version has radio.numRx{Bc,Uc}\n            status_has_radio_stats_ = false;\n            for (auto iter = cf_.logVariablesBegin(); iter != cf_.logVariablesEnd(); ++iter) {\n              auto entry = *iter;\n              if (entry.group == \"radio\" && entry.name == \"numRxBc\") {\n                logvars.push_back({\"radio\", \"numRxBc\"});\n                logvars.push_back({\"radio\", \"numRxUc\"});\n                status_has_radio_stats_ = true;\n                break;\n              }\n            }\n\n            // older firmware -> use other 16-bit variables\n            if (!status_has_radio_stats_) {\n                RCLCPP_WARN(logger_, \"[%s] Older firmware. status/num_rx_broadcast and status/num_rx_unicast are set to zero.\", name_.c_str());\n                logvars.push_back({\"pm\", \"vbatMV\"});\n                logvars.push_back({\"pm\", \"vbatMV\"});\n            }\n\n            log_block_status_.reset(new LogBlock<logStatus>(\n              &cf_,logvars, cb));\n            log_block_status_->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds\n          }\n          else if (i.first.find(\"custom_topics\") == 0\n                   && i.first.rfind(\".vars\") != std::string::npos) {\n            std::string topic_name = i.first.substr(14, i.first.size() - 14 - 5);\n\n            int freq = log_config_map[\"custom_topics.\" + topic_name + \".frequency\"].get<int>();\n            auto vars = log_config_map[\"custom_topics.\" + topic_name + \".vars\"].get<std::vector<std::string>>();\n            \n            RCLCPP_INFO(logger_, \"[%s] Logging to %s at %d Hz\", name_.c_str(), topic_name.c_str(), freq);\n\n            publishers_generic_.emplace_back(node->create_publisher<crazyflie_interfaces::msg::LogDataGeneric>(name + \"/\" + topic_name, 10));\n\n            std::function<void(uint32_t, const std::vector<float>*, void* userData)> cb = std::bind(\n              &CrazyflieROS::on_logging_custom,\n              this,\n              std::placeholders::_1,\n              std::placeholders::_2,\n              std::placeholders::_3);\n\n            log_blocks_generic_.emplace_back(new LogBlockGeneric(\n              &cf_,\n              vars,\n              (void*)&publishers_generic_.back(),\n              cb));\n            log_blocks_generic_.back()->start(uint8_t(100.0f / (float)freq)); // this is in tens of milliseconds\n          }\n        }\n      }\n    }\n\n    RCLCPP_INFO(logger_, \"[%s] Requesting memories...\", name_.c_str());\n    cf_.requestMemoryToc();\n  }\n\n  void spin_once()\n  {\n    // process all packets from the receive queue\n    cf_.processAllPackets();\n  }\n\n  std::string broadcastUri() const\n  {\n    return cf_.broadcastUri();\n  }\n\n  uint8_t id() const\n  {\n    return cf_.address() & 0xFF;\n  }\n\n  const Crazyflie::ParamTocEntry* paramTocEntry(const std::string& group, const std::string& name)\n  {\n    return cf_.getParamTocEntry(group, name);\n  }\n\n  const std::string& name() const\n  {\n    return name_;\n  }\n\n  void change_parameter(const rclcpp::Parameter& p)\n  {\n    std::string prefix = name_ + \".params.\";\n    if (p.get_name().find(prefix) != 0) {\n      RCLCPP_ERROR(\n              logger_,\n              \"[%s] Incorrect parameter update request for param \\\"%s\\\"\", name_.c_str(), p.get_name().c_str());\n      return;\n    }\n    size_t pos = p.get_name().find(\".\", prefix.size());\n    std::string group(p.get_name().begin() + prefix.size(), p.get_name().begin() + pos);\n    std::string name(p.get_name().begin() + pos + 1, p.get_name().end());\n\n    RCLCPP_INFO(\n        logger_,\n        \"[%s] Update parameter \\\"%s.%s\\\" to %s\",\n        name_.c_str(),\n        group.c_str(),\n        name.c_str(),\n        p.value_to_string().c_str());\n\n    auto entry = cf_.getParamTocEntry(group, name);\n    if (entry) {\n      switch (entry->type)\n      {\n      case Crazyflie::ParamTypeUint8:\n        cf_.setParam<uint8_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeInt8:\n        cf_.setParam<int8_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeUint16:\n        cf_.setParam<uint16_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeInt16:\n        cf_.setParam<int16_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeUint32:\n        cf_.setParam<uint32_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeInt32:\n        cf_.setParam<int32_t>(entry->id, p.as_int());\n        break;\n      case Crazyflie::ParamTypeFloat:\n        if (p.get_type() == rclcpp::PARAMETER_INTEGER) {\n          cf_.setParam<float>(entry->id, (float)p.as_int());\n        } else {\n          cf_.setParam<float>(entry->id, p.as_double());\n        }\n\n        break;\n      }\n    } else {\n      RCLCPP_ERROR(logger_, \"[%s] Could not find param %s/%s\", name_.c_str(), group.c_str(), name.c_str());\n    }\n  }\n\nprivate:\n\n  void cmd_full_state_changed(const crazyflie_interfaces::msg::FullState::SharedPtr msg)\n  { \n    float x = msg->pose.position.x;\n    float y = msg->pose.position.y;\n    float z = msg->pose.position.z;\n    float vx = msg->twist.linear.x;\n    float vy = msg->twist.linear.y;\n    float vz = msg->twist.linear.z;\n    float ax = msg->acc.x;\n    float ay = msg->acc.y;\n    float az = msg->acc.z;\n\n    float qx = msg->pose.orientation.x;\n    float qy = msg->pose.orientation.y;\n    float qz = msg->pose.orientation.z;\n    float qw = msg->pose.orientation.w;\n    float rollRate = msg->twist.angular.x;\n    float pitchRate = msg->twist.angular.y;\n    float yawRate = msg->twist.angular.z;\n    cf_.sendFullStateSetpoint(\n    x, y, z,\n    vx, vy, vz,\n    ax, ay, az,\n    qx, qy, qz, qw,\n    rollRate, pitchRate, yawRate);\n\n  }\n\n  void cmd_position_changed(const crazyflie_interfaces::msg::Position::SharedPtr msg) {\n    float x = msg->x;\n    float y = msg->y;\n    float z = msg->z;\n    float yaw = msg->yaw;\n    cf_.sendPositionSetpoint(x, y, z, yaw);\n  }\n\n    void cmd_velocity_world_changed(const crazyflie_interfaces::msg::VelocityWorld::SharedPtr msg) {\n    float vx = msg->vel.x;\n    float vy = msg->vel.y;\n    float vz = msg->vel.z;\n    float yaw_rate = msg->yaw_rate;\n    cf_.sendVelocityWorldSetpoint(vx, vy, vz, yaw_rate);\n  }\n\n  void cmd_hover_changed(const crazyflie_interfaces::msg::Hover::SharedPtr msg) {\n    float vx = msg->vx;\n    float vy = msg->vy;\n    float yawRate = -1.0 * msg->yaw_rate * 180.0 / M_PI; // Convert from radians to degrees\n    float z = msg->z_distance;\n    cf_.sendHoverSetpoint(vx, vy, yawRate, z);\n  }\n\n  void cmd_vel_legacy_changed(const geometry_msgs::msg::Twist::SharedPtr msg)\n  {\n    float roll = msg->linear.y;\n    float pitch = - (msg->linear.x);\n    float yawrate = msg->angular.z;\n    uint16_t thrust = std::min<uint16_t>(std::max<float>(msg->linear.z, 0.0), 60000);\n    // RCLCPP_INFO(logger_, \"roll: %f, pitch: %f, yaw: %f, thrust: %u\", roll, pitch, yawrate, (unsigned int)thrust);\n    cf_.sendSetpoint(roll, pitch, yawrate, thrust);\n  }\n\n  void on_console(const char *msg)\n  {\n    message_buffer_ += msg;\n    size_t pos = message_buffer_.find('\\n');\n    if (pos != std::string::npos)\n    {\n      message_buffer_[pos] = 0;\n      RCLCPP_INFO(logger_, \"[%s] %s\", name_.c_str(), message_buffer_.c_str());\n      message_buffer_.erase(0, pos + 1);\n    }\n  }\n\n  void emergency(const std::shared_ptr<Empty::Request> request,\n            std::shared_ptr<Empty::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] emergency()\", name_.c_str());\n    cf_.emergencyStop();\n  }\n\n  void start_trajectory(const std::shared_ptr<StartTrajectory::Request> request,\n                        std::shared_ptr<StartTrajectory::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] start_trajectory(id=%d, timescale=%f, reversed=%d, relative=%d, group_mask=%d)\",\n      name_.c_str(),\n      request->trajectory_id,\n      request->timescale,\n      request->reversed,\n      request->relative,\n      request->group_mask);\n    cf_.startTrajectory(request->trajectory_id,\n      request->timescale,\n      request->reversed,\n      request->relative,\n      request->group_mask);\n  }\n\n  void takeoff(const std::shared_ptr<Takeoff::Request> request,\n               std::shared_ptr<Takeoff::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] takeoff(height=%f m, duration=%f s, group_mask=%d)\", \n                name_.c_str(),\n                request->height,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n    cf_.takeoff(request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask);\n  }\n\n  void land(const std::shared_ptr<Land::Request> request,\n            std::shared_ptr<Land::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] land(height=%f m, duration=%f s, group_mask=%d)\",\n                name_.c_str(),\n                request->height,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n    cf_.land(request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask);\n  }\n\n  void go_to(const std::shared_ptr<GoTo::Request> request,\n             std::shared_ptr<GoTo::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, relative=%d, group_mask=%d)\",\n                name_.c_str(),\n                request->goal.x, request->goal.y, request->goal.z, request->yaw,\n                rclcpp::Duration(request->duration).seconds(),\n                request->relative,\n                request->group_mask);\n    cf_.goTo(request->goal.x, request->goal.y, request->goal.z, request->yaw, \n              rclcpp::Duration(request->duration).seconds(),\n              request->relative, request->group_mask);\n  }\n\n  void upload_trajectory(const std::shared_ptr<UploadTrajectory::Request> request,\n                        std::shared_ptr<UploadTrajectory::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] upload_trajectory(id=%d, offset=%d)\",\n                name_.c_str(),\n                request->trajectory_id,\n                request->piece_offset);\n\n    std::vector<Crazyflie::poly4d> pieces(request->pieces.size());\n    for (size_t i = 0; i < pieces.size(); ++i)\n    {\n      if (   request->pieces[i].poly_x.size() != 8 \n          || request->pieces[i].poly_y.size() != 8\n          || request->pieces[i].poly_z.size() != 8\n          || request->pieces[i].poly_yaw.size() != 8)\n      {\n        RCLCPP_FATAL(logger_, \"[%s] Wrong number of pieces!\", name_.c_str());\n        return;\n      }\n      pieces[i].duration = rclcpp::Duration(request->pieces[i].duration).seconds();\n      for (size_t j = 0; j < 8; ++j)\n      {\n        pieces[i].p[0][j] = request->pieces[i].poly_x[j];\n        pieces[i].p[1][j] = request->pieces[i].poly_y[j];\n        pieces[i].p[2][j] = request->pieces[i].poly_z[j];\n        pieces[i].p[3][j] = request->pieces[i].poly_yaw[j];\n      }\n    }\n    cf_.uploadTrajectory(request->trajectory_id, request->piece_offset, pieces);\n  }\n\n  void notify_setpoints_stop(const std::shared_ptr<NotifySetpointsStop::Request> request,\n                         std::shared_ptr<NotifySetpointsStop::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)\",\n                name_.c_str(),\n                request->remain_valid_millisecs,\n                request->group_mask);\n\n    cf_.notifySetpointsStop(request->remain_valid_millisecs);\n  }\n\n  void arm(const std::shared_ptr<Arm::Request> request,\n                         std::shared_ptr<Arm::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[%s] arm(%d)\",\n                name_.c_str(),\n                request->arm);\n\n    cf_.sendArmingRequest(request->arm);\n  }\n\n  void on_logging_pose(uint32_t time_in_ms, const logPose* data) {\n    if (publisher_pose_) {\n      geometry_msgs::msg::PoseStamped msg;\n      msg.header.stamp = node_->get_clock()->now();\n      msg.header.frame_id = reference_frame_;\n\n      msg.pose.position.x = data->x;\n      msg.pose.position.y = data->y;\n      msg.pose.position.z = data->z;\n\n      float q[4];\n      quatdecompress(data->quatCompressed, q);\n      msg.pose.orientation.x = q[0];\n      msg.pose.orientation.y = q[1];\n      msg.pose.orientation.z = q[2];\n      msg.pose.orientation.w = q[3];\n\n      publisher_pose_->publish(msg);\n\n      // send a transform for this pose\n      geometry_msgs::msg::TransformStamped msg2;\n      msg2.header = msg.header;\n      msg2.child_frame_id = name_;\n      msg2.transform.translation.x = data->x;\n      msg2.transform.translation.y = data->y;\n      msg2.transform.translation.z = data->z;\n      msg2.transform.rotation.x = q[0];\n      msg2.transform.rotation.y = q[1];\n      msg2.transform.rotation.z = q[2];\n      msg2.transform.rotation.w = q[3];\n      tf_broadcaster_.sendTransform(msg2);\n    }\n  }\n\n  void on_logging_scan(uint32_t time_in_ms, const logScan* data) {\n    if (publisher_scan_) {\n      \n      const float max_range = 3.49;\n      float front_range = data->front / 1000.0f;\n      if (front_range > max_range) front_range = std::numeric_limits<float>::infinity();\n      float left_range = data->left / 1000.0f;\n      if (left_range > max_range) left_range = std::numeric_limits<float>::infinity();\n      float back_range = data->back / 1000.0f;\n      if (back_range > max_range) back_range = std::numeric_limits<float>::infinity();\n      float right_range = data->right / 1000.0f;\n      if (right_range > max_range) right_range = std::numeric_limits<float>::infinity();\n\n      sensor_msgs::msg::LaserScan msg;\n      msg.header.stamp = node_->get_clock()->now();\n      msg.header.frame_id = name_;\n      msg.range_min = 0.01;\n      msg.range_max = max_range;\n      msg.ranges.push_back(back_range);\n      msg.ranges.push_back(right_range);\n      msg.ranges.push_back(front_range);\n      msg.ranges.push_back(left_range);\n      msg.angle_min = -0.5 * 2 * M_PI;\n      msg.angle_max = 0.25 * 2 * M_PI;\n      msg.angle_increment = 1.0 * M_PI / 2;\n\n      publisher_scan_->publish(msg);\n    }\n  }\n\n  void on_logging_odom(uint32_t time_in_ms, const logOdom* data) {\n    if (publisher_odom_) {\n      nav_msgs::msg::Odometry msg;\n      msg.header.stamp = node_->get_clock()->now();\n      msg.header.frame_id = name_;\n      msg.pose.pose.position.x = data->x / 1000.0f;\n      msg.pose.pose.position.y = data->y / 1000.0f;\n      msg.pose.pose.position.z = data->z / 1000.0f;\n\n      float q[4];\n      quatdecompress(data->quatCompressed, q);\n      msg.pose.pose.orientation.x = q[0];\n      msg.pose.pose.orientation.y = q[1];\n      msg.pose.pose.orientation.z = q[2];\n      msg.pose.pose.orientation.w = q[3];\n\n      msg.twist.twist.linear.x = data->vx / 1000.0f;\n      msg.twist.twist.linear.y = data->vy / 1000.0f;\n      msg.twist.twist.linear.z = data->vz / 1000.0f;\n      //msg.twist.twist.angular.x = data->rateRoll / 1000.0f;\n      //msg.twist.twist.angular.y = data->ratePitch / 1000.0f;\n      //msg.twist.twist.angular.z = data->rateYaw / 1000.0f;\n\n      publisher_odom_->publish(msg);\n    }\n\n  }\n\n  void on_logging_status(uint32_t time_in_ms, const logStatus* data) {\n    if (publisher_status_) {\n      \n      crazyflie_interfaces::msg::Status msg;\n      msg.header.stamp = node_->get_clock()->now();\n      msg.header.frame_id = name_;\n      msg.supervisor_info = data->supervisorInfo;\n      msg.battery_voltage = data->vbatMV / 1000.0f;\n      msg.pm_state = data->pmState;\n      msg.rssi = data->rssi;\n      if (status_has_radio_stats_) {\n        int32_t deltaRxBc = data->numRxBc - previous_numRxBc;\n        int32_t deltaRxUc = data->numRxUc - previous_numRxUc;\n        // handle overflow\n        if (deltaRxBc < 0) {\n          deltaRxBc += std::numeric_limits<uint16_t>::max();\n        }\n        if (deltaRxUc < 0) {\n          deltaRxUc += std::numeric_limits<uint16_t>::max();\n        }\n        msg.num_rx_broadcast = deltaRxBc;\n        msg.num_rx_unicast = deltaRxUc;\n        previous_numRxBc = data->numRxBc;\n        previous_numRxUc = data->numRxUc;\n      } else {\n        msg.num_rx_broadcast = 0;\n        msg.num_rx_unicast = 0;\n      }\n\n      // connection sent stats (unicast)\n      const auto statsUc = cf_.connectionStats();\n      size_t deltaTxUc = statsUc.sent_count - previous_stats_unicast_.sent_count;\n      msg.num_tx_unicast = deltaTxUc;\n      previous_stats_unicast_ = statsUc;\n\n      // connection sent stats (broadcast)\n      const auto statsBc = cfbc_->connectionStats();\n      size_t deltaTxBc = statsBc.sent_count - previous_stats_broadcast_.sent_count;\n      msg.num_tx_broadcast = deltaTxBc;\n      previous_stats_broadcast_ = statsBc;\n\n      msg.latency_unicast = last_latency_in_ms_;\n\n      publisher_status_->publish(msg);\n\n      // warnings\n      if (msg.num_rx_unicast > msg.num_tx_unicast * 1.05 /*allow some slack*/) {\n        RCLCPP_WARN(logger_, \"[%s] Unexpected number of unicast packets. Sent: %d. Received: %d\", name_.c_str(), msg.num_tx_unicast, msg.num_rx_unicast);\n      }\n      if (msg.num_tx_unicast > 0) {\n        float unicast_receive_rate = msg.num_rx_unicast / (float)msg.num_tx_unicast;\n        if (unicast_receive_rate < min_unicast_receive_rate_) {\n          RCLCPP_WARN(logger_, \"[%s] Low unicast receive rate (%.2f < %.2f). Sent: %d. Received: %d\", name_.c_str(), unicast_receive_rate, min_unicast_receive_rate_, msg.num_tx_unicast, msg.num_rx_unicast);\n        }\n      }\n\n      if (msg.num_rx_broadcast > msg.num_tx_broadcast * 1.05 /*allow some slack*/) {\n        RCLCPP_WARN(logger_, \"[%s] Unexpected number of broadcast packets. Sent: %d. Received: %d\", name_.c_str(), msg.num_tx_broadcast, msg.num_rx_broadcast);\n      }\n      if (msg.num_tx_broadcast > 0) {\n        float broadcast_receive_rate = msg.num_rx_broadcast / (float)msg.num_tx_broadcast;\n        if (broadcast_receive_rate < min_broadcast_receive_rate_) {\n          RCLCPP_WARN(logger_, \"[%s] Low broadcast receive rate (%.2f < %.2f). Sent: %d. Received: %d\", name_.c_str(), broadcast_receive_rate, min_broadcast_receive_rate_, msg.num_tx_broadcast, msg.num_rx_broadcast);\n        }\n      }\n    }\n  }\n\n  void on_logging_custom(uint32_t time_in_ms, const std::vector<float>* values, void* userData) {\n\n    auto pub = reinterpret_cast<rclcpp::Publisher<crazyflie_interfaces::msg::LogDataGeneric>::SharedPtr*>(userData);\n\n    crazyflie_interfaces::msg::LogDataGeneric msg;\n    msg.header.stamp = node_->get_clock()->now();\n    msg.header.frame_id = reference_frame_;\n    msg.timestamp = time_in_ms;\n    msg.values = *values;\n\n    (*pub)->publish(msg);\n  }\n\n  void on_link_statistics_timer()\n  {\n    cf_.triggerLatencyMeasurement();\n\n    auto now = std::chrono::steady_clock::now();\n    std::chrono::duration<double> elapsed = now - last_on_latency_;\n    if (elapsed.count() > 1.0 / warning_freq_) {\n      RCLCPP_WARN(logger_, \"[%s] last latency update: %f s\", name_.c_str(), elapsed.count());\n    }\n\n    auto stats = cf_.connectionStatsDelta();\n\n    if (stats.ack_count > 0) {\n      float ack_rate = stats.sent_count / stats.ack_count;\n      if (ack_rate < min_ack_rate_) {\n        RCLCPP_WARN(logger_, \"[%s] Ack rate: %.1f %%\", name_.c_str(), ack_rate * 100);\n      }\n    }\n\n    if (publish_stats_) {\n      crazyflie_interfaces::msg::ConnectionStatisticsArray msg;\n      msg.header.stamp = node_->get_clock()->now();\n      msg.header.frame_id = reference_frame_;\n      msg.stats.resize(1);\n\n      msg.stats[0].uri = cf_.uri();\n      msg.stats[0].sent_count = stats.sent_count;\n      msg.stats[0].sent_ping_count = stats.sent_ping_count;\n      msg.stats[0].receive_count = stats.receive_count;\n      msg.stats[0].enqueued_count = stats.enqueued_count;\n      msg.stats[0].ack_count = stats.ack_count;\n\n      publisher_connection_stats_->publish(msg);\n    }\n  }\n\n  void on_latency(uint64_t latency_in_us)\n  {\n    if (latency_in_us / 1000.0 > max_latency_) {\n      RCLCPP_WARN(logger_, \"[%s] High latency: %.1f ms\", name_.c_str(), latency_in_us / 1000.0);\n    }\n    last_on_latency_ = std::chrono::steady_clock::now();\n    last_latency_in_ms_ = (uint16_t)(latency_in_us / 1000.0);\n  }\n\nprivate:\n  rclcpp::Logger logger_;\n  CrazyflieLogger cf_logger_;\n\n  Crazyflie cf_;\n  std::string message_buffer_;\n  std::string name_;\n\n  rclcpp::Node* node_;\n  tf2_ros::TransformBroadcaster tf_broadcaster_;\n\n  rclcpp::Service<Empty>::SharedPtr service_emergency_;\n  rclcpp::Service<StartTrajectory>::SharedPtr service_start_trajectory_;\n  rclcpp::Service<Takeoff>::SharedPtr service_takeoff_;\n  rclcpp::Service<Land>::SharedPtr service_land_;\n  rclcpp::Service<GoTo>::SharedPtr service_go_to_;\n  rclcpp::Service<UploadTrajectory>::SharedPtr service_upload_trajectory_;\n  rclcpp::Service<NotifySetpointsStop>::SharedPtr service_notify_setpoints_stop_;\n  rclcpp::Service<Arm>::SharedPtr service_arm_;\n\n  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_cmd_vel_legacy_;\n  rclcpp::Subscription<crazyflie_interfaces::msg::FullState>::SharedPtr subscription_cmd_full_state_;\n  rclcpp::Subscription<crazyflie_interfaces::msg::Position>::SharedPtr subscription_cmd_position_;\n  rclcpp::Subscription<crazyflie_interfaces::msg::VelocityWorld>::SharedPtr subscription_cmd_velocity_world_;\n  rclcpp::Subscription<crazyflie_interfaces::msg::Hover>::SharedPtr subscription_cmd_hover_;\n\n  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_robot_description_;\n\n  // logging\n  std::string reference_frame_;\n\n  std::unique_ptr<LogBlock<logPose>> log_block_pose_;\n  rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr publisher_pose_;\n\n  std::unique_ptr<LogBlock<logScan>> log_block_scan_;\n  rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr publisher_scan_;\n\n  std::unique_ptr<LogBlock<logOdom>> log_block_odom_;\n  rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr publisher_odom_;\n\n  std::unique_ptr<LogBlock<logStatus>> log_block_status_;\n  bool status_has_radio_stats_;\n  rclcpp::Publisher<crazyflie_interfaces::msg::Status>::SharedPtr publisher_status_;\n  uint16_t previous_numRxBc;\n  uint16_t previous_numRxUc;\n  bitcraze::crazyflieLinkCpp::Connection::Statistics previous_stats_unicast_;\n  bitcraze::crazyflieLinkCpp::Connection::Statistics previous_stats_broadcast_;\n  const CrazyflieBroadcaster* cfbc_;\n\n  std::list<std::unique_ptr<LogBlockGeneric>> log_blocks_generic_;\n  std::list<rclcpp::Publisher<crazyflie_interfaces::msg::LogDataGeneric>::SharedPtr> publishers_generic_;\n\n  // multithreading\n  rclcpp::CallbackGroup::SharedPtr callback_group_cf_;\n  rclcpp::TimerBase::SharedPtr spin_timer_;\n\n  // link statistics\n  rclcpp::TimerBase::SharedPtr link_statistics_timer_;\n  std::chrono::time_point<std::chrono::steady_clock> last_on_latency_;\n  uint16_t last_latency_in_ms_;\n  float warning_freq_;\n  float max_latency_;\n  float min_ack_rate_;\n  float min_unicast_receive_rate_;\n  float min_broadcast_receive_rate_;\n  bool publish_stats_;\n  rclcpp::Publisher<crazyflie_interfaces::msg::ConnectionStatisticsArray>::SharedPtr publisher_connection_stats_;\n};\n\nclass CrazyflieServer : public rclcpp::Node\n{\npublic:\n  CrazyflieServer()\n      : Node(\"crazyflie_server\")\n      , logger_(get_logger())\n  {\n    // Create callback groups (each group can run in a separate thread)\n    callback_group_mocap_ = this->create_callback_group(\n      rclcpp::CallbackGroupType::MutuallyExclusive);\n    auto sub_opt_mocap = rclcpp::SubscriptionOptions();\n    sub_opt_mocap.callback_group = callback_group_mocap_;\n\n    callback_group_all_cmd_ = this->create_callback_group(\n      rclcpp::CallbackGroupType::MutuallyExclusive);\n    auto sub_opt_all_cmd = rclcpp::SubscriptionOptions();\n    sub_opt_all_cmd.callback_group = callback_group_all_cmd_;\n\n    callback_group_all_srv_ = this->create_callback_group(\n      rclcpp::CallbackGroupType::MutuallyExclusive);\n\n    callback_group_cf_cmd_ = this->create_callback_group(\n      rclcpp::CallbackGroupType::MutuallyExclusive);\n\n    callback_group_cf_srv_ = this->create_callback_group(\n      rclcpp::CallbackGroupType::MutuallyExclusive);\n\n    // declare global params\n    this->declare_parameter(\"all.broadcasts.num_repeats\", 15);\n    this->declare_parameter(\"all.broadcasts.delay_between_repeats_ms\", 1);\n    this->declare_parameter(\"firmware_params.query_all_values_on_connect\", false);\n\n    broadcasts_num_repeats_ = this->get_parameter(\"all.broadcasts.num_repeats\").get_parameter_value().get<int>();\n    broadcasts_delay_between_repeats_ms_ = this->get_parameter(\"all.broadcasts.delay_between_repeats_ms\").get_parameter_value().get<int>();\n    mocap_enabled_ = false;\n\n    this->declare_parameter(\"robot_description\", \"\");\n\n    // Warnings\n    this->declare_parameter(\"warnings.frequency\", 1.0);\n    float freq = this->get_parameter(\"warnings.frequency\").get_parameter_value().get<float>();\n    if (freq >= 0.0) {\n      watchdog_timer_ = this->create_wall_timer(std::chrono::milliseconds((int)(1000.0/freq)), std::bind(&CrazyflieServer::on_watchdog_timer, this), callback_group_all_srv_);\n    }\n    this->declare_parameter(\"warnings.motion_capture.warning_if_rate_outside\", std::vector<double>({80.0, 120.0}));\n    auto rate_range = this->get_parameter(\"warnings.motion_capture.warning_if_rate_outside\").get_parameter_value().get<std::vector<double>>();\n    mocap_min_rate_ = rate_range[0];\n    mocap_max_rate_ = rate_range[1];\n\n    this->declare_parameter(\"warnings.communication.max_unicast_latency\", 10.0);\n    this->declare_parameter(\"warnings.communication.min_unicast_ack_rate\", 0.9);\n    this->declare_parameter(\"warnings.communication.min_unicast_receive_rate\", 0.9);\n    this->declare_parameter(\"warnings.communication.min_broadcast_receive_rate\", 0.9);\n    this->declare_parameter(\"warnings.communication.publish_stats\", false);\n\n    publish_stats_ = this->get_parameter(\"warnings.communication.publish_stats\").get_parameter_value().get<bool>();\n    if (publish_stats_) {\n      publisher_connection_stats_ = this->create_publisher<crazyflie_interfaces::msg::ConnectionStatisticsArray>(\"all/connection_statistics\", 10);\n    }\n\n    // load crazyflies from params\n    auto node_parameters_iface = this->get_node_parameters_interface();\n    const std::map<std::string, rclcpp::ParameterValue> &parameter_overrides =\n        node_parameters_iface->get_parameter_overrides();\n\n    auto cf_names = extract_names(parameter_overrides, \"robots\");\n    for (const auto &name : cf_names) {\n      bool enabled = parameter_overrides.at(\"robots.\" + name + \".enabled\").get<bool>();\n      if (enabled) {\n        // Lookup type\n        std::string cf_type = parameter_overrides.at(\"robots.\" + name + \".type\").get<std::string>();\n        // Find the connection setting for the given type\n        const auto con = parameter_overrides.find(\"robot_types.\" + cf_type + \".connection\");\n        std::string constr = \"crazyflie\";\n        if (con != parameter_overrides.end()) {\n          constr = con->second.get<std::string>();\n        }\n        // Find the mocap setting\n        const auto mocap_en = parameter_overrides.find(\"robot_types.\" + cf_type + \".motion_capture.enabled\");\n        if (mocap_en != parameter_overrides.end()) {\n          if (mocap_en->second.get<bool>()) {\n            mocap_enabled_ = true;\n          }\n        }\n\n        // if it is a Crazyflie, try to connect\n        if (constr == \"crazyflie\") {\n          std::string uri = parameter_overrides.at(\"robots.\" + name + \".uri\").get<std::string>();\n          auto broadcastUri = Crazyflie::broadcastUriFromUnicastUri(uri);\n          if (broadcaster_.count(broadcastUri) == 0) {\n            broadcaster_.emplace(broadcastUri, std::make_unique<CrazyflieBroadcaster>(broadcastUri));\n          }\n\n          crazyflies_.emplace(name, std::make_unique<CrazyflieROS>(\n            uri,\n            cf_type,\n            name,\n            this,\n            callback_group_cf_cmd_,\n            callback_group_cf_srv_,\n            broadcaster_.at(broadcastUri).get()));\n\n          update_name_to_id_map(name, crazyflies_[name]->id());\n        }\n        else if (constr == \"none\") {\n          // we still might want to track this object, so update our map\n          uint8_t id = parameter_overrides.at(\"robots.\" + name + \".id\").get<uint8_t>();\n          update_name_to_id_map(name, id);\n        } else {\n          RCLCPP_INFO(logger_, \"[all] Unknown connection type %s\", constr.c_str());\n        }\n      }\n    }\n\n    this->declare_parameter(\"poses_qos_deadline\", 100.0f);\n    double poses_qos_deadline = this->get_parameter(\"poses_qos_deadline\").get_parameter_value().get<double>();\n\n    rclcpp::SensorDataQoS sensor_data_qos;\n    sensor_data_qos.keep_last(1);\n    sensor_data_qos.deadline(rclcpp::Duration(0/*s*/, 1e9/poses_qos_deadline /*ns*/));\n    sub_poses_ = this->create_subscription<NamedPoseArray>(\n        \"poses\", sensor_data_qos, std::bind(&CrazyflieServer::posesChanged, this, _1), sub_opt_mocap);\n\n    // support for all.params\n\n    // Create a parameter subscriber that can be used to monitor parameter changes\n    param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);\n    cb_handle_ = param_subscriber_->add_parameter_event_callback(std::bind(&CrazyflieServer::on_parameter_event, this, _1));\n\n    // topics for \"all\"\n    subscription_cmd_full_state_ = this->create_subscription<crazyflie_interfaces::msg::FullState>(\"all/cmd_full_state\", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieServer::cmd_full_state_changed, this, _1), sub_opt_all_cmd);\n\n    // services for \"all\"\n    service_start_trajectory_ = this->create_service<StartTrajectory>(\"all/start_trajectory\", std::bind(&CrazyflieServer::start_trajectory, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n    service_takeoff_ = this->create_service<Takeoff>(\"all/takeoff\", std::bind(&CrazyflieServer::takeoff, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n    service_land_ = this->create_service<Land>(\"all/land\", std::bind(&CrazyflieServer::land, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n    service_go_to_ = this->create_service<GoTo>(\"all/go_to\", std::bind(&CrazyflieServer::go_to, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n    service_notify_setpoints_stop_ = this->create_service<NotifySetpointsStop>(\"all/notify_setpoints_stop\", std::bind(&CrazyflieServer::notify_setpoints_stop, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n    service_arm_ = this->create_service<Arm>(\"all/arm\", std::bind(&CrazyflieServer::arm, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n\n    // This is the last service to announce and can be used to check if the server is fully available\n    service_emergency_ = this->create_service<Empty>(\"all/emergency\", std::bind(&CrazyflieServer::emergency, this, _1, _2), get_service_qos(), callback_group_all_srv_);\n  }\n\n\nprivate:\n  void emergency(const std::shared_ptr<Empty::Request> request,\n            std::shared_ptr<Empty::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] emergency()\");\n    for (int i = 0; i < broadcasts_num_repeats_; ++i)\n    {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->emergencyStop();\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void start_trajectory(const std::shared_ptr<StartTrajectory::Request> request,\n            std::shared_ptr<StartTrajectory::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] start_trajectory(id=%d, timescale=%f, reversed=%d, group_mask=%d)\",\n                request->trajectory_id,\n                request->timescale,\n                request->reversed,\n                request->group_mask);\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->startTrajectory(request->trajectory_id,\n                            request->timescale,\n                            request->reversed,\n                            request->group_mask);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void takeoff(const std::shared_ptr<Takeoff::Request> request,\n                        std::shared_ptr<Takeoff::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] takeoff(height=%f m, duration=%f s, group_mask=%d)\",\n                request->height,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto& bc : broadcaster_) {\n        auto& cfbc = bc.second;\n        cfbc->takeoff(request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void land(const std::shared_ptr<Land::Request> request,\n           std::shared_ptr<Land::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] land(height=%f m, duration=%f s, group_mask=%d)\",\n                request->height,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto& bc : broadcaster_) {\n        auto& cfbc = bc.second;\n        cfbc->land(request->height, rclcpp::Duration(request->duration).seconds(), request->group_mask);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void go_to(const std::shared_ptr<GoTo::Request> request,\n            std::shared_ptr<GoTo::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] go_to(position=%f,%f,%f m, yaw=%f rad, duration=%f s, group_mask=%d)\",\n                request->goal.x, request->goal.y, request->goal.z, request->yaw,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->goTo(request->goal.x, request->goal.y, request->goal.z, request->yaw,\n                rclcpp::Duration(request->duration).seconds(),\n                request->group_mask);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void notify_setpoints_stop(const std::shared_ptr<NotifySetpointsStop::Request> request,\n                         std::shared_ptr<NotifySetpointsStop::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] notify_setpoints_stop(remain_valid_millisecs%d, group_mask=%d)\",\n                request->remain_valid_millisecs,\n                request->group_mask);\n\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->notifySetpointsStop(request->remain_valid_millisecs);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void arm(const std::shared_ptr<Arm::Request> request,\n                         std::shared_ptr<Arm::Response> response)\n  {\n    RCLCPP_INFO(logger_, \"[all] arm(%d)\",\n                request->arm);\n\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->sendArmingRequest(request->arm);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void cmd_full_state_changed(const crazyflie_interfaces::msg::FullState::SharedPtr msg)\n  { \n    float x = msg->pose.position.x;\n    float y = msg->pose.position.y;\n    float z = msg->pose.position.z;\n    float vx = msg->twist.linear.x;\n    float vy = msg->twist.linear.y;\n    float vz = msg->twist.linear.z;\n    float ax = msg->acc.x;\n    float ay = msg->acc.y;\n    float az = msg->acc.z;\n\n    float qx = msg->pose.orientation.x;\n    float qy = msg->pose.orientation.y;\n    float qz = msg->pose.orientation.z;\n    float qw = msg->pose.orientation.w;\n    float rollRate = msg->twist.angular.x;\n    float pitchRate = msg->twist.angular.y;\n    float yawRate = msg->twist.angular.z;\n\n    for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->sendFullStateSetpoint(\n          x, y, z,\n          vx, vy, vz,\n          ax, ay, az,\n          qx, qy, qz, qw,\n          rollRate, pitchRate, yawRate);\n    }\n\n  }\n\n  void posesChanged(const NamedPoseArray::SharedPtr msg)\n  {\n    mocap_data_received_timepoints_.emplace_back(std::chrono::steady_clock::now());\n\n    // Here, we send all the poses to all CFs\n    // In Crazyswarm1, we only sent the poses of the same group (i.e. channel)\n\n\n    // split the message into parts that require position update and pose update\n    std::vector<CrazyflieBroadcaster::externalPosition> data_position;\n    std::vector<CrazyflieBroadcaster::externalPose> data_pose;\n\n    for (const auto& pose : msg->poses) {\n      const auto iter = name_to_id_.find(pose.name);\n      if (iter != name_to_id_.end()) {\n        uint8_t id = iter->second;\n        if (isnan(pose.pose.orientation.w)) {\n          data_position.push_back({id, \n            (float)pose.pose.position.x, (float)pose.pose.position.y, (float)pose.pose.position.z});\n        } else {\n          data_pose.push_back({id, \n            (float)pose.pose.position.x, (float)pose.pose.position.y, (float)pose.pose.position.z,\n            (float)pose.pose.orientation.x, (float)pose.pose.orientation.y, (float)pose.pose.orientation.z, (float)pose.pose.orientation.w});\n        }\n      }\n    }\n\n    // send position only updates to the swarm\n    if (data_position.size() > 0) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->sendExternalPositions(data_position);\n      }\n    }\n\n    // send pose only updates to the swarm\n    if (data_pose.size() > 0) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->sendExternalPoses(data_pose);\n      }\n    }\n  }\n\n  void on_parameter_event(const rcl_interfaces::msg::ParameterEvent &event)\n  {\n    if (event.node == \"/crazyflie_server\") {\n      auto params = param_subscriber_->get_parameters_from_event(event);\n      for (auto &p : params) {\n        size_t params_pos = p.get_name().find(\".params.\");\n        if (params_pos == std::string::npos) {\n          continue;\n        }\n        std::string cfname(p.get_name().begin(), p.get_name().begin() + params_pos);\n        size_t prefixsize = params_pos + 8;\n        if (cfname == \"all\") {\n          size_t pos = p.get_name().find(\".\", prefixsize);\n          std::string group(p.get_name().begin() + prefixsize, p.get_name().begin() + pos);\n          std::string name(p.get_name().begin() + pos + 1, p.get_name().end());\n\n          RCLCPP_INFO(\n              logger_,\n              \"[all] Update parameter \\\"%s.%s\\\" to %s\",\n              group.c_str(),\n              name.c_str(),\n              p.value_to_string().c_str());\n\n          Crazyflie::ParamType paramType;\n          for (auto& cf : crazyflies_) {\n            const auto entry = cf.second->paramTocEntry(group, name);\n            if (entry) {\n              switch (entry->type)\n              {\n              case Crazyflie::ParamTypeUint8:\n                broadcast_set_param<uint8_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeInt8:\n                broadcast_set_param<int8_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeUint16:\n                broadcast_set_param<uint16_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeInt16:\n                broadcast_set_param<int16_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeUint32:\n                broadcast_set_param<uint32_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeInt32:\n                broadcast_set_param<int32_t>(group, name, p.as_int());\n                break;\n              case Crazyflie::ParamTypeFloat:\n                if (p.get_type() == rclcpp::PARAMETER_INTEGER) {\n                  broadcast_set_param<float>(group, name, (float)p.as_int());\n                } else {\n                  broadcast_set_param<float>(group, name, p.as_double());\n                }\n                break;\n              }\n              break;\n            }\n          }\n        } else {\n          auto iter = crazyflies_.find(cfname);\n          if (iter != crazyflies_.end()) {\n            iter->second->change_parameter(p);\n          }\n        }\n      }\n    }\n  }\n\n  void on_watchdog_timer()\n  {\n    auto now = std::chrono::steady_clock::now();\n\n    // motion capture\n    // a) check if the rate was within specified bounds\n    if (mocap_data_received_timepoints_.size() >= 2) {\n      double mean_rate = 0;\n      double min_rate = std::numeric_limits<double>::max();\n      double max_rate = 0;\n      int num_rates_wrong = 0;\n      for (size_t i = 0; i < mocap_data_received_timepoints_.size() - 1; ++i) {\n        std::chrono::duration<double> diff = mocap_data_received_timepoints_[i+1] - mocap_data_received_timepoints_[i];\n        double rate = 1.0 / diff.count();\n        mean_rate += rate;\n        min_rate = std::min(min_rate, rate);\n        max_rate = std::max(max_rate, rate);\n        if (rate <= mocap_min_rate_ || rate >= mocap_max_rate_) {\n          num_rates_wrong++;\n        }\n      }\n      mean_rate /= (mocap_data_received_timepoints_.size() - 1);\n\n      if (num_rates_wrong > 0) {\n        RCLCPP_WARN(logger_, \"[all] Motion capture rate off (#: %d, Avg: %.1f, Min: %.1f, Max: %.1f)\", num_rates_wrong, mean_rate, min_rate, max_rate);\n      }\n    } else if (mocap_enabled_) {\n      // b) warn if no data was received\n      RCLCPP_WARN(logger_, \"[all] Motion capture did not receive data!\");\n    }\n\n    mocap_data_received_timepoints_.clear();\n\n    if (publish_stats_) {\n\n      crazyflie_interfaces::msg::ConnectionStatisticsArray msg;\n      msg.header.stamp = this->get_clock()->now();\n      msg.header.frame_id = \"world\"; // this is across broadcasters, which is not directly associated with single CFs; hence keep \"world\" here\n      msg.stats.resize(broadcaster_.size());\n\n      size_t i = 0;\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n\n        auto stats = cfbc->connectionStatsDelta();\n\n        msg.stats[i].uri = cfbc->uri();\n        msg.stats[i].sent_count = stats.sent_count;\n        msg.stats[i].sent_ping_count = stats.sent_ping_count;\n        msg.stats[i].receive_count = stats.receive_count;\n        msg.stats[i].enqueued_count = stats.enqueued_count;\n        msg.stats[i].ack_count = stats.ack_count;\n        ++i;\n      }\n      publisher_connection_stats_->publish(msg);\n    }\n  }\n\n  template<class T>\n  void broadcast_set_param(\n    const std::string& group,\n    const std::string& name,\n    const T& value)\n  {\n    for (int i = 0; i < broadcasts_num_repeats_; ++i) {\n      for (auto &bc : broadcaster_) {\n        auto &cfbc = bc.second;\n        cfbc->setParam<T>(group.c_str(), name.c_str(), value);\n      }\n      std::this_thread::sleep_for(std::chrono::milliseconds(broadcasts_delay_between_repeats_ms_));\n    }\n  }\n\n  void update_name_to_id_map(const std::string& name, uint8_t id)\n  {\n    const auto iter = name_to_id_.find(name);\n    if (iter != name_to_id_.end()) {\n      RCLCPP_WARN(logger_, \"[all] At least two objects with the same id (%d, %s, %s)\", id, name.c_str(), iter->first.c_str());\n    } else {\n      name_to_id_.insert(std::make_pair(name, id));\n    }\n  }\n\n  private:\n    rclcpp::Logger logger_;\n\n    // subscribers\n    rclcpp::Subscription<crazyflie_interfaces::msg::FullState>::SharedPtr subscription_cmd_full_state_;\n    rclcpp::Subscription<NamedPoseArray>::SharedPtr sub_poses_;\n\n    // services\n    rclcpp::Service<Empty>::SharedPtr service_emergency_;\n    rclcpp::Service<StartTrajectory>::SharedPtr service_start_trajectory_;\n    rclcpp::Service<Takeoff>::SharedPtr service_takeoff_;\n    rclcpp::Service<Land>::SharedPtr service_land_;\n    rclcpp::Service<GoTo>::SharedPtr service_go_to_;\n    rclcpp::Service<NotifySetpointsStop>::SharedPtr service_notify_setpoints_stop_;\n    rclcpp::Service<Arm>::SharedPtr service_arm_;\n\n    std::map<std::string, std::unique_ptr<CrazyflieROS>> crazyflies_;\n\n\n\n    // broadcastUri -> broadcast object\n    std::map<std::string, std::unique_ptr<CrazyflieBroadcaster>> broadcaster_;\n\n    // maps CF name -> CF id\n    std::map<std::string, uint8_t> name_to_id_;\n\n    // global params\n    int broadcasts_num_repeats_;\n    int broadcasts_delay_between_repeats_ms_;\n\n    // parameter updates\n    std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;\n    std::shared_ptr<rclcpp::ParameterEventCallbackHandle> cb_handle_;\n\n    // sanity checks\n    rclcpp::TimerBase::SharedPtr watchdog_timer_;\n    bool mocap_enabled_;\n    float mocap_min_rate_;\n    float mocap_max_rate_;\n    std::vector<std::chrono::time_point<std::chrono::steady_clock>> mocap_data_received_timepoints_;\n    bool publish_stats_;\n    rclcpp::Publisher<crazyflie_interfaces::msg::ConnectionStatisticsArray>::SharedPtr publisher_connection_stats_;\n\n    // multithreading\n    rclcpp::CallbackGroup::SharedPtr callback_group_mocap_;\n    rclcpp::CallbackGroup::SharedPtr callback_group_all_cmd_;\n    rclcpp::CallbackGroup::SharedPtr callback_group_all_srv_;\n    rclcpp::CallbackGroup::SharedPtr callback_group_cf_cmd_;\n    rclcpp::CallbackGroup::SharedPtr callback_group_cf_srv_;\n  };\n\nint main(int argc, char *argv[])\n{\n  rclcpp::init(argc, argv);\n\n\n  auto node = std::make_shared<CrazyflieServer>();\n\n  rclcpp::executors::MultiThreadedExecutor executor;\n  executor.add_node(node);\n  executor.spin();\n\n  rclcpp::shutdown();\n  return 0;\n}\n"
  },
  {
    "path": "crazyflie/src/teleop.cpp",
    "content": "#include <memory>\n#include <vector>\n#include <chrono>\n#include <math.h>\n#include \"rclcpp/rclcpp.hpp\"\n#include \"sensor_msgs/msg/joy.hpp\"\n#include \"std_srvs/srv/empty.hpp\"\n#include \"crazyflie_interfaces/srv/takeoff.hpp\"\n#include \"crazyflie_interfaces/srv/land.hpp\"\n#include \"crazyflie_interfaces/srv/arm.hpp\"\n#include <crazyflie_interfaces/srv/notify_setpoints_stop.hpp>\n#include \"geometry_msgs/msg/twist.hpp\"\n#include \"crazyflie_interfaces/msg/full_state.hpp\"\n\n\n#include <Eigen/Geometry>\n\nusing std::placeholders::_1;\n\nusing std_srvs::srv::Empty;\nusing crazyflie_interfaces::srv::Takeoff;\nusing crazyflie_interfaces::srv::Land;\nusing crazyflie_interfaces::srv::Arm;\nusing crazyflie_interfaces::srv::NotifySetpointsStop;\nusing crazyflie_interfaces::msg::FullState;\n\nusing namespace std::chrono_literals;\nusing namespace Eigen;\n\nclass TeleopNode : public rclcpp::Node\n{\npublic:\n    TeleopNode()\n        : Node(\"teleop\")\n    {\n        \n        subscription_ = this->create_subscription<sensor_msgs::msg::Joy>(\n            \"joy\", 1, std::bind(&TeleopNode::joyChanged, this, _1));\n\n        pub_cmd_vel_legacy_ = this->create_publisher<geometry_msgs::msg::Twist>(\"cmd_vel_legacy\", 10);\n        pub_cmd_full_state_ = this->create_publisher<crazyflie_interfaces::msg::FullState>(\"cmd_full_state\", 10);\n\n        this->declare_parameter(\"frequency\", 0);\n        this->get_parameter<int>(\"frequency\", frequency_);\n        this->declare_parameter(\"mode\", \"high_level\");\n        this->get_parameter<std::string>(\"mode\", mode_);\n        this->declare_parameter(\"auto_yaw_rate\", 0.0);\n        this->get_parameter<double>(\"auto_yaw_rate\", auto_yaw_rate_);\n\n        this->declare_parameter<float>(\"initial_position.x\");\n        this->get_parameter<float>(\"initial_position.x\", state_.x);\n        this->declare_parameter<float>(\"initial_position.y\");\n        this->get_parameter<float>(\"initial_position.y\", state_.y);\n        this->declare_parameter<float>(\"initial_position.z\");\n        this->get_parameter<float>(\"initial_position.z\", state_.z);\n\n        // declare cmd_rpy params\n        declareAxis(\"cmd_rpy.roll\");\n        declareAxis(\"cmd_rpy.pitch\");\n        declareAxis(\"cmd_rpy.yawrate\");\n        declareAxis(\"cmd_rpy.thrust\");\n\n        // declare cmd_vel_world params\n        declareAxis(\"cmd_vel_world.x_velocity\");\n        declareAxis(\"cmd_vel_world.y_velocity\");\n        declareAxis(\"cmd_vel_world.z_velocity\");\n        declareAxis(\"cmd_vel_world.yaw_velocity\");\n        this->declare_parameter(\"cmd_vel_world.x_limit\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n        this->declare_parameter(\"cmd_vel_world.y_limit\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n        this->declare_parameter(\"cmd_vel_world.z_limit\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n\n        this->declare_parameter<float>(\"takeoff.duration\");\n        this->get_parameter<float>(\"takeoff.duration\", takeoff_paras_.duration);\n        this->declare_parameter<float>(\"takeoff.height\");\n        this->get_parameter<float>(\"takeoff.height\", takeoff_paras_.height);\n        this->declare_parameter<int>(\"takeoff.button\");\n        this->get_parameter<int>(\"takeoff.button\", takeoff_paras_.button);\n\n        this->declare_parameter<int>(\"land.button\");\n        this->get_parameter<int>(\"land.button\", land_button);\n        this->declare_parameter<int>(\"emergency.button\");\n        this->get_parameter<int>(\"emergency.button\", emergency_button);\n\n        this->declare_parameter<int>(\"arm.button\");\n        this->get_parameter<int>(\"arm.button\", arm_button);\n        is_armed_ = false;\n\n        on_mode_switched();\n\n        dt_ = 1.0f/frequency_;\n        is_low_level_flight_active_ = false;\n\n        // Create a parameter subscriber that can be used to monitor parameter changes\n        param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);\n        cb_handle_ = param_subscriber_->add_parameter_event_callback(std::bind(&TeleopNode::on_parameter_event, this, _1));\n\n        if (frequency_ > 0) {\n            timer_ = this->create_wall_timer(std::chrono::milliseconds(1000/frequency_), std::bind(&TeleopNode::publish, this));\n        }\n\n        client_emergency_ = this->create_client<Empty>(\"emergency\");\n        client_arm_ = this->create_client<Arm>(\"arm\");\n        client_takeoff_ = this->create_client<Takeoff>(\"takeoff\");\n        client_land_ = this->create_client<Land>(\"land\");\n        client_notify_setpoints_stop_ = this->create_client<NotifySetpointsStop>(\"notify_setpoints_stop\");\n    }\n\nprivate:\n    struct \n    {\n        float x;\n        float y;\n        float z;\n        float yaw;\n    }state_;\n\n    struct Axis\n    { \n        int axis;\n        float max;\n        float deadband;\n    };\n    struct\n    {\n        Axis x;\n        Axis y;\n        Axis z;\n        Axis yaw;\n    } axes_;\n\n    float angle_normalize(float a){ \n        a = fmod(a, 2*M_PI);\n        a = fmod((a + 2*M_PI),2*M_PI);\n        if (a > M_PI){\n            a -= 2*M_PI;\n        }\n        return a;\n    }\n\n    struct \n    { \n        float duration;\n        float height;\n        int button;\n    } takeoff_paras_;\n\n    int land_button;\n    int emergency_button;\n    int arm_button;\n\n    void on_parameter_event(const rcl_interfaces::msg::ParameterEvent &event)\n    {\n        if (event.node == \"/teleop\") {\n            auto params = param_subscriber_->get_parameters_from_event(event);\n            for (auto &p : params) {\n                if (p.get_name() == \"mode\") {\n                    mode_ = p.as_string();\n                    on_mode_switched();\n                }\n            }\n        }\n    }\n\n    void publish() \n    {\n        if (!is_low_level_flight_active_) {\n            return;\n        }\n\n        if (mode_ == \"cmd_rpy\") { \n            pub_cmd_vel_legacy_->publish(twist_);\n        }\n        if (mode_ == \"cmd_vel_world\") {   \n\n            float prev_x = state_.x;\n            float prev_y = state_.y;\n            float prev_z = state_.z;\n            state_.x = std::min<float>(std::max<float>(state_.x + twist_.linear.x*dt_, x_limit_[0]), x_limit_[1]);\n            state_.y = std::min<float>(std::max<float>(state_.y + twist_.linear.y*dt_, y_limit_[0]), y_limit_[1]);\n            state_.z = std::min<float>(std::max<float>(state_.z + twist_.linear.z*dt_, z_limit_[0]), z_limit_[1]);\n            state_.yaw = angle_normalize(state_.yaw + twist_.angular.z*dt_);\n\n            Quaternionf q;\n            q = AngleAxisf(0, Vector3f::UnitX())\n                    * AngleAxisf(0, Vector3f::UnitY())\n                    * AngleAxisf(state_.yaw, Vector3f::UnitZ());\n\n            fullstate_.pose.position.x = state_.x; \n            fullstate_.pose.position.y = state_.y;\n            fullstate_.pose.position.z = state_.z;\n            fullstate_.twist.linear.x = (state_.x-prev_x)/dt_;\n            fullstate_.twist.linear.y = (state_.y-prev_y)/dt_;\n            fullstate_.twist.linear.z = (state_.z-prev_z)/dt_;\n            fullstate_.acc.x = 0;\n            fullstate_.acc.y = 0;\n            fullstate_.acc.z = 0;\n            fullstate_.pose.orientation.x = q.x(); \n            fullstate_.pose.orientation.y = q.y();\n            fullstate_.pose.orientation.z = q.z();\n            fullstate_.pose.orientation.w = q.w();\n            fullstate_.twist.angular.x = 0;       \n            fullstate_.twist.angular.y = 0;       \n            fullstate_.twist.angular.z = twist_.angular.z; // yaw rate \n            \n            pub_cmd_full_state_->publish(fullstate_);\n        }\n\n    }\n\n    void joyChanged(const sensor_msgs::msg::Joy::SharedPtr msg)\n    {\n        static std::vector<int> lastButtonState;\n\n        auto checkButton = [&](int button) { \n            return msg->buttons.size() > button &&\n                msg->buttons[button] == 1 &&\n                lastButtonState.size() > button &&\n                lastButtonState[button] == 0;\n        };\n\n        if (checkButton(emergency_button)) {\n            emergency();\n        }\n        if (checkButton(arm_button)) {\n            arm();\n        }\n        if (checkButton(takeoff_paras_.button)) {\n            takeoff();\n        }\n        if (checkButton(land_button)) {\n            land();\n        }\n\n        lastButtonState = msg->buttons;\n        \n        twist_.linear.x = getAxis(msg, axes_.x);\n        twist_.linear.y = getAxis(msg, axes_.y);\n        twist_.linear.z = getAxis(msg, axes_.z);\n        if(auto_yaw_rate_ == 0.0){\n            twist_.angular.z = getAxis(msg, axes_.yaw);\n        }\n        else {\n            twist_.angular.z = auto_yaw_rate_; \n        }\n    }\n\n    sensor_msgs::msg::Joy::_axes_type::value_type getAxis(const sensor_msgs::msg::Joy::SharedPtr &msg, Axis a)\n    {\n        if (a.axis == 0) {\n            return 0;\n        }\n\n        sensor_msgs::msg::Joy::_axes_type::value_type sign = 1.0;\n        if (a.axis < 0) {\n            sign = -1.0;\n            a.axis = -a.axis;\n        }\n        if ((size_t) a.axis > msg->axes.size()) {\n            return 0;\n        }\n        auto result = sign * msg->axes[a.axis - 1]*a.max;\n        if (fabs(result) > a.deadband) {\n            return result;\n        } else {\n            return 0;\n        }\n    }\n    \n    void emergency()\n    {\n        if (!client_emergency_->service_is_ready()) {\n            RCLCPP_ERROR(get_logger(), \"Emergency service not ready!\");\n            return;\n        }\n        auto request = std::make_shared<Empty::Request>();\n        client_emergency_->async_send_request(request);\n    }\n\n    void arm()\n    {\n        if (!client_arm_->service_is_ready()) {\n            RCLCPP_ERROR(get_logger(), \"Arm service not ready!\");\n            return;\n        }\n        auto request = std::make_shared<Arm::Request>();\n        request->arm = !is_armed_;\n        client_arm_->async_send_request(request);\n        is_armed_ = !is_armed_;\n    }\n\n    void takeoff()\n    {\n        if (!client_takeoff_->service_is_ready()) {\n            RCLCPP_ERROR(get_logger(), \"Takeoff service not ready!\");\n            return;\n        }\n        auto request = std::make_shared<Takeoff::Request>();\n        request->group_mask = 0;\n        request->height = takeoff_paras_.height;\n        request->duration = rclcpp::Duration::from_seconds(takeoff_paras_.duration);\n        client_takeoff_->async_send_request(request);\n\n        timer_takeoff_ = this->create_wall_timer(std::chrono::duration<float>(takeoff_paras_.duration), [this]() {\n            state_.z = takeoff_paras_.height;  \n            is_low_level_flight_active_ = true;\n            this->timer_takeoff_->cancel();\n        });\n    }\n\n    void land()\n    {\n        if (!client_land_->service_is_ready()) {\n            RCLCPP_ERROR(get_logger(), \"Land service not ready!\");\n            return;\n        }\n\n        is_low_level_flight_active_ = false;\n\n        // If we are in manual flight mode, first switch back to high-level mode\n        if (!client_notify_setpoints_stop_->service_is_ready()) {\n            RCLCPP_ERROR(get_logger(), \"NotifySetpointStop service not ready!\");\n        } else {\n            auto request1 = std::make_shared<NotifySetpointsStop::Request>();\n            request1->remain_valid_millisecs = 100;\n            request1->group_mask = 0;\n            client_notify_setpoints_stop_->async_send_request(request1);\n        }\n\n        // Now we should be able to land!\n        auto request2 = std::make_shared<Land::Request>();\n        request2->group_mask = 0;\n        request2->height = 0.0;\n        request2->duration = rclcpp::Duration::from_seconds(3.5);\n        client_land_->async_send_request(request2);\n    }\n\n    void declareAxis(const std::string& name)\n    {\n        this->declare_parameter<int>(name + \".axis\");\n        this->declare_parameter<float>(name + \".max\");\n        this->declare_parameter<float>(name + \".deadband\");\n    }\n\n    void getAxis(const std::string& name, Axis& axis)\n    {\n        this->get_parameter<int>(name + \".axis\", axis.axis);\n        this->get_parameter<float>(name + \".max\", axis.max);\n        this->get_parameter<float>(name + \".deadband\", axis.deadband);\n    }\n\n    void on_mode_switched()\n    {\n        if (mode_ == \"high_level\") {\n            // nothing to do\n        } else if (mode_ == \"cmd_rpy\") {\n            getAxis(mode_ + \".roll\", axes_.x);\n            getAxis(mode_ + \".pitch\", axes_.y);\n            getAxis(mode_ + \".yawrate\", axes_.yaw);\n            getAxis(mode_ + \".thrust\", axes_.z);\n        } else if (mode_ == \"cmd_vel_world\"){\n            getAxis(mode_ + \".x_velocity\", axes_.x);\n            getAxis(mode_ + \".y_velocity\", axes_.y);\n            getAxis(mode_ + \".z_velocity\", axes_.z);\n            getAxis(mode_ + \".yaw_velocity\", axes_.yaw);\n\n            this->get_parameter(mode_ + \".x_limit\", x_param);\n            x_limit_ = x_param.as_double_array();\n            this->get_parameter(mode_ + \".y_limit\", y_param);\n            y_limit_ = y_param.as_double_array();\n            this->get_parameter(mode_ + \".z_limit\", z_param);\n            z_limit_ = z_param.as_double_array();\n        } else {\n            RCLCPP_ERROR(get_logger(), \"Unknown mode %s\", mode_.c_str());\n            return;\n        }\n\n        RCLCPP_INFO(get_logger(), \"Mode changed to %s\", mode_.c_str());\n    }\n\n    // monitor parameter changes\n    std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;\n    std::shared_ptr<rclcpp::ParameterEventCallbackHandle> cb_handle_;\n\n    rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr subscription_;\n    rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_emergency_;\n    rclcpp::Client<Arm>::SharedPtr client_arm_;\n    rclcpp::Client<Takeoff>::SharedPtr client_takeoff_;\n    rclcpp::Client<Land>::SharedPtr client_land_;\n    rclcpp::Client<NotifySetpointsStop>::SharedPtr client_notify_setpoints_stop_;\n    rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_cmd_vel_legacy_;\n    rclcpp::Publisher<crazyflie_interfaces::msg::FullState>::SharedPtr pub_cmd_full_state_;\n    rclcpp::TimerBase::SharedPtr timer_;\n    rclcpp::TimerBase::SharedPtr timer_takeoff_;\n    geometry_msgs::msg::Twist twist_;\n    crazyflie_interfaces::msg::FullState fullstate_;\n    std::vector<double> x_limit_;\n    std::vector<double> y_limit_;\n    std::vector<double> z_limit_;\n    std::string mode_;\n    rclcpp::Parameter x_param;\n    rclcpp::Parameter y_param;\n    rclcpp::Parameter z_param;\n    int frequency_;\n    float dt_;\n    bool is_low_level_flight_active_;\n    double auto_yaw_rate_;\n    bool is_armed_;\n};\n\nint main(int argc, char *argv[])\n{\n    rclcpp::init(argc, argv);\n    rclcpp::spin(std::make_shared<TeleopNode>());\n    rclcpp::shutdown();\n    return 0;\n}\n"
  },
  {
    "path": "crazyflie/urdf/cf2_assembly_with_props.dae",
    "content": "<?xml version=\"1.0\" encoding=\"utf-8\"?>\n<!--\n ...........       ____  _ __\n |  ,-^-,  |      / __ )(_) /_______________ _____  ___\n | (  O  ) |     / __  / / __/ ___/ ___/ __ `/_  / / _ \\\n | / ,..´  |    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/\n    +.......   /_____/_/\\__/\\___/_/   \\__,_/ /___/\\___/\n\nMIT License\n\nCopyright (c) 2024 Bitcraze\n-->\n<COLLADA xmlns=\"http://www.collada.org/2005/11/COLLADASchema\" version=\"1.4.1\" xmlns:xsi=\"http://www.w3.org/2001/XMLSchema-instance\">\n  <asset>\n    <contributor>\n      <author>Kimberly McGuire (Bitcraze AB)</author>\n      <authoring_tool>Blender 3.1.2 commit date:2022-03-31, commit time:17:40, hash:cc66d1020c3b</authoring_tool>\n    </contributor>\n    <created>2024-01-30T21:06:41</created>\n    <modified>2024-01-30T21:06:41</modified>\n    <unit name=\"meter\" meter=\"1\"/>\n    <up_axis>Z_UP</up_axis>\n  </asset>\n  <library_effects>\n    <effect id=\"pcb-effect\">\n      <profile_COMMON>\n        <technique sid=\"common\">\n          <lambert>\n            <emission>\n              <color sid=\"emission\">0 0 0 1</color>\n            </emission>\n            <diffuse>\n              <color sid=\"diffuse\">0.009523815 0.009523815 0.009523815 1</color>\n            </diffuse>\n            <index_of_refraction>\n              <float sid=\"ior\">1.45</float>\n            </index_of_refraction>\n          </lambert>\n        </technique>\n      </profile_COMMON>\n    </effect>\n    <effect id=\"metal-effect\">\n      <profile_COMMON>\n        <technique sid=\"common\">\n          <lambert>\n            <emission>\n              <color sid=\"emission\">0 0 0 1</color>\n            </emission>\n            <diffuse>\n              <color sid=\"diffuse\">0.1169535 0.1169535 0.1169535 1</color>\n            </diffuse>\n            <reflectivity>\n              <float sid=\"specular\">0.8</float>\n            </reflectivity>\n            <index_of_refraction>\n              <float sid=\"ior\">1.45</float>\n            </index_of_refraction>\n          </lambert>\n        </technique>\n      </profile_COMMON>\n    </effect>\n    <effect id=\"Material_001-effect\">\n      <profile_COMMON>\n        <technique sid=\"common\">\n          <lambert>\n            <emission>\n              <color sid=\"emission\">0 0 0 1</color>\n            </emission>\n            <diffuse>\n              <color sid=\"diffuse\">0.3428556 0.3428556 0.3428556 1</color>\n            </diffuse>\n            <reflectivity>\n              <float sid=\"specular\">0.6528497</float>\n            </reflectivity>\n            <index_of_refraction>\n              <float sid=\"ior\">1.45</float>\n            </index_of_refraction>\n          </lambert>\n        </technique>\n      </profile_COMMON>\n    </effect>\n    <effect id=\"Material_002-effect\">\n      <profile_COMMON>\n        <technique sid=\"common\">\n          <lambert>\n            <emission>\n              <color sid=\"emission\">0 0 0 1</color>\n            </emission>\n            <diffuse>\n              <color sid=\"diffuse\">0.8 0.8 0.8 1</color>\n            </diffuse>\n            <reflectivity>\n              <float sid=\"specular\">0.5</float>\n            </reflectivity>\n          </lambert>\n        </technique>\n      </profile_COMMON>\n    </effect>\n  </library_effects>\n  <library_images/>\n  <library_materials>\n    <material id=\"pcb-material\" name=\"pcb\">\n      <instance_effect url=\"#pcb-effect\"/>\n    </material>\n    <material id=\"metal-material\" name=\"metal\">\n      <instance_effect url=\"#metal-effect\"/>\n    </material>\n    <material id=\"Material_001-material\" name=\"Material.001\">\n      <instance_effect url=\"#Material_001-effect\"/>\n    </material>\n    <material id=\"Material_002-material\" name=\"Material.002\">\n      <instance_effect url=\"#Material_002-effect\"/>\n    </material>\n  </library_materials>\n  <library_geometries>\n    <geometry id=\"battery_holder-mesh\" name=\"battery_holder\">\n      <mesh>\n        <source id=\"battery_holder-mesh-positions\">\n          <float_array id=\"battery_holder-mesh-positions-array\" count=\"120\">-0.00999999 0.00999999 5e-4 -0.00999999 0.00999999 0.002499997 -0.00999999 0.01199996 0.002499997 -0.00999999 0.01199996 5e-4 0.00999999 0.01199996 0.002499997 0.00999999 0.01199996 5e-4 0.00999999 0.00999999 0.002499997 0.00999999 0.00999999 5e-4 -0.00999999 -0.00999999 5e-4 -0.00999999 -0.01199996 5e-4 -0.00999999 -0.01199996 0.002499997 -0.00999999 -0.00999999 0.002499997 0.00999999 -0.01199996 5e-4 0.00999999 -0.01199996 0.002499997 0.00999999 -0.00999999 5e-4 0.00999999 -0.00999999 0.002499997 -0.00999999 -0.01399999 -5e-4 -0.00999999 -0.01399999 5e-4 -0.00999999 0.01399999 5e-4 -0.00999999 0.01399999 -5e-4 0.00999999 0.01399999 5e-4 0.00999999 0.01399999 -5e-4 0.00999999 -0.01399999 5e-4 0.00999999 -0.01399999 -5e-4 -0.00109595 0.008999943 -5e-4 0.00109595 0.008999943 -5e-4 0.00109595 -0.008999943 -5e-4 -0.00109595 -0.008999943 -5e-4 -0.008095979 0.008999943 -5e-4 -0.008095979 -0.008999943 -5e-4 0.008095979 -0.008999943 -5e-4 0.008095979 0.008999943 -5e-4 -0.00109595 -0.008999943 5e-4 -0.008095979 -0.008999943 5e-4 -0.008095979 0.008999943 5e-4 -0.00109595 0.008999943 5e-4 0.00109595 0.008999943 5e-4 0.008095979 0.008999943 5e-4 0.008095979 -0.008999943 5e-4 0.00109595 -0.008999943 5e-4</float_array>\n          <technique_common>\n            <accessor source=\"#battery_holder-mesh-positions-array\" count=\"40\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"battery_holder-mesh-normals\">\n          <float_array id=\"battery_holder-mesh-normals-array\" count=\"45\">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 1 0 0 1 0 0</float_array>\n          <technique_common>\n            <accessor source=\"#battery_holder-mesh-normals-array\" count=\"15\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"battery_holder-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#battery_holder-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"pcb-material\" count=\"76\">\n          <input semantic=\"VERTEX\" source=\"#battery_holder-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#battery_holder-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 0 2 0 0 0 2 0 3 0 3 1 2 1 4 1 3 1 4 1 5 1 5 2 4 2 6 2 5 2 6 2 7 2 7 3 6 3 1 3 7 3 1 3 0 3 3 4 5 4 7 4 3 4 7 4 0 4 4 5 2 5 1 5 4 5 1 5 6 5 8 0 9 0 10 0 8 0 10 0 11 0 9 3 12 3 13 3 9 3 13 3 10 3 12 2 14 2 15 2 12 2 15 2 13 2 14 1 8 1 11 1 14 1 11 1 15 1 9 4 8 4 14 4 9 4 14 4 12 4 13 5 15 5 11 5 13 5 11 5 10 5 16 0 17 0 18 0 16 0 18 0 19 0 19 1 18 1 20 1 19 1 20 1 21 1 21 2 20 2 22 2 21 2 22 2 23 2 23 3 22 3 17 3 23 3 17 3 16 3 24 6 25 6 26 6 24 4 26 4 27 4 16 4 19 4 28 4 16 4 28 4 29 4 24 4 28 4 19 4 23 4 16 4 29 4 27 5 26 5 30 5 23 4 29 4 27 4 24 4 19 4 21 4 31 4 25 4 24 4 23 4 27 4 30 4 31 4 24 4 21 4 23 4 30 4 31 4 21 7 23 7 31 7 32 5 33 5 17 5 20 5 18 5 34 5 35 5 36 5 37 5 20 5 34 5 35 5 32 5 17 5 22 5 38 5 39 5 32 5 20 8 35 8 37 8 38 5 32 5 22 5 20 9 37 9 38 9 22 5 20 5 38 5 34 5 18 5 17 5 34 10 17 10 33 10 36 11 35 11 32 11 36 5 32 5 39 5 27 1 29 1 33 1 27 1 33 1 32 1 33 2 29 2 28 2 33 2 28 2 34 2 34 3 28 3 24 3 34 3 24 3 35 3 24 0 27 0 32 0 24 0 32 0 35 0 30 1 26 1 39 1 30 1 39 1 38 1 31 0 30 0 38 0 31 12 38 12 37 12 36 3 25 3 31 3 36 3 31 3 37 3 39 13 26 13 25 13 39 14 25 14 36 14</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"pin_headers_001-mesh\" name=\"pin_headers.001\">\n      <mesh>\n        <source id=\"pin_headers_001-mesh-positions\">\n          <float_array id=\"pin_headers_001-mesh-positions-array\" count=\"528\">-0.008816301 2.5e-4 0.01445657 -0.009316325 2.5e-4 0.01445657 -0.009316325 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 -0.003543376 -0.009316325 -2.5e-4 -0.003543376 -0.009316325 2.5e-4 -0.003543376 -0.008816301 2.5e-4 -0.003543376 -0.006816327 2.5e-4 0.01445657 -0.00731635 2.5e-4 0.01445657 -0.00731635 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 -0.003543376 -0.00731635 -2.5e-4 -0.003543376 -0.00731635 2.5e-4 -0.003543376 -0.006816327 2.5e-4 -0.003543376 -0.004816353 2.5e-4 0.01445657 -0.005316317 2.5e-4 0.01445657 -0.005316317 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 -0.003543376 -0.005316317 -2.5e-4 -0.003543376 -0.005316317 2.5e-4 -0.003543376 -0.004816353 2.5e-4 -0.003543376 -0.002816319 2.5e-4 0.01445657 -0.003316342 2.5e-4 0.01445657 -0.003316342 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 -0.003543376 -0.003316342 -2.5e-4 -0.003543376 -0.003316342 2.5e-4 -0.003543376 -0.002816319 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 0.01445657 -0.001316308 2.5e-4 0.01445657 -0.001316308 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 -0.003543376 -0.001316308 -2.5e-4 -0.003543376 -0.001316308 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 0.01445657 6.8364e-4 2.5e-4 0.01445657 6.8364e-4 -2.5e-4 0.01445657 0.001183629 -2.5e-4 0.01445657 0.001183629 -2.5e-4 -0.003543376 6.8364e-4 -2.5e-4 -0.003543376 6.8364e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 -0.003543376 0.003183603 2.5e-4 0.01445657 0.002683639 2.5e-4 0.01445657 0.002683639 -2.5e-4 0.01445657 0.003183603 -2.5e-4 0.01445657 0.003183603 -2.5e-4 -0.003543376 0.002683639 -2.5e-4 -0.003543376 0.002683639 2.5e-4 -0.003543376 0.003183603 2.5e-4 -0.003543376 0.005183637 2.5e-4 0.01445657 0.004683613 2.5e-4 0.01445657 0.004683613 -2.5e-4 0.01445657 0.005183637 -2.5e-4 0.01445657 0.005183637 -2.5e-4 -0.003543376 0.004683613 -2.5e-4 -0.003543376 0.004683613 2.5e-4 -0.003543376 0.005183637 2.5e-4 -0.003543376 0.007183611 2.5e-4 0.01445657 0.006683588 2.5e-4 0.01445657 0.006683588 -2.5e-4 0.01445657 0.007183611 -2.5e-4 0.01445657 0.007183611 -2.5e-4 -0.003543376 0.006683588 -2.5e-4 -0.003543376 0.006683588 2.5e-4 -0.003543376 0.007183611 2.5e-4 -0.003543376 0.009183585 2.5e-4 0.01445657 0.008683621 2.5e-4 0.01445657 0.008683621 -2.5e-4 0.01445657 0.009183585 -2.5e-4 0.01445657 0.009183585 -2.5e-4 -0.003543376 0.008683621 -2.5e-4 -0.003543376 0.008683621 2.5e-4 -0.003543376 0.009183585 2.5e-4 -0.003543376 -0.00999999 -0.000999987 -10e-4 -0.00999999 -0.000999987 0.000999987 -0.00999999 0.000999987 0.000999987 -0.00999999 0.000999987 -10e-4 0.00999999 0.000999987 0.000999987 0.00999999 0.000999987 -10e-4 0.00999999 -0.000999987 0.000999987 0.00999999 -0.000999987 -10e-4 -0.008816301 -0.02224999 0.01445657 -0.009316325 -0.02224999 0.01445657 -0.009316325 -0.02174997 0.01445657 -0.008816301 -0.02174997 0.01445657 -0.008816301 -0.02174997 -0.003543376 -0.009316325 -0.02174997 -0.003543376 -0.009316325 -0.02224999 -0.003543376 -0.008816301 -0.02224999 -0.003543376 -0.006816327 -0.02224999 0.01445657 -0.00731635 -0.02224999 0.01445657 -0.00731635 -0.02174997 0.01445657 -0.006816327 -0.02174997 0.01445657 -0.006816327 -0.02174997 -0.003543376 -0.00731635 -0.02174997 -0.003543376 -0.00731635 -0.02224999 -0.003543376 -0.006816327 -0.02224999 -0.003543376 -0.004816353 -0.02224999 0.01445657 -0.005316317 -0.02224999 0.01445657 -0.005316317 -0.02174997 0.01445657 -0.004816353 -0.02174997 0.01445657 -0.004816353 -0.02174997 -0.003543376 -0.005316317 -0.02174997 -0.003543376 -0.005316317 -0.02224999 -0.003543376 -0.004816353 -0.02224999 -0.003543376 -0.002816319 -0.02224999 0.01445657 -0.003316342 -0.02224999 0.01445657 -0.003316342 -0.02174997 0.01445657 -0.002816319 -0.02174997 0.01445657 -0.002816319 -0.02174997 -0.003543376 -0.003316342 -0.02174997 -0.003543376 -0.003316342 -0.02224999 -0.003543376 -0.002816319 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 0.01445657 -0.001316308 -0.02224999 0.01445657 -0.001316308 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 -0.003543376 -0.001316308 -0.02174997 -0.003543376 -0.001316308 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 0.01445657 6.8364e-4 -0.02224999 0.01445657 6.8364e-4 -0.02174997 0.01445657 0.001183629 -0.02174997 0.01445657 0.001183629 -0.02174997 -0.003543376 6.8364e-4 -0.02174997 -0.003543376 6.8364e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 -0.003543376 0.003183603 -0.02224999 0.01445657 0.002683639 -0.02224999 0.01445657 0.002683639 -0.02174997 0.01445657 0.003183603 -0.02174997 0.01445657 0.003183603 -0.02174997 -0.003543376 0.002683639 -0.02174997 -0.003543376 0.002683639 -0.02224999 -0.003543376 0.003183603 -0.02224999 -0.003543376 0.005183637 -0.02224999 0.01445657 0.004683613 -0.02224999 0.01445657 0.004683613 -0.02174997 0.01445657 0.005183637 -0.02174997 0.01445657 0.005183637 -0.02174997 -0.003543376 0.004683613 -0.02174997 -0.003543376 0.004683613 -0.02224999 -0.003543376 0.005183637 -0.02224999 -0.003543376 0.007183611 -0.02224999 0.01445657 0.006683588 -0.02224999 0.01445657 0.006683588 -0.02174997 0.01445657 0.007183611 -0.02174997 0.01445657 0.007183611 -0.02174997 -0.003543376 0.006683588 -0.02174997 -0.003543376 0.006683588 -0.02224999 -0.003543376 0.007183611 -0.02224999 -0.003543376 0.009183585 -0.02224999 0.01445657 0.008683621 -0.02224999 0.01445657 0.008683621 -0.02174997 0.01445657 0.009183585 -0.02174997 0.01445657 0.009183585 -0.02174997 -0.003543376 0.008683621 -0.02174997 -0.003543376 0.008683621 -0.02224999 -0.003543376 0.009183585 -0.02224999 -0.003543376 -0.00999999 -0.02099996 -10e-4 -0.00999999 -0.02099996 0.000999987 -0.00999999 -0.023 0.000999987 -0.00999999 -0.023 -10e-4 0.00999999 -0.023 0.000999987 0.00999999 -0.023 -10e-4 0.00999999 -0.02099996 0.000999987 0.00999999 -0.02099996 -10e-4</float_array>\n          <technique_common>\n            <accessor source=\"#pin_headers_001-mesh-positions-array\" count=\"176\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"pin_headers_001-mesh-normals\">\n          <float_array id=\"pin_headers_001-mesh-normals-array\" count=\"18\">0 0 1 0 -1 0 -1 0 0 0 0 -1 1 0 0 0 1 0</float_array>\n          <technique_common>\n            <accessor source=\"#pin_headers_001-mesh-normals-array\" count=\"6\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"pin_headers_001-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#pin_headers_001-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"metal-material\" count=\"264\">\n          <input semantic=\"VERTEX\" source=\"#pin_headers_001-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#pin_headers_001-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 0 2 0 0 0 2 0 3 0 4 1 3 1 2 1 4 1 2 1 5 1 5 2 2 2 1 2 5 2 1 2 6 2 6 3 7 3 4 3 6 3 4 3 5 3 7 4 0 4 3 4 7 4 3 4 4 4 6 5 1 5 0 5 6 5 0 5 7 5 8 0 9 0 10 0 8 0 10 0 11 0 12 1 11 1 10 1 12 1 10 1 13 1 13 2 10 2 9 2 13 2 9 2 14 2 14 3 15 3 12 3 14 3 12 3 13 3 15 4 8 4 11 4 15 4 11 4 12 4 14 5 9 5 8 5 14 5 8 5 15 5 16 0 17 0 18 0 16 0 18 0 19 0 20 1 19 1 18 1 20 1 18 1 21 1 21 2 18 2 17 2 21 2 17 2 22 2 22 3 23 3 20 3 22 3 20 3 21 3 23 4 16 4 19 4 23 4 19 4 20 4 22 5 17 5 16 5 22 5 16 5 23 5 24 0 25 0 26 0 24 0 26 0 27 0 28 1 27 1 26 1 28 1 26 1 29 1 29 2 26 2 25 2 29 2 25 2 30 2 30 3 31 3 28 3 30 3 28 3 29 3 31 4 24 4 27 4 31 4 27 4 28 4 30 5 25 5 24 5 30 5 24 5 31 5 32 0 33 0 34 0 32 0 34 0 35 0 36 1 35 1 34 1 36 1 34 1 37 1 37 2 34 2 33 2 37 2 33 2 38 2 38 3 39 3 36 3 38 3 36 3 37 3 39 4 32 4 35 4 39 4 35 4 36 4 38 5 33 5 32 5 38 5 32 5 39 5 40 0 41 0 42 0 40 0 42 0 43 0 44 1 43 1 42 1 44 1 42 1 45 1 45 2 42 2 41 2 45 2 41 2 46 2 46 3 47 3 44 3 46 3 44 3 45 3 47 4 40 4 43 4 47 4 43 4 44 4 46 5 41 5 40 5 46 5 40 5 47 5 48 0 49 0 50 0 48 0 50 0 51 0 52 1 51 1 50 1 52 1 50 1 53 1 53 2 50 2 49 2 53 2 49 2 54 2 54 3 55 3 52 3 54 3 52 3 53 3 55 4 48 4 51 4 55 4 51 4 52 4 54 5 49 5 48 5 54 5 48 5 55 5 56 0 57 0 58 0 56 0 58 0 59 0 60 1 59 1 58 1 60 1 58 1 61 1 61 2 58 2 57 2 61 2 57 2 62 2 62 3 63 3 60 3 62 3 60 3 61 3 63 4 56 4 59 4 63 4 59 4 60 4 62 5 57 5 56 5 62 5 56 5 63 5 64 0 65 0 66 0 64 0 66 0 67 0 68 1 67 1 66 1 68 1 66 1 69 1 69 2 66 2 65 2 69 2 65 2 70 2 70 3 71 3 68 3 70 3 68 3 69 3 71 4 64 4 67 4 71 4 67 4 68 4 70 5 65 5 64 5 70 5 64 5 71 5 72 0 73 0 74 0 72 0 74 0 75 0 76 1 75 1 74 1 76 1 74 1 77 1 77 2 74 2 73 2 77 2 73 2 78 2 78 3 79 3 76 3 78 3 76 3 77 3 79 4 72 4 75 4 79 4 75 4 76 4 78 5 73 5 72 5 78 5 72 5 79 5 80 2 81 2 82 2 80 2 82 2 83 2 83 5 82 5 84 5 83 5 84 5 85 5 85 4 84 4 86 4 85 4 86 4 87 4 87 1 86 1 81 1 87 1 81 1 80 1 83 3 85 3 87 3 83 3 87 3 80 3 84 0 82 0 81 0 84 0 81 0 86 0 88 0 90 0 89 0 88 0 91 0 90 0 92 5 90 5 91 5 92 5 93 5 90 5 93 2 89 2 90 2 93 2 94 2 89 2 94 3 92 3 95 3 94 3 93 3 92 3 95 4 91 4 88 4 95 4 92 4 91 4 94 1 88 1 89 1 94 1 95 1 88 1 96 0 98 0 97 0 96 0 99 0 98 0 100 5 98 5 99 5 100 5 101 5 98 5 101 2 97 2 98 2 101 2 102 2 97 2 102 3 100 3 103 3 102 3 101 3 100 3 103 4 99 4 96 4 103 4 100 4 99 4 102 1 96 1 97 1 102 1 103 1 96 1 104 0 106 0 105 0 104 0 107 0 106 0 108 5 106 5 107 5 108 5 109 5 106 5 109 2 105 2 106 2 109 2 110 2 105 2 110 3 108 3 111 3 110 3 109 3 108 3 111 4 107 4 104 4 111 4 108 4 107 4 110 1 104 1 105 1 110 1 111 1 104 1 112 0 114 0 113 0 112 0 115 0 114 0 116 5 114 5 115 5 116 5 117 5 114 5 117 2 113 2 114 2 117 2 118 2 113 2 118 3 116 3 119 3 118 3 117 3 116 3 119 4 115 4 112 4 119 4 116 4 115 4 118 1 112 1 113 1 118 1 119 1 112 1 120 0 122 0 121 0 120 0 123 0 122 0 124 5 122 5 123 5 124 5 125 5 122 5 125 2 121 2 122 2 125 2 126 2 121 2 126 3 124 3 127 3 126 3 125 3 124 3 127 4 123 4 120 4 127 4 124 4 123 4 126 1 120 1 121 1 126 1 127 1 120 1 128 0 130 0 129 0 128 0 131 0 130 0 132 5 130 5 131 5 132 5 133 5 130 5 133 2 129 2 130 2 133 2 134 2 129 2 134 3 132 3 135 3 134 3 133 3 132 3 135 4 131 4 128 4 135 4 132 4 131 4 134 1 128 1 129 1 134 1 135 1 128 1 136 0 138 0 137 0 136 0 139 0 138 0 140 5 138 5 139 5 140 5 141 5 138 5 141 2 137 2 138 2 141 2 142 2 137 2 142 3 140 3 143 3 142 3 141 3 140 3 143 4 139 4 136 4 143 4 140 4 139 4 142 1 136 1 137 1 142 1 143 1 136 1 144 0 146 0 145 0 144 0 147 0 146 0 148 5 146 5 147 5 148 5 149 5 146 5 149 2 145 2 146 2 149 2 150 2 145 2 150 3 148 3 151 3 150 3 149 3 148 3 151 4 147 4 144 4 151 4 148 4 147 4 150 1 144 1 145 1 150 1 151 1 144 1 152 0 154 0 153 0 152 0 155 0 154 0 156 5 154 5 155 5 156 5 157 5 154 5 157 2 153 2 154 2 157 2 158 2 153 2 158 3 156 3 159 3 158 3 157 3 156 3 159 4 155 4 152 4 159 4 156 4 155 4 158 1 152 1 153 1 158 1 159 1 152 1 160 0 162 0 161 0 160 0 163 0 162 0 164 5 162 5 163 5 164 5 165 5 162 5 165 2 161 2 162 2 165 2 166 2 161 2 166 3 164 3 167 3 166 3 165 3 164 3 167 4 163 4 160 4 167 4 164 4 163 4 166 1 160 1 161 1 166 1 167 1 160 1 168 2 170 2 169 2 168 2 171 2 170 2 171 1 172 1 170 1 171 1 173 1 172 1 173 4 174 4 172 4 173 4 175 4 174 4 175 5 169 5 174 5 175 5 168 5 169 5 171 3 175 3 173 3 171 3 168 3 175 3 172 0 169 0 170 0 172 0 174 0 169 0</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"battery-mesh\" name=\"battery\">\n      <mesh>\n        <source id=\"battery-mesh-positions\">\n          <float_array id=\"battery-mesh-positions-array\" count=\"72\">0.01091998 -0.008999943 -0.001559972 0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 -0.001559972 0.01399999 0.007019996 -0.001559972 0.01399999 0.007019996 0.001559972 0.01399999 -0.007019996 0.001559972 0.01399999 -0.007019996 -0.001559972 0.01091998 0.007019996 0.001999974 -0.01091998 0.007019996 0.001999974 -0.01091998 -0.007019996 0.001999974 0.01091998 -0.007019996 0.001999974 -0.01399999 -0.007019996 -0.001559972 -0.01399999 -0.007019996 0.001559972 -0.01399999 0.007019996 0.001559972 -0.01399999 0.007019996 -0.001559972 -0.01091998 0.008999943 -0.001559972 -0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 -0.001559972 -0.01091998 -0.007019996 -0.001999974 -0.01091998 0.007019996 -0.001999974 0.01091998 -0.007019996 -0.001999974 0.01091998 0.007019996 -0.001999974</float_array>\n          <technique_common>\n            <accessor source=\"#battery-mesh-positions-array\" count=\"24\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"battery-mesh-normals\">\n          <float_array id=\"battery-mesh-normals-array\" count=\"102\">0 -1 0 1 0 0 0 0 1 -1 0 0 0 1 0 -0.1381187 -0.2148514 -0.966831 -0.1381187 -0.2148514 0.966831 -0.1381187 0.2148514 -0.966831 -0.1381187 0.2148514 0.966831 0.1381187 -0.2148514 -0.966831 0.1381187 -0.2148514 0.966831 0.1381187 0.2148514 -0.966831 0.1381187 0.2148514 0.966831 -0.1414214 0 -0.9899496 -0.5407575 -0.8411786 0 -0.5407578 -0.8411785 0 -0.1414214 0 0.9899496 -0.5407575 0.8411786 0 -0.5407578 0.8411785 0 0 0.2169303 -0.9761872 0 0.2169306 -0.9761871 0 0.2169303 0.9761872 0 0.2169306 0.9761871 0.5407578 0.8411785 0 0.5407575 0.8411786 0 0.1414214 0 -0.9899496 0.1414214 0 0.9899496 0.5407575 -0.8411786 0 0.5407578 -0.8411785 0 0 -0.2169303 -0.9761872 0 -0.2169306 -0.9761871 0 -0.2169303 0.9761872 0 -0.2169306 0.9761871 0 0 -1</float_array>\n          <technique_common>\n            <accessor source=\"#battery-mesh-normals-array\" count=\"34\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"battery-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#battery-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"Material_001-material\" count=\"44\">\n          <input semantic=\"VERTEX\" source=\"#battery-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#battery-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 0 2 0 0 0 2 0 3 0 4 1 5 1 6 1 4 1 6 1 7 1 8 2 9 2 10 2 8 2 10 2 11 2 12 3 13 3 14 3 12 3 14 3 15 3 16 4 17 4 18 4 16 4 18 4 19 4 20 5 3 5 12 5 2 6 10 6 13 6 21 7 15 7 16 7 9 8 17 8 14 8 22 9 7 9 0 9 11 10 1 10 6 10 23 11 19 11 4 11 8 12 5 12 18 12 21 13 20 13 12 13 21 13 12 13 15 13 3 14 2 14 13 14 3 15 13 15 12 15 10 16 9 16 14 16 10 16 14 16 13 16 17 17 16 17 15 17 17 18 15 18 14 18 23 19 21 19 16 19 23 20 16 20 19 20 9 21 8 21 18 21 9 22 18 22 17 22 5 23 4 23 19 23 5 24 19 24 18 24 22 25 23 25 4 25 22 25 4 25 7 25 8 26 11 26 6 26 8 26 6 26 5 26 1 27 0 27 7 27 1 28 7 28 6 28 20 29 22 29 0 29 20 30 0 30 3 30 11 31 10 31 2 31 11 32 2 32 1 32 21 33 23 33 22 33 21 33 22 33 20 33</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"cf_body_001-mesh\" name=\"cf_body.001\">\n      <mesh>\n        <source id=\"cf_body_001-mesh-positions\">\n          <float_array id=\"cf_body_001-mesh-positions-array\" count=\"510\">0.01349288 0.003098845 0.001246988 0.002614974 0.01389831 0.001246988 0.002614974 0.01389831 -0.001246988 0.01349288 0.003098845 -0.001246988 0.0288853 0.02750301 0.001246988 0.0288853 0.02750301 -0.001246988 0.0269072 0.02946692 -0.001246988 0.0269072 0.02946692 0.001246988 0.01658421 0.01987266 0.001246988 0.01658421 0.01987266 -0.001246988 0.01936602 0.01711088 0.001246988 0.01936602 0.01711088 -0.001246988 0.01064378 0.01584881 -0.001246988 0.01538521 0.01114153 -0.001246988 0.01538521 0.01114153 0.001246988 0.01064378 0.01584881 0.001246988 -0.01349288 0.003098845 0.001246988 -0.01349288 0.003098845 -0.001246988 -0.002614974 0.01389831 -0.001246988 -0.002614974 0.01389831 0.001246988 -0.0288853 0.02750301 0.001246988 -0.0269072 0.02946692 0.001246988 -0.0269072 0.02946692 -0.001246988 -0.0288853 0.02750301 -0.001246988 -0.01658421 0.01987266 0.001246988 -0.01658421 0.01987266 -0.001246988 -0.01936602 0.01711088 0.001246988 -0.01936602 0.01711088 -0.001246988 -0.01064378 0.01584881 -0.001246988 -0.01538521 0.01114153 -0.001246988 -0.01538521 0.01114153 0.001246988 -0.01064378 0.01584881 0.001246988 0.01349288 -0.003098845 0.001246988 0.01349288 -0.003098845 -0.001246988 0.002614974 -0.01389831 -0.001246988 0.002614974 -0.01389831 0.001246988 0.0288853 -0.02750301 0.001246988 0.0269072 -0.02946692 0.001246988 0.0269072 -0.02946692 -0.001246988 0.0288853 -0.02750301 -0.001246988 0.01658421 -0.01987266 0.001246988 0.01658421 -0.01987266 -0.001246988 0.01936602 -0.01711088 0.001246988 0.01936602 -0.01711088 -0.001246988 0.01064378 -0.01584881 -0.001246988 0.01538521 -0.01114153 -0.001246988 0.01538521 -0.01114153 0.001246988 0.01064378 -0.01584881 0.001246988 -0.01349288 -0.003098845 0.001246988 -0.002614974 -0.01389831 0.001246988 -0.002614974 -0.01389831 -0.001246988 -0.01349288 -0.003098845 -0.001246988 -0.0288853 -0.02750301 0.001246988 -0.0288853 -0.02750301 -0.001246988 -0.0269072 -0.02946692 -0.001246988 -0.0269072 -0.02946692 0.001246988 -0.01658421 -0.01987266 0.001246988 -0.01658421 -0.01987266 -0.001246988 -0.01936602 -0.01711088 0.001246988 -0.01936602 -0.01711088 -0.001246988 -0.01064378 -0.01584881 -0.001246988 -0.01538521 -0.01114153 -0.001246988 -0.01538521 -0.01114153 0.001246988 -0.01064378 -0.01584881 0.001246988 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.003097176 0.01383805 0.001246988 -0.003097176 0.01383805 -0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.002675712 0.01383805 -0.001246988 0.002675712 0.01383805 0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.01199996 0.001311063 -0.00999999 0.01199996 0.003311097 -0.00999999 0.00999999 0.003311097 0.00999999 0.01199996 0.001311063 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.001311063 0.00999999 0.00999999 0.003311097 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.00999999 0.003311097 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.00999999 0.003311097 0.00999999 -0.00999999 0.001311063 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.00999999 0.003311097 -0.00999999 0.01199996 0.003311097 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.003311097 0.00999999 0.00999999 0.001311063 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.01199996 0.001311063 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.00999999 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.00999999 0.001311063 0.00999999 -0.00999999 0.003311097</float_array>\n          <technique_common>\n            <accessor source=\"#cf_body_001-mesh-positions-array\" count=\"170\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"cf_body_001-mesh-normals\">\n          <float_array id=\"cf_body_001-mesh-normals-array\" count=\"552\">-0.7045438 -0.7096605 0 -0.7045438 -0.7096605 0 0.7045443 0.70966 0 0.7045433 0.7096611 0 -0.6807795 0.7324885 0 -0.6807794 0.7324886 0 0 0 1 0 0 1 0.7373957 -0.6754611 0 0.7373957 -0.675461 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319734 -0.5548156 0 0.8319732 -0.5548159 0 0 0 1 0 0 1 -0.5608213 0.827937 0 -0.5608218 0.8279366 0 -0.2360691 0.9717363 0 -0.236069 0.9717363 0 0 0 1 0 0 1 0.9734192 -0.229031 0 0.9734191 -0.2290314 0 0 0 -1 0.7045438 -0.7096605 0 0.7045439 -0.7096605 0 -0.7045432 0.7096611 0 -0.7045443 0.7096601 0 0.6807794 0.7324886 0 0.6807794 0.7324885 0 0 0 1 0 0 1 -0.7373958 -0.6754609 0 -0.7373957 -0.6754611 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319733 -0.5548158 0 -0.831973 -0.5548161 0 0 0 1 0 0 1 0.5608217 0.8279367 0 0.5608213 0.827937 0 0.2360689 0.9717363 0 0 0 1 0 0 1 -0.9734192 -0.2290311 0 -0.9734191 -0.2290314 0 0 0 -1 0 0 -1 -0.7045438 0.7096605 0 0.7045429 -0.7096614 0 0.704544 -0.7096604 0 -0.6807792 -0.7324887 0 -0.6807792 -0.7324886 0 0 0 1 0 0 1 0.7373957 0.6754611 0 0.7373955 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319733 0.5548158 0 0.8319734 0.5548156 0 0 0 1 0 0 1 -0.5608217 -0.8279367 0 -0.5608213 -0.827937 0 -0.2360693 -0.9717363 0 -0.2360693 -0.9717363 0 0 0 1 0 0 1 0.9734191 0.2290314 0 0.9734192 0.2290311 0 0 0 -1 0.7045438 0.7096605 0 0.7045438 0.7096605 0 -0.7045439 -0.7096604 0 0.6807792 -0.7324886 0 0.6807791 -0.7324888 0 0 0 1 0 0 1 -0.7373958 0.6754609 0 -0.7373956 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319734 0.5548156 0 -0.8319731 0.5548161 0 0 0 1 0 0 1 0.5608215 -0.8279368 0 0.5608215 -0.8279367 0 0.2360691 -0.9717363 0 0.236069 -0.9717363 0 -0.973419 0.2290314 0 -0.9734191 0.2290311 0 -3.70063e-6 1.16742e-6 -1 -0.5859354 0.8103578 0 -0.589901 0.8074757 0 -0.5923686 0.8054254 -0.01973915 0.7045438 0.7096606 0 1 0 0 0 -1 0 0 0 1 0 0 -1 0.7045436 0.7096607 0 0 0 1 0 0 1 -1 0 0 -1 -1.10705e-6 0 0 0 -1 0 0 1 0 0 1 0.3181167 0.9480516 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 -1.01069e-6 0.7045438 0.7096605 0 0.704544 0.7096604 0 -9.25141e-7 -1.1674e-6 -1 -0.589901 -0.8074756 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054255 -0.01973885 0.7045437 -0.7096606 0 0.7045438 -0.7096605 0 1 1.10391e-6 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0.7045435 -0.7096607 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0.3181167 -0.9480516 0 0 0 -1 0 0 -1 0 0 -1 -1.85029e-6 0 -1 -0.5859355 0.8103576 0 -0.5899011 0.8074756 0 -0.5923686 0.8054254 -0.01973855 0.7045439 0.7096605 0 0 0 1 0 0 -1 0 0 1 -1 -2.19824e-6 0 -1 1.09118e-6 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 -2.7754e-6 -1.16739e-6 -1 -0.5899009 -0.8074757 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054254 -0.01973885 0.7045438 -0.7096606 0 0.7045438 -0.7096605 0 0 0 -1 0.7045436 -0.7096608 0 0.7045437 -0.7096607 0 0 0 1 0 0 -1 0 0 1 0 0 1 0.3181168 -0.9480515 0 0 0 -1 0 0 -1 0 0 -1 0.7045437 -0.7096607 0</float_array>\n          <technique_common>\n            <accessor source=\"#cf_body_001-mesh-normals-array\" count=\"184\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"cf_body_001-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#cf_body_001-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"pcb-material\" count=\"314\">\n          <input semantic=\"VERTEX\" source=\"#cf_body_001-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#cf_body_001-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 0 2 0 0 1 2 1 3 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 7 4 6 4 8 5 6 5 9 5 10 6 4 6 7 6 10 7 7 7 8 7 11 8 5 8 4 8 11 9 4 9 10 9 9 10 6 10 5 10 9 11 5 11 11 11 12 12 9 12 11 12 12 13 11 13 13 13 13 14 11 14 10 14 13 15 10 15 14 15 14 16 10 16 8 16 14 17 8 17 15 17 15 18 8 18 9 18 15 19 9 19 12 19 1 20 15 20 12 20 1 21 12 21 2 21 0 22 14 22 15 22 0 23 15 23 1 23 3 24 13 24 14 24 3 25 14 25 0 25 2 26 12 26 13 26 2 26 13 26 3 26 16 27 17 27 18 27 16 28 18 28 19 28 20 29 21 29 22 29 20 30 22 30 23 30 24 31 25 31 22 31 24 32 22 32 21 32 26 33 24 33 21 33 26 34 21 34 20 34 27 35 26 35 20 35 27 36 20 36 23 36 25 37 27 37 23 37 25 38 23 38 22 38 28 39 29 39 27 39 28 40 27 40 25 40 29 41 30 41 26 41 29 42 26 42 27 42 30 43 31 43 24 43 30 44 24 44 26 44 31 45 28 45 25 45 31 46 25 46 24 46 19 47 18 47 28 47 19 47 28 47 31 47 16 48 19 48 31 48 16 49 31 49 30 49 17 50 16 50 30 50 17 51 30 51 29 51 18 52 17 52 29 52 18 53 29 53 28 53 32 54 33 54 34 54 32 54 34 54 35 54 36 55 37 55 38 55 36 56 38 56 39 56 40 57 41 57 38 57 40 58 38 58 37 58 42 59 40 59 37 59 42 60 37 60 36 60 43 61 42 61 36 61 43 62 36 62 39 62 41 63 43 63 39 63 41 64 39 64 38 64 44 65 45 65 43 65 44 66 43 66 41 66 45 67 46 67 42 67 45 68 42 68 43 68 46 69 47 69 40 69 46 70 40 70 42 70 47 71 44 71 41 71 47 72 41 72 40 72 35 73 34 73 44 73 35 74 44 74 47 74 32 75 35 75 47 75 32 76 47 76 46 76 33 77 32 77 46 77 33 78 46 78 45 78 34 26 33 26 45 26 34 79 45 79 44 79 48 80 49 80 50 80 48 81 50 81 51 81 52 82 53 82 54 82 52 82 54 82 55 82 56 83 55 83 54 83 56 84 54 84 57 84 58 85 52 85 55 85 58 86 55 86 56 86 59 87 53 87 52 87 59 88 52 88 58 88 57 89 54 89 53 89 57 90 53 90 59 90 60 91 57 91 59 91 60 92 59 92 61 92 61 93 59 93 58 93 61 94 58 94 62 94 62 95 58 95 56 95 62 96 56 96 63 96 63 97 56 97 57 97 63 98 57 98 60 98 49 99 63 99 60 99 49 100 60 100 50 100 48 49 62 49 63 49 48 23 63 23 49 23 51 101 61 101 62 101 51 102 62 102 48 102 50 79 60 79 61 79 50 26 61 26 51 26 64 103 65 103 66 103 66 104 67 104 68 104 68 105 69 105 64 105 66 106 68 106 64 106 70 81 71 81 72 81 70 107 72 107 73 107 74 108 75 108 76 108 74 108 76 108 77 108 75 109 78 109 79 109 75 109 79 109 76 109 80 110 78 110 75 110 80 16 75 16 74 16 77 26 76 26 79 26 77 111 79 111 81 111 82 107 83 107 84 107 82 112 84 112 85 112 64 113 82 113 85 113 64 114 85 114 65 114 65 16 85 16 70 16 65 16 70 16 66 16 80 115 64 115 69 115 80 115 69 115 81 115 78 115 80 115 81 115 78 116 81 116 79 116 83 117 77 117 81 117 83 26 81 26 69 26 64 118 80 118 74 118 64 119 74 119 82 119 82 120 74 120 77 120 82 120 77 120 83 120 84 121 83 121 69 121 69 122 68 122 72 122 71 123 84 123 69 123 69 124 72 124 71 124 66 16 70 16 73 16 66 16 73 16 67 16 67 125 73 125 72 125 67 126 72 126 68 126 85 127 84 127 71 127 85 128 71 128 70 128 86 129 87 129 88 129 88 130 89 130 90 130 90 131 91 131 86 131 88 132 90 132 86 132 92 133 93 133 94 133 92 134 94 134 95 134 96 135 97 135 76 135 96 108 76 108 75 108 98 136 96 136 75 136 98 137 75 137 78 137 97 138 99 138 79 138 97 139 79 139 76 139 100 140 101 140 102 140 100 140 102 140 103 140 88 141 87 141 101 141 88 142 101 142 100 142 87 16 86 16 92 16 87 16 92 16 101 16 98 115 99 115 89 115 98 115 89 115 88 115 78 115 79 115 99 115 78 115 99 115 98 115 103 143 89 143 99 143 103 144 99 144 97 144 88 145 100 145 96 145 88 146 96 146 98 146 100 147 103 147 97 147 100 147 97 147 96 147 89 148 103 148 102 148 95 26 94 26 90 26 89 149 102 149 95 149 95 150 90 150 89 150 86 16 91 16 93 16 86 16 93 16 92 16 91 109 90 109 94 109 91 109 94 109 93 109 101 134 92 134 95 134 101 133 95 133 102 133 104 108 105 108 106 108 104 108 106 108 107 108 105 109 108 109 109 109 105 109 109 109 106 109 108 115 110 115 111 115 108 115 111 115 109 115 110 125 104 125 107 125 110 125 107 125 111 125 105 16 104 16 110 16 105 16 110 16 108 16 109 26 111 26 107 26 109 26 107 26 106 26 112 108 113 108 114 108 112 108 114 108 115 108 115 125 114 125 116 125 115 125 116 125 117 125 117 115 116 115 118 115 117 115 118 115 119 115 119 109 118 109 113 109 119 109 113 109 112 109 115 16 117 16 119 16 115 16 119 16 112 16 116 26 114 26 113 26 116 26 113 26 118 26 120 151 121 151 122 151 122 152 67 152 68 152 68 153 123 153 120 153 122 154 68 154 120 154 124 128 125 128 72 128 124 155 72 155 73 155 126 108 127 108 128 108 126 108 128 108 129 108 127 109 130 109 131 109 127 109 131 109 128 109 132 156 130 156 127 156 132 16 127 16 126 16 129 26 128 26 131 26 129 157 131 157 133 157 134 107 135 107 136 107 134 112 136 112 137 112 120 158 134 158 137 158 120 16 137 16 121 16 121 16 137 16 124 16 121 16 124 16 122 16 132 115 120 115 123 115 132 115 123 115 133 115 130 159 132 159 133 159 130 160 133 160 131 160 135 161 129 161 133 161 135 26 133 26 123 26 120 162 132 162 126 162 120 16 126 16 134 16 134 120 126 120 129 120 134 120 129 120 135 120 136 163 135 163 123 163 123 26 68 26 72 26 125 164 136 164 123 164 123 165 72 165 125 165 122 16 124 16 73 16 122 16 73 16 67 16 137 107 136 107 125 107 137 155 125 155 124 155 138 166 139 166 140 166 140 167 141 167 142 167 142 168 143 168 138 168 140 169 142 169 138 169 144 170 145 170 146 170 144 171 146 171 147 171 148 108 149 108 128 108 148 108 128 108 127 108 150 16 148 16 127 16 150 16 127 16 130 16 149 172 151 172 131 172 149 26 131 26 128 26 152 173 153 173 154 173 152 174 154 174 155 174 140 141 139 141 153 141 140 175 153 175 152 175 139 16 138 16 144 16 139 16 144 16 153 16 150 115 151 115 141 115 150 115 141 115 140 115 130 115 131 115 151 115 130 115 151 115 150 115 155 26 141 26 151 26 155 176 151 176 149 176 140 177 152 177 148 177 140 178 148 178 150 178 152 179 155 179 149 179 152 179 149 179 148 179 141 180 155 180 154 180 147 26 146 26 142 26 141 181 154 181 147 181 147 182 142 182 141 182 138 16 143 16 145 16 138 16 145 16 144 16 143 109 142 109 146 109 143 109 146 109 145 109 153 27 144 27 147 27 153 183 147 183 154 183 156 115 157 115 158 115 156 115 158 115 105 115 105 125 158 125 159 125 105 125 159 125 108 125 108 108 159 108 160 108 108 108 160 108 161 108 161 109 160 109 157 109 161 109 157 109 156 109 105 26 108 26 161 26 105 26 161 26 156 26 159 16 158 16 157 16 159 16 157 16 160 16 162 115 163 115 164 115 162 115 164 115 165 115 163 109 166 109 167 109 163 109 167 109 164 109 166 108 168 108 169 108 166 108 169 108 167 108 168 125 162 125 165 125 168 125 165 125 169 125 163 26 162 26 168 26 163 26 168 26 166 26 167 16 169 16 165 16 167 16 165 16 164 16</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"Cylinder-mesh\" name=\"Cylinder\">\n      <mesh>\n        <source id=\"Cylinder-mesh-positions\">\n          <float_array id=\"Cylinder-mesh-positions-array\" count=\"384\">0 0.003999948 -0.007499992 0 0.003999948 0.007499992 0.001530706 0.003695487 -0.007499992 0.001530706 0.003695487 0.007499992 0.002828419 0.002828419 -0.007499992 0.002828419 0.002828419 0.007499992 0.003695487 0.001530706 -0.007499992 0.003695487 0.001530706 0.007499992 0.003999948 0 -0.007499992 0.003999948 0 0.007499992 0.003695487 -0.001530706 -0.007499992 0.003695487 -0.001530706 0.007499992 0.002828419 -0.002828419 -0.007499992 0.002828419 -0.002828419 0.007499992 0.001530706 -0.003695487 -0.007499992 0.001530706 -0.003695487 0.007499992 0 -0.003999948 -0.007499992 0 -0.003999948 0.007499992 -0.001530706 -0.003695487 -0.007499992 -0.001530706 -0.003695487 0.007499992 -0.002828419 -0.002828419 -0.007499992 -0.002828419 -0.002828419 0.007499992 -0.003695487 -0.001530706 -0.007499992 -0.003695487 -0.001530706 0.007499992 -0.003999948 0 -0.007499992 -0.003999948 0 0.007499992 -0.003695487 0.001530706 -0.007499992 -0.003695487 0.001530706 0.007499992 -0.002828419 0.002828419 -0.007499992 -0.002828419 0.002828419 0.007499992 -0.001530706 0.003695487 -0.007499992 -0.001530706 0.003695487 0.007499992 -0.08789849 0.003999948 -0.007499992 -0.08789849 0.003999948 0.007499992 -0.08942919 0.003695487 -0.007499992 -0.08942919 0.003695487 0.007499992 -0.09072691 0.002828419 -0.007499992 -0.09072691 0.002828419 0.007499992 -0.09159398 0.001530706 -0.007499992 -0.09159398 0.001530706 0.007499992 -0.0918985 0 -0.007499992 -0.0918985 0 0.007499992 -0.09159398 -0.001530706 -0.007499992 -0.09159398 -0.001530706 0.007499992 -0.09072691 -0.002828419 -0.007499992 -0.09072691 -0.002828419 0.007499992 -0.08942919 -0.003695487 -0.007499992 -0.08942919 -0.003695487 0.007499992 -0.08789849 -0.003999948 -0.007499992 -0.08789849 -0.003999948 0.007499992 -0.08636772 -0.003695487 -0.007499992 -0.08636772 -0.003695487 0.007499992 -0.08507007 -0.002828419 -0.007499992 -0.08507007 -0.002828419 0.007499992 -0.08420294 -0.001530706 -0.007499992 -0.08420294 -0.001530706 0.007499992 -0.08389848 0 -0.007499992 -0.08389848 0 0.007499992 -0.08420294 0.001530706 -0.007499992 -0.08420294 0.001530706 0.007499992 -0.08507007 0.002828419 -0.007499992 -0.08507007 0.002828419 0.007499992 -0.08636772 0.003695487 -0.007499992 -0.08636772 0.003695487 0.007499992 0 -0.0918985 -0.007499992 0 -0.0918985 0.007499992 0.001530706 -0.09159398 -0.007499992 0.001530706 -0.09159398 0.007499992 0.002828419 -0.09072691 -0.007499992 0.002828419 -0.09072691 0.007499992 0.003695487 -0.08942919 -0.007499992 0.003695487 -0.08942919 0.007499992 0.003999948 -0.08789849 -0.007499992 0.003999948 -0.08789849 0.007499992 0.003695487 -0.08636772 -0.007499992 0.003695487 -0.08636772 0.007499992 0.002828419 -0.08507007 -0.007499992 0.002828419 -0.08507007 0.007499992 0.001530706 -0.08420294 -0.007499992 0.001530706 -0.08420294 0.007499992 0 -0.08389848 -0.007499992 0 -0.08389848 0.007499992 -0.001530706 -0.08420294 -0.007499992 -0.001530706 -0.08420294 0.007499992 -0.002828419 -0.08507007 -0.007499992 -0.002828419 -0.08507007 0.007499992 -0.003695487 -0.08636772 -0.007499992 -0.003695487 -0.08636772 0.007499992 -0.003999948 -0.08789849 -0.007499992 -0.003999948 -0.08789849 0.007499992 -0.003695487 -0.08942919 -0.007499992 -0.003695487 -0.08942919 0.007499992 -0.002828419 -0.09072691 -0.007499992 -0.002828419 -0.09072691 0.007499992 -0.001530706 -0.09159398 -0.007499992 -0.001530706 -0.09159398 0.007499992 -0.08789849 -0.0918985 -0.007499992 -0.08789849 -0.0918985 0.007499992 -0.08942919 -0.09159398 -0.007499992 -0.08942919 -0.09159398 0.007499992 -0.09072691 -0.09072691 -0.007499992 -0.09072691 -0.09072691 0.007499992 -0.09159398 -0.08942919 -0.007499992 -0.09159398 -0.08942919 0.007499992 -0.09189844 -0.08789849 -0.007499992 -0.09189844 -0.08789849 0.007499992 -0.09159398 -0.08636772 -0.007499992 -0.09159398 -0.08636772 0.007499992 -0.09072691 -0.08507007 -0.007499992 -0.09072691 -0.08507007 0.007499992 -0.08942919 -0.08420294 -0.007499992 -0.08942919 -0.08420294 0.007499992 -0.08789849 -0.08389848 -0.007499992 -0.08789849 -0.08389848 0.007499992 -0.08636772 -0.08420294 -0.007499992 -0.08636772 -0.08420294 0.007499992 -0.08507001 -0.08507007 -0.007499992 -0.08507001 -0.08507007 0.007499992 -0.08420294 -0.08636772 -0.007499992 -0.08420294 -0.08636772 0.007499992 -0.08389848 -0.08789849 -0.007499992 -0.08389848 -0.08789849 0.007499992 -0.08420294 -0.08942919 -0.007499992 -0.08420294 -0.08942919 0.007499992 -0.08507001 -0.09072691 -0.007499992 -0.08507001 -0.09072691 0.007499992 -0.08636772 -0.09159398 -0.007499992 -0.08636772 -0.09159398 0.007499992</float_array>\n          <technique_common>\n            <accessor source=\"#Cylinder-mesh-positions-array\" count=\"128\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"Cylinder-mesh-normals\">\n          <float_array id=\"Cylinder-mesh-normals-array\" count=\"432\">0.1950904 0.9807854 0 0.5555704 0.8314697 0 0.8314695 0.5555704 0 0.9807853 0.1950905 0 0.9807854 -0.1950903 0 0.8314695 -0.5555704 0 0.5555704 -0.8314697 0 0.1950903 -0.9807854 0 -0.1950904 -0.9807853 0 -0.5555703 -0.8314696 0 -0.8314693 -0.5555707 0 -0.9807853 -0.1950905 0 -0.9807854 0.1950902 0 -0.8314696 0.5555703 0 0 0 1 -0.5555704 0.8314695 0 -0.1950902 0.9807853 0 3.21555e-7 0 -1 -0.1950899 0.9807854 0 -0.5555716 0.8314688 0 -0.8314738 0.5555639 0 -0.9807836 0.1950989 0 -0.9807875 -0.1950799 0 -0.8314647 -0.5555776 0 -0.5555716 -0.8314688 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.555576 -0.8314658 0 0.8314738 -0.5555641 0 0.9807856 -0.1950893 0 0.9807856 0.1950893 0 0.8314645 0.555578 0 -3.21555e-7 0 1 0.5555672 0.8314718 0 0.1950898 0.9807854 0 0 0 -1 0.1950909 -0.9807853 0 0.5555703 -0.8314696 0 0.831469 -0.5555712 0 0.9807854 -0.1950899 0 0.9807854 0.1950899 0 0.8314687 0.5555716 0 0.5555704 0.8314695 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555705 0.8314695 0 -0.8314687 0.5555716 0 -0.9807854 0.1950899 0 -0.9807854 -0.1950899 0 -0.8314692 -0.555571 0 -2.27374e-7 0 1 -0.5555703 -0.8314696 0 -0.1950909 -0.9807853 0 0 0 -1 -0.1950859 -0.9807862 0 -0.5555715 -0.8314688 0 -0.83147 -0.5555697 0 -0.9807856 -0.1950891 0 -0.9807873 0.1950803 0 -0.8314655 0.5555766 0 -0.5555762 0.8314658 0 -0.1950859 0.9807862 0 0.1950859 0.9807862 0 0.5555715 0.8314688 0 0.8314746 0.5555627 0 0.9807856 0.1950891 0 0.9807835 -0.1950995 0 0.83147 -0.5555697 0 -5.48928e-7 0 1 0.5555669 -0.8314719 0 0.1950859 -0.9807862 0 0.8314697 0.5555703 0 0.9807853 0.1950902 0 0.5555704 -0.8314695 0 -0.8314696 -0.5555703 0 -0.9807854 -0.1950902 0 -0.9807852 0.1950908 0 1.95137e-6 0 1 1.95137e-6 0 1 -1.95137e-6 0 1 -0.5555704 0.8314696 0 -1.95137e-6 0 -1 -3.90274e-6 0 -1 1.95137e-6 0 -1 1.95137e-6 0 -1 3.90274e-6 0 -1 -4.54747e-7 0 -1 -0.1950899 0.9807854 0 -0.5555715 0.8314688 0 -0.8314647 0.5555778 0 -0.9807875 0.1950798 0 -0.9807836 -0.1950989 0 -0.8314738 -0.5555639 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.5555669 -0.831472 0 0.8314646 -0.5555779 0 0.8314736 0.5555643 0 9.75681e-7 0 1 -7.41687e-7 0 1 9.75679e-7 0 1 -9.75679e-7 0 1 4.54747e-7 0 1 0.5555763 0.8314656 0 0.1950898 0.9807854 0 7.41687e-7 0 -1 -1.95136e-6 0 -1 -1.48338e-6 0 -1 1.95136e-6 0 -1 -2.27374e-7 0 -1 0.195091 -0.9807853 0 0.8314689 -0.5555714 0 0.9807854 -0.1950899 0 0.9807855 0.1950896 0 0.8314689 0.5555712 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555704 0.8314697 0 -0.8314689 0.5555712 0 -0.9807854 0.1950899 0 -0.9807853 -0.1950902 0 -0.8314691 -0.555571 0 -1.95136e-6 0 1 -1.95133e-6 0 1 -4.87839e-7 0 1 1.95133e-6 0 1 1.95136e-6 0 1 -0.5555702 -0.8314698 0 -0.195091 -0.9807853 0 -1.95142e-6 0 -1 1.95142e-6 0 -1 9.75709e-7 0 -1 -0.5555762 -0.8314658 0 -0.8314655 -0.5555766 0 -0.9807875 -0.1950795 0 -0.83147 0.5555697 0 0.5555669 0.8314719 0 0.83147 0.5555697 0 0.9807837 0.1950986 0 0.8314746 -0.5555627 0 0.5555715 -0.8314688 0 9.75724e-7 0 -1 -1.95132e-6 0 -1 -9.75633e-7 0 -1</float_array>\n          <technique_common>\n            <accessor source=\"#Cylinder-mesh-normals-array\" count=\"144\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"Cylinder-mesh-map-0\">\n          <float_array id=\"Cylinder-mesh-map-0-array\" count=\"1440\">1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.08029437 0.08029437 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.5282689 0.341844 0.658156 0.4717311 0.841844 0.02826887 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029431 0.4197056 0.25 0.49 0.25 0.00999999 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.5282689 0.341844 0.658156 0.02826887 0.9717311 0.1581559 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029437 0.08029437 0.00999999 0.25 0.25 0.49 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.4717311 1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.4197056 0.08029437 0.49 0.25 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.9717311 0.341844 0.841844 0.02826887 0.5282689 0.1581559 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029437 0.08029437 0.08029437 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.4197056 0.08029437 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.08029437 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.08029437 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029431 0.4197056 0.00999999 0.25 0.08029437 0.08029437 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.841844 0.4717311 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.9717311 0.1581559 0.9717311 0.1581559 0.9197056 0.08029437 0.9717311 0.341844 0.9197056 0.08029437 0.841844 0.02826887 0.9717311 0.341844 0.841844 0.02826887 0.75 0.00999999 0.658156 0.02826887 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.658156 0.4717311 0.841844 0.4717311 0.841844 0.02826887 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.02826887 0.841844 0.02826887 0.658156 0.02826887 0.5282689 0.1581559 0.5282689 0.1581559 0.5282689 0.341844 0.841844 0.02826887 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.4197056 0.4197056 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.25 0.00999999 0.4717311 0.1581559 0.4197056 0.08029437 0.25 0.00999999 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.25 0.49 0.25 0.49 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.4197056 0.49 0.25 0.25 0.00999999 0.25 0.00999999 0.08029437 0.08029437 0.00999999 0.25 0.00999999 0.25 0.08029431 0.4197056 0.25 0.00999999 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.841844 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.841844 0.4717311 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.9717311 0.1581559 0.75 0.00999999 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.9717311 0.341844 0.9717311 0.341844 0.9197056 0.4197056 0.9717311 0.1581559 0.9197056 0.4197056 0.841844 0.4717311 0.9717311 0.1581559 0.841844 0.4717311 0.5282689 0.341844 0.9717311 0.1581559 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.49 0.25 0.341844 0.4717311 0.4197056 0.4197056 0.49 0.25 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.4197056 0.08029437 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.00999999 0.25 0.1581559 0.4717311 0.25 0.49 0.00999999 0.25 0.49 0.25 0.4197056 0.08029437 0.25 0.49 0.4197056 0.08029437 0.25 0.00999999 0.25 0.49 0.25 0.00999999 0.08029437 0.08029437 0.25 0.49 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.841844 0.02826887 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.841844 0.4717311 0.99 0.25 0.9717311 0.341844 0.841844 0.4717311 0.9717311 0.341844 0.9197056 0.4197056 0.841844 0.4717311 0.841844 0.4717311 0.658156 0.4717311 0.658156 0.02826887 0.658156 0.4717311 0.5282689 0.341844 0.658156 0.02826887 0.658156 0.02826887 0.841844 0.02826887 0.841844 0.4717311 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029431 0.4197056 0.02826887 0.1581559 0.08029437 0.08029437 0.08029431 0.4197056 0.08029437 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029437 0.08029437 0.25 0.00999999 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.9717311 0.341844 0.75 0.49 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.841844 0.02826887 0.99 0.25 0.9717311 0.1581559 0.841844 0.02826887 0.9717311 0.1581559 0.9197056 0.08029437 0.841844 0.02826887 0.841844 0.02826887 0.75 0.00999999 0.5282689 0.1581559 0.75 0.00999999 0.658156 0.02826887 0.5282689 0.1581559 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.5282689 0.1581559 0.5282689 0.341844 0.658156 0.4717311 0.658156 0.4717311 0.9717311 0.341844 0.5282689 0.1581559</float_array>\n          <technique_common>\n            <accessor source=\"#Cylinder-mesh-map-0-array\" count=\"720\" stride=\"2\">\n              <param name=\"S\" type=\"float\"/>\n              <param name=\"T\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"Cylinder-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#Cylinder-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"metal-material\" count=\"240\">\n          <input semantic=\"VERTEX\" source=\"#Cylinder-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#Cylinder-mesh-normals\" offset=\"1\"/>\n          <input semantic=\"TEXCOORD\" source=\"#Cylinder-mesh-map-0\" offset=\"2\" set=\"0\"/>\n          <p>1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 21 14 42 13 14 43 5 14 44 29 15 45 30 15 46 28 15 47 31 16 48 0 16 49 30 16 50 26 17 51 30 17 52 14 17 53 34 18 54 33 18 55 32 18 56 36 19 57 35 19 58 34 19 59 38 20 60 37 20 61 36 20 62 40 21 63 39 21 64 38 21 65 42 22 66 41 22 67 40 22 68 44 23 69 43 23 70 42 23 71 46 24 72 45 24 73 44 24 74 48 25 75 47 25 76 46 25 77 50 26 78 49 26 79 48 26 80 52 27 81 51 27 82 50 27 83 54 28 84 53 28 85 52 28 86 56 29 87 55 29 88 54 29 89 58 30 90 57 30 91 56 30 92 60 31 93 59 31 94 58 31 95 61 32 96 33 32 97 49 32 98 62 33 99 61 33 100 60 33 101 32 34 102 63 34 103 62 34 104 58 35 105 50 35 106 42 35 107 66 36 108 65 36 109 64 36 110 68 37 111 67 37 112 66 37 113 70 38 114 69 38 115 68 38 116 72 39 117 71 39 118 70 39 119 74 40 120 73 40 121 72 40 122 76 41 123 75 41 124 74 41 125 78 42 126 77 42 127 76 42 128 80 43 129 79 43 130 78 43 131 82 44 132 81 44 133 80 44 134 84 45 135 83 45 136 82 45 137 86 46 138 85 46 139 84 46 140 88 47 141 87 47 142 86 47 143 90 48 144 89 48 145 88 48 146 92 49 147 91 49 148 90 49 149 85 50 150 89 50 151 65 50 152 94 51 153 93 51 154 92 51 155 64 52 156 95 52 157 94 52 158 78 53 159 74 53 160 66 53 161 97 54 162 98 54 163 96 54 164 99 55 165 100 55 166 98 55 167 101 56 168 102 56 169 100 56 170 103 57 171 104 57 172 102 57 173 105 58 174 106 58 175 104 58 176 107 59 177 108 59 178 106 59 179 109 60 180 110 60 181 108 60 182 111 61 183 112 61 184 110 61 185 113 62 186 114 62 187 112 62 188 115 63 189 116 63 190 114 63 191 117 64 192 118 64 193 116 64 194 119 65 195 120 65 196 118 65 197 121 66 198 122 66 199 120 66 200 123 67 201 124 67 202 122 67 203 109 68 204 105 68 205 101 68 206 125 69 207 126 69 208 124 69 209 127 70 210 96 70 211 126 70 212 102 53 213 110 53 214 118 53 215 1 0 216 3 0 217 2 0 218 3 1 219 5 1 220 4 1 221 5 71 222 7 71 223 6 71 224 7 72 225 9 72 226 8 72 227 9 4 228 11 4 229 10 4 230 11 5 231 13 5 232 12 5 233 13 73 234 15 73 235 14 73 236 15 7 237 17 7 238 16 7 239 17 8 240 19 8 241 18 8 242 19 51 243 21 51 244 20 51 245 21 74 246 23 74 247 22 74 248 23 75 249 25 75 250 24 75 251 25 76 252 27 76 253 26 76 254 27 13 255 29 13 256 28 13 257 5 14 258 3 14 259 1 14 260 1 14 261 31 14 262 29 14 263 29 77 264 27 77 265 25 77 266 25 78 267 23 78 268 21 78 269 21 14 270 19 14 271 13 14 272 19 14 273 17 14 274 13 14 275 17 14 276 15 14 277 13 14 278 13 79 279 11 79 280 9 79 281 9 14 282 7 14 283 13 14 284 7 14 285 5 14 286 13 14 287 5 14 288 1 14 289 21 14 290 1 14 291 29 14 292 21 14 293 29 14 294 25 14 295 21 14 296 29 80 297 31 80 298 30 80 299 31 16 300 1 16 301 0 16 302 30 53 303 0 53 304 2 53 305 2 81 306 4 81 307 6 81 308 6 82 309 8 82 310 10 82 311 10 53 312 12 53 313 6 53 314 12 53 315 14 53 316 6 53 317 14 53 318 16 53 319 18 53 320 18 83 321 20 83 322 22 83 323 22 84 324 24 84 325 26 84 326 26 85 327 28 85 328 30 85 329 30 53 330 2 53 331 14 53 332 2 53 333 6 53 334 14 53 335 14 53 336 18 53 337 22 53 338 22 86 339 26 86 340 14 86 341 34 87 342 35 87 343 33 87 344 36 88 345 37 88 346 35 88 347 38 89 348 39 89 349 37 89 350 40 90 351 41 90 352 39 90 353 42 91 354 43 91 355 41 91 356 44 92 357 45 92 358 43 92 359 46 55 360 47 55 361 45 55 362 48 93 363 49 93 364 47 93 365 50 94 366 51 94 367 49 94 368 52 95 369 53 95 370 51 95 371 54 96 372 55 96 373 53 96 374 56 29 375 57 29 376 55 29 377 58 30 378 59 30 379 57 30 380 60 97 381 61 97 382 59 97 383 33 98 384 35 98 385 37 98 386 37 14 387 39 14 388 41 14 389 41 99 390 43 99 391 49 99 392 43 14 393 45 14 394 49 14 395 45 100 396 47 100 397 49 100 398 49 101 399 51 101 400 53 101 401 53 14 402 55 14 403 57 14 404 57 14 405 59 14 406 61 14 407 61 14 408 63 14 409 33 14 410 33 14 411 37 14 412 49 14 413 37 14 414 41 14 415 49 14 416 49 14 417 53 14 418 57 14 419 57 102 420 61 102 421 49 102 422 62 103 423 63 103 424 61 103 425 32 104 426 33 104 427 63 104 428 34 53 429 32 53 430 62 53 431 62 53 432 60 53 433 34 53 434 60 105 435 58 105 436 34 105 437 58 106 438 56 106 439 54 106 440 54 53 441 52 53 442 58 53 443 52 107 444 50 107 445 58 107 446 50 53 447 48 53 448 42 53 449 48 53 450 46 53 451 42 53 452 46 53 453 44 53 454 42 53 455 42 108 456 40 108 457 38 108 458 38 53 459 36 53 460 42 53 461 36 53 462 34 53 463 42 53 464 34 109 465 58 109 466 42 109 467 66 110 468 67 110 469 65 110 470 68 6 471 69 6 472 67 6 473 70 111 474 71 111 475 69 111 476 72 112 477 73 112 478 71 112 479 74 113 480 75 113 481 73 113 482 76 114 483 77 114 484 75 114 485 78 1 486 79 1 487 77 1 488 80 115 489 81 115 490 79 115 491 82 116 492 83 116 493 81 116 494 84 117 495 85 117 496 83 117 497 86 118 498 87 118 499 85 118 500 88 119 501 89 119 502 87 119 503 90 120 504 91 120 505 89 120 506 92 121 507 93 121 508 91 121 509 65 14 510 67 14 511 73 14 512 67 14 513 69 14 514 73 14 515 69 122 516 71 122 517 73 122 518 73 123 519 75 123 520 77 123 521 77 124 522 79 124 523 81 124 524 81 14 525 83 14 526 85 14 527 85 125 528 87 125 529 89 125 530 89 126 531 91 126 532 93 126 533 93 14 534 95 14 535 89 14 536 95 14 537 65 14 538 89 14 539 73 102 540 77 102 541 65 102 542 77 14 543 81 14 544 65 14 545 81 14 546 85 14 547 65 14 548 94 127 549 95 127 550 93 127 551 64 128 552 65 128 553 95 128 554 66 53 555 64 53 556 94 53 557 94 129 558 92 129 559 90 129 560 90 53 561 88 53 562 86 53 563 86 53 564 84 53 565 90 53 566 84 53 567 82 53 568 90 53 569 82 53 570 80 53 571 78 53 572 78 130 573 76 130 574 74 130 575 74 53 576 72 53 577 66 53 578 72 53 579 70 53 580 66 53 581 70 131 582 68 131 583 66 131 584 66 53 585 94 53 586 82 53 587 94 53 588 90 53 589 82 53 590 82 53 591 78 53 592 66 53 593 97 54 594 99 54 595 98 54 596 99 132 597 101 132 598 100 132 599 101 133 600 103 133 601 102 133 602 103 134 603 105 134 604 104 134 605 105 47 606 107 47 607 106 47 608 107 135 609 109 135 610 108 135 611 109 88 612 111 88 613 110 88 614 111 61 615 113 61 616 112 61 617 113 62 618 115 62 619 114 62 620 115 136 621 117 136 622 116 136 623 117 137 624 119 137 625 118 137 626 119 138 627 121 138 628 120 138 629 121 39 630 123 39 631 122 39 632 123 139 633 125 139 634 124 139 635 101 14 636 99 14 637 97 14 638 97 14 639 127 14 640 125 14 641 125 14 642 123 14 643 121 14 644 121 14 645 119 14 646 125 14 647 119 14 648 117 14 649 125 14 650 117 14 651 115 14 652 113 14 653 113 14 654 111 14 655 109 14 656 109 14 657 107 14 658 105 14 659 105 14 660 103 14 661 101 14 662 101 14 663 97 14 664 117 14 665 97 14 666 125 14 667 117 14 668 117 14 669 113 14 670 101 14 671 113 14 672 109 14 673 101 14 674 125 140 675 127 140 676 126 140 677 127 70 678 97 70 679 96 70 680 126 53 681 96 53 682 102 53 683 96 53 684 98 53 685 102 53 686 98 53 687 100 53 688 102 53 689 102 53 690 104 53 691 110 53 692 104 53 693 106 53 694 110 53 695 106 141 696 108 141 697 110 141 698 110 53 699 112 53 700 118 53 701 112 53 702 114 53 703 118 53 704 114 53 705 116 53 706 118 53 707 118 142 708 120 142 709 122 142 710 122 143 711 124 143 712 126 143 713 118 53 714 122 53 715 126 53 716 126 53 717 102 53 718 118 53 719</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"motor_mount-mesh\" name=\"motor_mount\">\n      <mesh>\n        <source id=\"motor_mount-mesh-positions\">\n          <float_array id=\"motor_mount-mesh-positions-array\" count=\"2904\">0.005317986 0.00486803 0.003593802 0.004800558 0.004358887 0.004319727 0.002978742 0.002566218 0.004319727 0.002978742 0.002566218 -0.005680263 0.005317986 0.00486803 -0.005680263 0.004953145 0.00523889 0.003593802 0.004953145 0.00523889 -0.005680263 0.002613842 0.002937018 -0.005680263 0.002613842 0.002937018 0.004319727 0.004435718 0.004729688 0.004319727 0.004017651 0.003588497 -0.01271951 0.005317986 0.00486803 -0.01089519 0.002978742 0.002566218 -0.01271951 0.003652751 0.003959298 -0.01271951 0.002613842 0.002937018 -0.01271951 0.004953145 0.00523889 -0.01089519 -0.004823744 0.005358219 0.003593802 -0.004318952 0.004836559 0.004319727 -0.002541422 0.002999961 0.004319727 -0.002541422 0.002999961 -0.005680263 -0.004823744 0.005358219 -0.005680263 -0.005197584 0.004996418 0.003593802 -0.005197584 0.004996418 -0.005680263 -0.002915203 0.002638161 -0.005680263 -0.002915203 0.002638161 0.004319727 -0.004692733 0.004474759 0.004319727 -0.003555059 0.004047274 -0.01271951 -0.004823744 0.005358219 -0.01089519 -0.002541422 0.002999961 -0.01271951 -0.003928899 0.003685474 -0.01271951 -0.002915203 0.002638161 -0.01271951 -0.005197584 0.004996418 -0.01089519 0.002129197 -0.02311611 0.003208577 0.001975595 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003119826 0.001999974 -0.02311611 0.003119826 -0.002499997 -0.02311611 2.79243e-5 -0.002499997 -0.02311611 0.003103077 -0.002499997 -0.01974391 0.003103077 -0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 0.003103077 0.002499997 -0.02311611 0.003103077 0.002499997 -0.02311611 2.79243e-5 0.001409769 -0.01974391 0.003463387 -0.001409769 -0.01974391 0.003463387 -0.001409769 -0.02311611 0.003463387 0.001409769 -0.006255149 0.003463387 -0.001409769 -0.006255149 0.003463387 -0.001409769 -0.009627342 0.003463387 0.001409769 -0.009627342 0.003463387 0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01637172 0.003463387 0.001409769 -0.01637172 0.003463387 0.002217113 -0.002882957 0.003183543 0.002499997 -0.002882957 0.003103077 0.002499997 -0.002882957 2.79243e-5 0.002217113 -0.002882957 2.79243e-5 0.002499997 -0.009627342 2.79243e-5 0.002499997 -0.009627342 0.003103077 0.002499997 -0.01299953 0.003103077 0.002499997 -0.01299953 2.79243e-5 0.002499997 -0.01637172 0.003103077 0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.006255149 2.79243e-5 -0.002499997 -0.006255149 0.003103077 -0.002499997 -0.002882957 0.003103077 -0.002499997 -0.002882957 2.79243e-5 0.002499997 -0.006255149 2.79243e-5 0.002499997 -0.006255149 0.003103077 -0.002499997 -0.009627342 2.79243e-5 -0.002499997 -0.009627342 0.003103077 -0.002499997 -0.01299953 2.79243e-5 -0.002499997 -0.01299953 0.003103077 -0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.01637172 0.003103077 0.001975595 -0.006255149 0.003463387 0.001975595 -0.009627342 0.003463387 0.001975595 -0.01299953 0.003463387 0.001975595 -0.01637172 0.003463387 0.001975595 -0.01974391 0.003463387 -0.001975595 -0.02311611 0.003463387 -0.002129197 -0.02311611 0.003208577 -0.001999974 -0.02311611 0.003119826 -0.001409769 -0.02311611 0.003119826 -0.001975595 -0.01637172 0.003463387 -0.001975595 -0.01974391 0.003463387 -0.001975595 -0.01299953 0.003463387 -0.001975595 -0.009627342 0.003463387 -0.001975595 -0.006255149 0.003463387 -0.001999974 -0.003028035 0.003119826 -0.001999974 -0.006255149 0.003119826 -0.001999974 -0.006255149 2.79243e-5 -0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.01974391 2.79243e-5 0.001999974 -0.02311611 2.79243e-5 0.001999974 -0.01974391 0.003119826 -0.001409769 -0.01974391 0.003119826 -0.001999974 -0.01974391 0.003119826 0.001409769 -0.01974391 0.003119826 0.001409769 -0.006255149 0.003119826 0.001409769 -0.009627342 0.003119826 -0.001409769 -0.009627342 0.003119826 -0.001409769 -0.006255149 0.003119826 0.001409769 -0.01299953 0.003119826 0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01299953 0.003119826 0.001999974 -0.003028035 0.003119826 0.001999974 -0.006255149 0.003119826 0.001409769 -0.003419578 0.003119826 0.001415908 -0.003418326 0.003119826 0.001999974 -0.009627342 0.003119826 0.001999974 -0.01299953 0.003119826 0.001999974 -0.01637172 0.003119826 -0.001409769 -0.003419578 0.003119826 -0.001415908 -0.003418326 0.003119826 -0.001999974 -0.009627342 0.003119826 -0.001999974 -0.01299953 0.003119826 -0.001999974 -0.01637172 0.003119826 0.001999974 -0.006255149 2.79243e-5 0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.009627342 2.79243e-5 0.001999974 -0.01299953 2.79243e-5 0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.02311611 2.79243e-5 -0.001999974 -0.01974391 2.79243e-5 -0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.01299953 2.79243e-5 -0.001999974 -0.009627342 2.79243e-5 0.001415908 -0.003418326 0.003463387 0.001409769 -0.003419578 0.003463387 0.001975595 -0.003044307 0.003463387 -0.001415908 -0.003418326 0.003463387 -0.001975595 -0.003044307 0.003463387 -0.001409769 -0.003419578 0.003463387 -0.002217113 -0.002882957 2.79243e-5 -0.002217113 -0.002882957 0.003183603 -0.002217113 -0.002882957 0.003297388 0.002217113 -0.002882957 0.003297388 -0.003361761 -0.002167582 -0.005680263 -0.003361761 -0.002167582 0.004319727 -0.003935337 -7.16104e-4 0.004319727 -0.003935337 -7.16104e-4 -0.005680263 -0.003909826 8.4441e-4 0.004319727 -0.003909826 8.4441e-4 -0.005680263 -0.003289043 0.00227636 0.004319727 -0.003289043 0.00227636 -0.005680263 -0.002167582 0.003361761 0.004319727 -0.002167582 0.003361761 -0.005680263 -7.16104e-4 0.003935337 0.004319727 -7.16104e-4 0.003935337 -0.005680263 8.4441e-4 0.003909826 0.004319727 8.4441e-4 0.003909826 -0.005680263 0.00227636 0.003289043 0.004319727 0.00227636 0.003289043 -0.005680263 0.003361761 0.002167582 0.004319727 0.003361761 0.002167582 -0.005680263 0.003935337 7.16104e-4 0.004319727 0.003935337 7.16104e-4 -0.005680263 0.003909826 -8.4441e-4 0.004319727 0.003909826 -8.4441e-4 -0.005680263 0.003289043 -0.00227636 0.004319727 0.003289043 -0.00227636 -0.005680263 0.002167582 -0.003361761 0.004319727 0.002167582 -0.003361761 -0.005680263 7.16103e-4 -0.003935337 0.004319727 7.16103e-4 -0.003935337 -0.005680263 -8.44409e-4 -0.003909826 0.004319727 -8.44409e-4 -0.003909826 -0.005680263 -0.00227636 -0.003289043 0.004319727 -0.00227636 -0.003289043 -0.005680263 -0.002991139 -0.001928627 0.004319727 -0.003501534 -6.37161e-4 0.004319727 -0.003478825 7.51323e-4 0.004319727 -0.002926468 0.002025365 0.004319727 -0.001928627 0.002991139 0.004319727 -6.37161e-4 0.003501534 0.004319727 7.51323e-4 0.003478825 0.004319727 0.002025365 0.002926468 0.004319727 0.002991139 0.001928627 0.004319727 0.003501534 6.37161e-4 0.004319727 0.003478825 -7.51322e-4 0.004319727 0.002926468 -0.002025365 0.004319727 0.001928627 -0.002991139 0.004319727 6.3716e-4 -0.003501534 0.004319727 -7.51322e-4 -0.003478825 0.004319727 -0.002025365 -0.002926468 0.004319727 -7.51322e-4 -0.003478825 -0.00413084 -0.002025365 -0.002926468 -0.00413084 -0.002999961 0 -0.00413084 -0.0028764 6.21222e-4 -0.00413084 -0.003478825 7.51323e-4 -0.00413084 -0.003501534 -6.37161e-4 -0.00413084 -0.002991139 -0.001928627 -0.00413084 6.3716e-4 -0.003501534 -0.00413084 0.001928627 -0.002991139 -0.00413084 0.002926468 -0.002025365 -0.00413084 0.003478825 -7.51322e-4 -0.00413084 0.0028764 -6.21221e-4 -0.00413084 0.002771615 -0.001148045 -0.00413084 0.002121269 -0.002121269 -0.00413084 -0.002771615 -0.001148045 -0.00413084 0.001148045 -0.002771615 -0.00413084 -0.002121269 -0.002121269 -0.00413084 -0.001148045 -0.002771615 -0.00413084 0 -0.002999961 -0.00413084 0.002999961 0 -0.00413084 0.003501534 6.37161e-4 -0.00413084 0.002991139 0.001928627 -0.00413084 0.002025365 0.002926468 -0.00413084 7.51323e-4 0.003478825 -0.00413084 -6.37161e-4 0.003501534 -0.00413084 -0.001928627 0.002991139 -0.00413084 -0.002926468 0.002025365 -0.00413084 -0.002771615 0.001148045 -0.00413084 -0.002121269 0.002121269 -0.00413084 0.002771615 0.001148045 -0.00413084 -0.001148045 0.002771615 -0.00413084 0.002121269 0.002121269 -0.00413084 0.001148045 0.002771615 -0.00413084 0 0.002999961 -0.00413084 -0.001674652 -0.00241971 -0.005680263 0.001674652 0.00241971 -0.005680263 0.001148045 0.002771615 -0.005680263 -0.002121269 -0.002121269 -0.005680263 -0.002771615 -0.001148045 -0.005680263 0 0.002999961 -0.005680263 -0.001148045 0.002771615 -0.005680263 -0.002999961 0 -0.005680263 -0.002121269 0.002121269 -0.005680263 -0.002771615 0.001148045 -0.005680263 0.002121269 0.002121269 -0.005680263 -0.001148045 -0.002771615 -0.005680263 0 -0.002999961 -0.005680263 0.002771615 0.001148045 -0.005680263 0.001148045 -0.002771615 -0.005680263 0.002999961 0 -0.005680263 0.002771615 -0.001148045 -0.005680263 0.002121269 -0.002121269 -0.005680263 -0.04870867 -0.04915863 0.003593802 -0.04819953 -0.0486412 0.004319727 -0.0464068 -0.04681938 0.004319727 -0.0464068 -0.04681938 -0.005680263 -0.04870867 -0.04915863 -0.005680263 -0.04907947 -0.04879373 0.003593802 -0.04907947 -0.04879373 -0.005680263 -0.04677766 -0.04645448 -0.005680263 -0.04677766 -0.04645448 0.004319727 -0.04857033 -0.0482763 0.004319727 -0.04742914 -0.04785829 -0.01271951 -0.04870867 -0.04915863 -0.01089519 -0.0464068 -0.04681938 -0.01271951 -0.04779994 -0.04749339 -0.01271951 -0.04677766 -0.04645448 -0.01271951 -0.04907947 -0.04879373 -0.01089519 -0.04919886 -0.03901678 0.003593802 -0.0486772 -0.03952163 0.004319727 -0.04684054 -0.04129916 0.004319727 -0.04684054 -0.04129916 -0.005680263 -0.04919886 -0.03901678 -0.005680263 -0.048837 -0.03864294 0.003593802 -0.048837 -0.03864294 -0.005680263 -0.04647874 -0.04092532 -0.005680263 -0.04647874 -0.04092532 0.004319727 -0.0483154 -0.03914779 0.004319727 -0.04788792 -0.04028552 -0.01271951 -0.04919886 -0.03901678 -0.01089519 -0.04684054 -0.04129916 -0.01271951 -0.04752612 -0.03991168 -0.01271951 -0.04647874 -0.04092532 -0.01271951 -0.048837 -0.03864294 -0.01089519 -0.02072447 -0.04596984 0.003208577 -0.02072447 -0.04581624 0.003463327 -0.02072447 -0.04525035 0.003463327 -0.02072447 -0.04525035 0.003119826 -0.02072447 -0.04584062 0.003119826 -0.02072447 -0.04134058 2.79233e-5 -0.02072447 -0.04134058 0.003103077 -0.02409666 -0.04134058 0.003103077 -0.02409666 -0.04134058 2.79233e-5 -0.02409666 -0.04634058 2.79233e-5 -0.02409666 -0.04634058 0.003103077 -0.02072447 -0.04634058 0.003103077 -0.02072447 -0.04634058 2.79233e-5 -0.02409666 -0.04525035 0.003463327 -0.02409666 -0.04243081 0.003463327 -0.02072447 -0.04243081 0.003463327 -0.03758543 -0.04525035 0.003463327 -0.03758543 -0.04243081 0.003463327 -0.03421324 -0.04243081 0.003463327 -0.03421324 -0.04525035 0.003463327 -0.03084105 -0.04525035 0.003463327 -0.03084105 -0.04243081 0.003463327 -0.02746886 -0.04243081 0.003463327 -0.02746886 -0.04525035 0.003463327 -0.04095762 -0.04605776 0.003183543 -0.04095762 -0.04634058 0.003103077 -0.04095762 -0.04634058 2.79233e-5 -0.04095762 -0.04605776 2.79233e-5 -0.03421324 -0.04634058 2.79233e-5 -0.03421324 -0.04634058 0.003103077 -0.03084105 -0.04634058 0.003103077 -0.03084105 -0.04634058 2.79233e-5 -0.02746886 -0.04634058 0.003103077 -0.02746886 -0.04634058 2.79233e-5 -0.03758543 -0.04134058 2.79233e-5 -0.03758543 -0.04134058 0.003103077 -0.04095762 -0.04134058 0.003103077 -0.04095762 -0.04134058 2.79233e-5 -0.03758543 -0.04634058 2.79233e-5 -0.03758543 -0.04634058 0.003103077 -0.03421324 -0.04134058 2.79233e-5 -0.03421324 -0.04134058 0.003103077 -0.03084105 -0.04134058 2.79233e-5 -0.03084105 -0.04134058 0.003103077 -0.02746886 -0.04134058 2.79233e-5 -0.02746886 -0.04134058 0.003103077 -0.03758543 -0.04581624 0.003463327 -0.03421324 -0.04581624 0.003463327 -0.03084105 -0.04581624 0.003463327 -0.02746886 -0.04581624 0.003463327 -0.02409666 -0.04581624 0.003463327 -0.02072447 -0.04186493 0.003463327 -0.02072447 -0.04171139 0.003208577 -0.02072447 -0.04184061 0.003119826 -0.02072447 -0.04243081 0.003119826 -0.02746886 -0.04186493 0.003463327 -0.02409666 -0.04186493 0.003463327 -0.03084105 -0.04186493 0.003463327 -0.03421324 -0.04186493 0.003463327 -0.03758543 -0.04186493 0.003463327 -0.04081249 -0.04184061 0.003119826 -0.03758543 -0.04184061 0.003119826 -0.03758543 -0.04184061 2.79233e-5 -0.04081249 -0.04184061 2.79233e-5 -0.02409666 -0.04584062 2.79233e-5 -0.02072447 -0.04584062 2.79233e-5 -0.02409666 -0.04584062 0.003119826 -0.02409666 -0.04243081 0.003119826 -0.02409666 -0.04184061 0.003119826 -0.02409666 -0.04525035 0.003119826 -0.03758543 -0.04525035 0.003119826 -0.03421324 -0.04525035 0.003119826 -0.03421324 -0.04243081 0.003119826 -0.03758543 -0.04243081 0.003119826 -0.03084105 -0.04525035 0.003119826 -0.02746886 -0.04525035 0.003119826 -0.02746886 -0.04243081 0.003119826 -0.03084105 -0.04243081 0.003119826 -0.04081249 -0.04584062 0.003119826 -0.03758543 -0.04584062 0.003119826 -0.040421 -0.04525035 0.003119826 -0.04042226 -0.04525655 0.003119826 -0.03421324 -0.04584062 0.003119826 -0.03084105 -0.04584062 0.003119826 -0.02746886 -0.04584062 0.003119826 -0.040421 -0.04243081 0.003119826 -0.04042226 -0.04242467 0.003119826 -0.03421324 -0.04184061 0.003119826 -0.03084105 -0.04184061 0.003119826 -0.02746886 -0.04184061 0.003119826 -0.03758543 -0.04584062 2.79233e-5 -0.04081249 -0.04584062 2.79233e-5 -0.03421324 -0.04584062 2.79233e-5 -0.03084105 -0.04584062 2.79233e-5 -0.02746886 -0.04584062 2.79233e-5 -0.02072447 -0.04184061 2.79233e-5 -0.02409666 -0.04184061 2.79233e-5 -0.02746886 -0.04184061 2.79233e-5 -0.03084105 -0.04184061 2.79233e-5 -0.03421324 -0.04184061 2.79233e-5 -0.04042226 -0.04525655 0.003463327 -0.040421 -0.04525035 0.003463327 -0.04079622 -0.04581624 0.003463327 -0.04042226 -0.04242467 0.003463327 -0.04079622 -0.04186493 0.003463327 -0.040421 -0.04243081 0.003463327 -0.04095762 -0.04162341 2.79233e-5 -0.04095762 -0.04162341 0.003183543 -0.04095762 -0.04162341 0.003297388 -0.04095762 -0.04605776 0.003297388 -0.041673 -0.04047882 -0.005680263 -0.041673 -0.04047882 0.004319727 -0.04312449 -0.03990525 0.004319727 -0.04312449 -0.03990525 -0.005680263 -0.044685 -0.03993076 0.004319727 -0.044685 -0.03993076 -0.005680263 -0.04611694 -0.04055148 0.004319727 -0.04611694 -0.04055148 -0.005680263 -0.04720234 -0.041673 0.004319727 -0.04720234 -0.041673 -0.005680263 -0.04777598 -0.04312449 0.004319727 -0.04777598 -0.04312449 -0.005680263 -0.04775047 -0.044685 0.004319727 -0.04775047 -0.044685 -0.005680263 -0.04712969 -0.04611694 0.004319727 -0.04712969 -0.04611694 -0.005680263 -0.04600816 -0.04720234 0.004319727 -0.04600816 -0.04720234 -0.005680263 -0.04455667 -0.04777598 0.004319727 -0.04455667 -0.04777598 -0.005680263 -0.04299616 -0.04775047 0.004319727 -0.04299616 -0.04775047 -0.005680263 -0.04156422 -0.04712969 0.004319727 -0.04156422 -0.04712969 -0.005680263 -0.04047882 -0.04600816 0.004319727 -0.04047882 -0.04600816 -0.005680263 -0.03990525 -0.04455667 0.004319727 -0.03990525 -0.04455667 -0.005680263 -0.03993076 -0.04299616 0.004319727 -0.03993076 -0.04299616 -0.005680263 -0.04055148 -0.04156422 0.004319727 -0.04055148 -0.04156422 -0.005680263 -0.04191195 -0.04084944 0.004319727 -0.04320341 -0.04033905 0.004319727 -0.0445919 -0.04036176 0.004319727 -0.04586601 -0.04091411 0.004319727 -0.04683178 -0.04191195 0.004319727 -0.04734212 -0.04320341 0.004319727 -0.04731941 -0.0445919 0.004319727 -0.04676711 -0.04586601 0.004319727 -0.04576921 -0.04683178 0.004319727 -0.04447776 -0.04734212 0.004319727 -0.04308927 -0.04731941 0.004319727 -0.04181516 -0.04676711 0.004319727 -0.04084944 -0.04576921 0.004319727 -0.04033905 -0.04447776 0.004319727 -0.04036176 -0.04308927 0.004319727 -0.04091411 -0.04181516 0.004319727 -0.04036176 -0.04308927 -0.00413084 -0.04091411 -0.04181516 -0.00413084 -0.04384058 -0.04084062 -0.00413084 -0.04446184 -0.04096418 -0.00413084 -0.0445919 -0.04036176 -0.00413084 -0.04320341 -0.04033905 -0.00413084 -0.04191195 -0.04084944 -0.00413084 -0.04033905 -0.04447776 -0.00413084 -0.04084944 -0.04576921 -0.00413084 -0.04181516 -0.04676711 -0.00413084 -0.04308927 -0.04731941 -0.00413084 -0.04321938 -0.04671704 -0.00413084 -0.04269254 -0.04661226 -0.00413084 -0.04171925 -0.04596191 -0.00413084 -0.04269254 -0.04106897 -0.00413084 -0.04106897 -0.04498863 -0.00413084 -0.04171925 -0.04171925 -0.00413084 -0.04106897 -0.04269254 -0.00413084 -0.04084062 -0.04384058 -0.00413084 -0.04384058 -0.0468406 -0.00413084 -0.04447776 -0.04734212 -0.00413084 -0.04576921 -0.04683178 -0.00413084 -0.04676711 -0.04586601 -0.00413084 -0.04731941 -0.0445919 -0.00413084 -0.04734212 -0.04320341 -0.00413084 -0.04683178 -0.04191195 -0.00413084 -0.04586601 -0.04091411 -0.00413084 -0.04498863 -0.04106897 -0.00413084 -0.04596191 -0.04171925 -0.00413084 -0.04498863 -0.04661226 -0.00413084 -0.04661226 -0.04269254 -0.00413084 -0.04596191 -0.04596191 -0.00413084 -0.04661226 -0.04498863 -0.00413084 -0.0468406 -0.04384058 -0.00413084 -0.04142087 -0.04216587 -0.005680263 -0.04626035 -0.04551529 -0.005680263 -0.04661226 -0.04498863 -0.005680263 -0.04171925 -0.04171925 -0.005680263 -0.04269254 -0.04106897 -0.005680263 -0.0468406 -0.04384058 -0.005680263 -0.04661226 -0.04269254 -0.005680263 -0.04384058 -0.04084062 -0.005680263 -0.04596191 -0.04171925 -0.005680263 -0.04498863 -0.04106897 -0.005680263 -0.04596191 -0.04596191 -0.005680263 -0.04106897 -0.04269254 -0.005680263 -0.04084062 -0.04384058 -0.005680263 -0.04498863 -0.04661226 -0.005680263 -0.04106897 -0.04498863 -0.005680263 -0.04384058 -0.0468406 -0.005680263 -0.04269254 -0.04661226 -0.005680263 -0.04171925 -0.04596191 -0.005680263 0.04870867 -0.03852254 0.003593802 0.04819953 -0.03903996 0.004319727 0.0464068 -0.04086178 0.004319727 0.0464068 -0.04086178 -0.005680263 0.04870867 -0.03852254 -0.005680263 0.04907947 -0.03888744 0.003593802 0.04907947 -0.03888744 -0.005680263 0.04677766 -0.04122668 -0.005680263 0.04677766 -0.04122668 0.004319727 0.04857033 -0.03940486 0.004319727 0.04742914 -0.03982287 -0.01271951 0.04870867 -0.03852254 -0.01089519 0.0464068 -0.04086178 -0.01271951 0.04779994 -0.04018777 -0.01271951 0.04677766 -0.04122668 -0.01271951 0.04907947 -0.03888744 -0.01089519 0.04919886 -0.04866439 0.003593802 0.0486772 -0.04815953 0.004319727 0.04684054 -0.046382 0.004319727 0.04684054 -0.046382 -0.005680263 0.04919886 -0.04866439 -0.005680263 0.048837 -0.04903823 0.003593802 0.048837 -0.04903823 -0.005680263 0.04647874 -0.04675585 -0.005680263 0.04647874 -0.04675585 0.004319727 0.0483154 -0.04853338 0.004319727 0.04788792 -0.04739564 -0.01271951 0.04919886 -0.04866439 -0.01089519 0.04684054 -0.046382 -0.01271951 0.04752612 -0.04776948 -0.01271951 0.04647874 -0.04675585 -0.01271951 0.048837 -0.04903823 -0.01089519 0.02072447 -0.04171139 0.003208577 0.02072447 -0.04186493 0.003463327 0.02072447 -0.04243081 0.003463327 0.02072447 -0.04243081 0.003119826 0.02072447 -0.04184061 0.003119826 0.02072447 -0.04634058 2.79233e-5 0.02072447 -0.04634058 0.003103077 0.02409666 -0.04634058 0.003103077 0.02409666 -0.04634058 2.79233e-5 0.02409666 -0.04134058 2.79233e-5 0.02409666 -0.04134058 0.003103077 0.02072447 -0.04134058 0.003103077 0.02072447 -0.04134058 2.79233e-5 0.02409666 -0.04243081 0.003463327 0.02409666 -0.04525035 0.003463327 0.02072447 -0.04525035 0.003463327 0.03758543 -0.04243081 0.003463327 0.03758543 -0.04525035 0.003463327 0.03421324 -0.04525035 0.003463327 0.03421324 -0.04243081 0.003463327 0.03084105 -0.04243081 0.003463327 0.03084105 -0.04525035 0.003463327 0.02746886 -0.04525035 0.003463327 0.02746886 -0.04243081 0.003463327 0.04095762 -0.04162341 0.003183543 0.04095762 -0.04134058 0.003103077 0.04095762 -0.04134058 2.79233e-5 0.04095762 -0.04162341 2.79233e-5 0.03421324 -0.04134058 2.79233e-5 0.03421324 -0.04134058 0.003103077 0.03084105 -0.04134058 0.003103077 0.03084105 -0.04134058 2.79233e-5 0.02746886 -0.04134058 0.003103077 0.02746886 -0.04134058 2.79233e-5 0.03758543 -0.04634058 2.79233e-5 0.03758543 -0.04634058 0.003103077 0.04095762 -0.04634058 0.003103077 0.04095762 -0.04634058 2.79233e-5 0.03758543 -0.04134058 2.79233e-5 0.03758543 -0.04134058 0.003103077 0.03421324 -0.04634058 2.79233e-5 0.03421324 -0.04634058 0.003103077 0.03084105 -0.04634058 2.79233e-5 0.03084105 -0.04634058 0.003103077 0.02746886 -0.04634058 2.79233e-5 0.02746886 -0.04634058 0.003103077 0.03758543 -0.04186493 0.003463327 0.03421324 -0.04186493 0.003463327 0.03084105 -0.04186493 0.003463327 0.02746886 -0.04186493 0.003463327 0.02409666 -0.04186493 0.003463327 0.02072447 -0.04581624 0.003463327 0.02072447 -0.04596984 0.003208577 0.02072447 -0.04584062 0.003119826 0.02072447 -0.04525035 0.003119826 0.02746886 -0.04581624 0.003463327 0.02409666 -0.04581624 0.003463327 0.03084105 -0.04581624 0.003463327 0.03421324 -0.04581624 0.003463327 0.03758543 -0.04581624 0.003463327 0.04081249 -0.04584062 0.003119826 0.03758543 -0.04584062 0.003119826 0.03758543 -0.04584062 2.79233e-5 0.04081249 -0.04584062 2.79233e-5 0.02409666 -0.04184061 2.79233e-5 0.02072447 -0.04184061 2.79233e-5 0.02409666 -0.04184061 0.003119826 0.02409666 -0.04525035 0.003119826 0.02409666 -0.04584062 0.003119826 0.02409666 -0.04243081 0.003119826 0.03758543 -0.04243081 0.003119826 0.03421324 -0.04243081 0.003119826 0.03421324 -0.04525035 0.003119826 0.03758543 -0.04525035 0.003119826 0.03084105 -0.04243081 0.003119826 0.02746886 -0.04243081 0.003119826 0.02746886 -0.04525035 0.003119826 0.03084105 -0.04525035 0.003119826 0.04081249 -0.04184061 0.003119826 0.03758543 -0.04184061 0.003119826 0.040421 -0.04243081 0.003119826 0.04042226 -0.04242467 0.003119826 0.03421324 -0.04184061 0.003119826 0.03084105 -0.04184061 0.003119826 0.02746886 -0.04184061 0.003119826 0.040421 -0.04525035 0.003119826 0.04042226 -0.04525655 0.003119826 0.03421324 -0.04584062 0.003119826 0.03084105 -0.04584062 0.003119826 0.02746886 -0.04584062 0.003119826 0.03758543 -0.04184061 2.79233e-5 0.04081249 -0.04184061 2.79233e-5 0.03421324 -0.04184061 2.79233e-5 0.03084105 -0.04184061 2.79233e-5 0.02746886 -0.04184061 2.79233e-5 0.02072447 -0.04584062 2.79233e-5 0.02409666 -0.04584062 2.79233e-5 0.02746886 -0.04584062 2.79233e-5 0.03084105 -0.04584062 2.79233e-5 0.03421324 -0.04584062 2.79233e-5 0.04042226 -0.04242467 0.003463327 0.040421 -0.04243081 0.003463327 0.04079622 -0.04186493 0.003463327 0.04042226 -0.04525655 0.003463327 0.04079622 -0.04581624 0.003463327 0.040421 -0.04525035 0.003463327 0.04095762 -0.04605776 2.79233e-5 0.04095762 -0.04605776 0.003183543 0.04095762 -0.04605776 0.003297388 0.04095762 -0.04162341 0.003297388 0.041673 -0.04720234 -0.005680263 0.041673 -0.04720234 0.004319727 0.04312449 -0.04777598 0.004319727 0.04312449 -0.04777598 -0.005680263 0.044685 -0.04775047 0.004319727 0.044685 -0.04775047 -0.005680263 0.04611694 -0.04712969 0.004319727 0.04611694 -0.04712969 -0.005680263 0.04720234 -0.04600816 0.004319727 0.04720234 -0.04600816 -0.005680263 0.04777598 -0.04455667 0.004319727 0.04777598 -0.04455667 -0.005680263 0.04775047 -0.04299616 0.004319727 0.04775047 -0.04299616 -0.005680263 0.04712969 -0.04156422 0.004319727 0.04712969 -0.04156422 -0.005680263 0.04600816 -0.04047882 0.004319727 0.04600816 -0.04047882 -0.005680263 0.04455667 -0.03990525 0.004319727 0.04455667 -0.03990525 -0.005680263 0.04299616 -0.03993076 0.004319727 0.04299616 -0.03993076 -0.005680263 0.04156422 -0.04055148 0.004319727 0.04156422 -0.04055148 -0.005680263 0.04047882 -0.041673 0.004319727 0.04047882 -0.041673 -0.005680263 0.03990525 -0.04312449 0.004319727 0.03990525 -0.04312449 -0.005680263 0.03993076 -0.044685 0.004319727 0.03993076 -0.044685 -0.005680263 0.04055148 -0.04611694 0.004319727 0.04055148 -0.04611694 -0.005680263 0.04191195 -0.04683178 0.004319727 0.04320341 -0.04734212 0.004319727 0.0445919 -0.04731941 0.004319727 0.04586601 -0.04676711 0.004319727 0.04683178 -0.04576921 0.004319727 0.04734212 -0.04447776 0.004319727 0.04731941 -0.04308927 0.004319727 0.04676711 -0.04181516 0.004319727 0.04576921 -0.04084944 0.004319727 0.04447776 -0.04033905 0.004319727 0.04308927 -0.04036176 0.004319727 0.04181516 -0.04091411 0.004319727 0.04084944 -0.04191195 0.004319727 0.04033905 -0.04320341 0.004319727 0.04036176 -0.0445919 0.004319727 0.04091411 -0.04586601 0.004319727 0.04036176 -0.0445919 -0.00413084 0.04091411 -0.04586601 -0.00413084 0.04384058 -0.0468406 -0.00413084 0.04446184 -0.04671704 -0.00413084 0.0445919 -0.04731941 -0.00413084 0.04320341 -0.04734212 -0.00413084 0.04191195 -0.04683178 -0.00413084 0.04033905 -0.04320341 -0.00413084 0.04084944 -0.04191195 -0.00413084 0.04181516 -0.04091411 -0.00413084 0.04308927 -0.04036176 -0.00413084 0.04321938 -0.04096418 -0.00413084 0.04269254 -0.04106897 -0.00413084 0.04171925 -0.04171925 -0.00413084 0.04269254 -0.04661226 -0.00413084 0.04106897 -0.04269254 -0.00413084 0.04171925 -0.04596191 -0.00413084 0.04106897 -0.04498863 -0.00413084 0.04084062 -0.04384058 -0.00413084 0.04384058 -0.04084062 -0.00413084 0.04447776 -0.04033905 -0.00413084 0.04576921 -0.04084944 -0.00413084 0.04676711 -0.04181516 -0.00413084 0.04731941 -0.04308927 -0.00413084 0.04734212 -0.04447776 -0.00413084 0.04683178 -0.04576921 -0.00413084 0.04586601 -0.04676711 -0.00413084 0.04498863 -0.04661226 -0.00413084 0.04596191 -0.04596191 -0.00413084 0.04498863 -0.04106897 -0.00413084 0.04661226 -0.04498863 -0.00413084 0.04596191 -0.04171925 -0.00413084 0.04661226 -0.04269254 -0.00413084 0.0468406 -0.04384058 -0.00413084 0.04142087 -0.04551529 -0.005680263 0.04626035 -0.04216587 -0.005680263 0.04661226 -0.04269254 -0.005680263 0.04171925 -0.04596191 -0.005680263 0.04269254 -0.04661226 -0.005680263 0.0468406 -0.04384058 -0.005680263 0.04661226 -0.04498863 -0.005680263 0.04384058 -0.0468406 -0.005680263 0.04596191 -0.04596191 -0.005680263 0.04498863 -0.04661226 -0.005680263 0.04596191 -0.04171925 -0.005680263 0.04106897 -0.04498863 -0.005680263 0.04084062 -0.04384058 -0.005680263 0.04498863 -0.04106897 -0.005680263 0.04106897 -0.04269254 -0.005680263 0.04384058 -0.04084062 -0.005680263 0.04269254 -0.04106897 -0.005680263 0.04171925 -0.04171925 -0.005680263 -0.005317986 -0.09254932 0.003593802 -0.004800558 -0.09204012 0.004319727 -0.002978742 -0.09024745 0.004319727 -0.002978742 -0.09024745 -0.005680263 -0.005317986 -0.09254932 -0.005680263 -0.004953145 -0.09292012 0.003593802 -0.004953145 -0.09292012 -0.005680263 -0.002613842 -0.09061825 -0.005680263 -0.002613842 -0.09061825 0.004319727 -0.004435718 -0.09241098 0.004319727 -0.004017651 -0.09126973 -0.01271951 -0.005317986 -0.09254932 -0.01089519 -0.002978742 -0.09024745 -0.01271951 -0.003652751 -0.09164059 -0.01271951 -0.002613842 -0.09061825 -0.01271951 -0.004953145 -0.09292012 -0.01089519 0.004823744 -0.09303945 0.003593802 0.004318952 -0.09251785 0.004319727 0.002541422 -0.09068119 0.004319727 0.002541422 -0.09068119 -0.005680263 0.004823744 -0.09303945 -0.005680263 0.005197584 -0.09267765 0.003593802 0.005197584 -0.09267765 -0.005680263 0.002915263 -0.09031939 -0.005680263 0.002915263 -0.09031939 0.004319727 0.004692733 -0.09215605 0.004319727 0.003555059 -0.09172856 -0.01271951 0.004823744 -0.09303945 -0.01089519 0.002541422 -0.09068119 -0.01271951 0.003928899 -0.09136676 -0.01271951 0.002915263 -0.09031939 -0.01271951 0.005197584 -0.09267765 -0.01089519 -0.002129197 -0.06456512 0.003208577 -0.001975595 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003119826 -0.001999974 -0.06456512 0.003119826 0.002499997 -0.06456512 2.79224e-5 0.002499997 -0.06456512 0.003103077 0.002499997 -0.06793731 0.003103077 0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 0.003103077 -0.002499997 -0.06456512 0.003103077 -0.002499997 -0.06456512 2.79224e-5 -0.001409769 -0.06793731 0.003463327 0.001409769 -0.06793731 0.003463327 0.001409769 -0.06456512 0.003463327 -0.001409769 -0.08142608 0.003463327 0.001409769 -0.08142608 0.003463327 0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07468169 0.003463327 0.001409769 -0.07468169 0.003463327 0.001409769 -0.0713095 0.003463327 -0.001409769 -0.0713095 0.003463327 -0.002217173 -0.08479827 0.003183543 -0.002499997 -0.08479827 0.003103077 -0.002499997 -0.08479827 2.79224e-5 -0.002217173 -0.08479827 2.79224e-5 -0.002499997 -0.07805389 2.79224e-5 -0.002499997 -0.07805389 0.003103077 -0.002499997 -0.07468169 0.003103077 -0.002499997 -0.07468169 2.79224e-5 -0.002499997 -0.0713095 0.003103077 -0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.08142608 2.79224e-5 0.002499997 -0.08142608 0.003103077 0.002499997 -0.08479827 0.003103077 0.002499997 -0.08479827 2.79224e-5 -0.002499997 -0.08142608 2.79224e-5 -0.002499997 -0.08142608 0.003103077 0.002499997 -0.07805389 2.79224e-5 0.002499997 -0.07805389 0.003103077 0.002499997 -0.07468169 2.79224e-5 0.002499997 -0.07468169 0.003103077 0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.0713095 0.003103077 -0.001975595 -0.08142608 0.003463327 -0.001975595 -0.07805389 0.003463327 -0.001975595 -0.07468169 0.003463327 -0.001975595 -0.0713095 0.003463327 -0.001975595 -0.06793731 0.003463327 0.001975595 -0.06456512 0.003463327 0.002129197 -0.06456512 0.003208577 0.001999974 -0.06456512 0.003119826 0.001409769 -0.06456512 0.003119826 0.001975595 -0.0713095 0.003463327 0.001975595 -0.06793731 0.003463327 0.001975595 -0.07468169 0.003463327 0.001975595 -0.07805389 0.003463327 0.001975595 -0.08142608 0.003463327 0.001999974 -0.08465313 0.003119826 0.001999974 -0.08142608 0.003119826 0.001999974 -0.08142608 2.79224e-5 0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.06793731 2.79224e-5 -0.001999974 -0.06456512 2.79224e-5 -0.001999974 -0.06793731 0.003119826 0.001409769 -0.06793731 0.003119826 0.001999974 -0.06793731 0.003119826 -0.001409769 -0.06793731 0.003119826 -0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07805389 0.003119826 0.001409769 -0.07805389 0.003119826 0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07468169 0.003119826 -0.001409769 -0.0713095 0.003119826 0.001409769 -0.0713095 0.003119826 0.001409769 -0.07468169 0.003119826 -0.001999974 -0.08465313 0.003119826 -0.001999974 -0.08142608 0.003119826 -0.001409769 -0.08426165 0.003119826 -0.001415908 -0.08426284 0.003119826 -0.001999974 -0.07805389 0.003119826 -0.001999974 -0.07468169 0.003119826 -0.001999974 -0.0713095 0.003119826 0.001409769 -0.08426165 0.003119826 0.001415908 -0.08426284 0.003119826 0.001999974 -0.07805389 0.003119826 0.001999974 -0.07468169 0.003119826 0.001999974 -0.0713095 0.003119826 -0.001999974 -0.08142608 2.79224e-5 -0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.07805389 2.79224e-5 -0.001999974 -0.07468169 2.79224e-5 -0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.06456512 2.79224e-5 0.001999974 -0.06793731 2.79224e-5 0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.07468169 2.79224e-5 0.001999974 -0.07805389 2.79224e-5 -0.001415908 -0.08426284 0.003463327 -0.001409769 -0.08426165 0.003463327 -0.001975595 -0.08463686 0.003463327 0.001415908 -0.08426284 0.003463327 0.001975595 -0.08463686 0.003463327 0.001409769 -0.08426165 0.003463327 0.002217113 -0.08479827 2.79224e-5 0.002217113 -0.08479827 0.003183543 0.002217113 -0.08479827 0.003297388 -0.002217173 -0.08479827 0.003297388 0.003361761 -0.08551365 -0.005680263 0.003361761 -0.08551365 0.004319727 0.003935337 -0.08696514 0.004319727 0.003935337 -0.08696514 -0.005680263 0.003909826 -0.08852565 0.004319727 0.003909826 -0.08852565 -0.005680263 0.003289043 -0.08995759 0.004319727 0.003289043 -0.08995759 -0.005680263 0.002167582 -0.09104299 0.004319727 0.002167582 -0.09104299 -0.005680263 7.16105e-4 -0.09161663 0.004319727 7.16105e-4 -0.09161663 -0.005680263 -8.44412e-4 -0.09159106 0.004319727 -8.44412e-4 -0.09159106 -0.005680263 -0.00227636 -0.09097033 0.004319727 -0.00227636 -0.09097033 -0.005680263 -0.003361761 -0.08984881 0.004319727 -0.003361761 -0.08984881 -0.005680263 -0.003935337 -0.08839732 0.004319727 -0.003935337 -0.08839732 -0.005680263 -0.003909826 -0.08683681 0.004319727 -0.003909826 -0.08683681 -0.005680263 -0.003289043 -0.08540487 0.004319727 -0.003289043 -0.08540487 -0.005680263 -0.002167582 -0.08431947 0.004319727 -0.002167582 -0.08431947 -0.005680263 -7.16105e-4 -0.08374583 0.004319727 -7.16105e-4 -0.08374583 -0.005680263 8.44408e-4 -0.08377134 0.004319727 8.44408e-4 -0.08377134 -0.005680263 0.00227636 -0.08439213 0.004319727 0.00227636 -0.08439213 -0.005680263 0.002991139 -0.0857526 0.004319727 0.003501534 -0.08704406 0.004319727 0.003478825 -0.08843255 0.004319727 0.002926468 -0.08970665 0.004319727 0.001928627 -0.09067237 0.004319727 6.37162e-4 -0.09118276 0.004319727 -7.51324e-4 -0.09116005 0.004319727 -0.002025425 -0.09060776 0.004319727 -0.002991139 -0.08960986 0.004319727 -0.003501534 -0.0883184 0.004319727 -0.003478825 -0.08692991 0.004319727 -0.002926468 -0.0856558 0.004319727 -0.001928627 -0.08469003 0.004319727 -6.37159e-4 -0.08417969 0.004319727 7.51324e-4 -0.0842024 0.004319727 0.002025425 -0.0847547 0.004319727 7.51324e-4 -0.0842024 -0.00413084 0.002025425 -0.0847547 -0.00413084 0.002999961 -0.08768123 -0.00413084 0.0028764 -0.08830243 -0.00413084 0.003478825 -0.08843255 -0.00413084 0.003501534 -0.08704406 -0.00413084 0.002991139 -0.0857526 -0.00413084 -6.37159e-4 -0.08417969 -0.00413084 -0.001928627 -0.08469003 -0.00413084 -0.002926468 -0.0856558 -0.00413084 -0.003478825 -0.08692991 -0.00413084 -0.0028764 -0.08706003 -0.00413084 -0.002771615 -0.08653318 -0.00413084 -0.002121269 -0.0855599 -0.00413084 0.002771615 -0.08653318 -0.00413084 -0.001148045 -0.08490961 -0.00413084 0.002121269 -0.0855599 -0.00413084 0.001148045 -0.08490961 -0.00413084 0 -0.08468121 -0.00413084 -0.002999961 -0.08768123 -0.00413084 -0.003501534 -0.0883184 -0.00413084 -0.002991139 -0.08960986 -0.00413084 -0.002025425 -0.09060776 -0.00413084 -7.51324e-4 -0.09116005 -0.00413084 6.37162e-4 -0.09118276 -0.00413084 0.001928627 -0.09067237 -0.00413084 0.002926468 -0.08970665 -0.00413084 0.002771615 -0.08882927 -0.00413084 0.002121269 -0.08980256 -0.00413084 -0.002771615 -0.08882927 -0.00413084 0.001148045 -0.09045284 -0.00413084 -0.002121269 -0.08980256 -0.00413084 -0.001148045 -0.09045284 -0.00413084 0 -0.09068125 -0.00413084 0.001674652 -0.08526146 -0.005680263 -0.001674652 -0.09010094 -0.005680263 -0.001148045 -0.09045284 -0.005680263 0.002121269 -0.0855599 -0.005680263 0.002771615 -0.08653318 -0.005680263 0 -0.09068125 -0.005680263 0.001148045 -0.09045284 -0.005680263 0.002999961 -0.08768123 -0.005680263 0.002121269 -0.08980256 -0.005680263 0.002771615 -0.08882927 -0.005680263 -0.002121269 -0.08980256 -0.005680263 0.001148045 -0.08490961 -0.005680263 0 -0.08468121 -0.005680263 -0.002771615 -0.08882927 -0.005680263 -0.001148045 -0.08490961 -0.005680263 -0.002999961 -0.08768123 -0.005680263 -0.002771615 -0.08653318 -0.005680263 -0.002121269 -0.0855599 -0.005680263</float_array>\n          <technique_common>\n            <accessor source=\"#motor_mount-mesh-positions-array\" count=\"968\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"motor_mount-mesh-normals\">\n          <float_array id=\"motor_mount-mesh-normals-array\" count=\"2643\">0.7013857 -0.712782 -4.90183e-7 0.7013856 -0.7127822 0 0.7013857 -0.712782 0 -0.7013856 0.7127821 0 -0.7013856 0.712782 0 -0.7013857 0.7127819 0 0.712782 0.7013857 0 0.7127824 0.7013853 0 0.701386 -0.7127817 0 0.7013857 -0.712782 0 0.7013853 -0.7127824 0 -0.7013857 0.712782 0 -0.7013857 0.712782 0 -0.7127825 -0.7013853 0 -0.712782 -0.7013857 0 0 0 -1 0.5040131 0.495955 -0.7071065 0.5040118 0.4959551 -0.7071073 0.7127831 0.7013846 0 0.7127822 0.7013854 0 0.5040128 0.4959534 0.7071079 0.5040138 0.4959544 0.7071064 0 0 1 1.70996e-7 0 1 0.7185755 0.6954489 -4.90183e-7 0.7185751 0.6954494 0 0.7185753 0.6954492 0 -0.7185752 -0.6954492 0 -0.7185752 -0.6954494 0 -0.7185751 -0.6954494 0 -0.6954478 0.7185766 0 -0.6954493 0.7185752 0 0.7185752 0.6954494 0 0.7185753 0.6954492 0 -0.7185751 -0.6954494 0 -0.7185754 -0.6954491 0 -0.7185751 -0.6954494 1.76021e-7 0.6954499 -0.7185747 0 0.6954489 -0.7185757 0 2.39887e-6 0 -1 -1.19943e-6 0 -1 -0.491756 0.5081108 -0.7071064 -0.4917582 0.5081082 -0.7071067 -0.6954489 0.7185757 0 -0.6954481 0.7185765 0 -0.4917567 0.5081105 0.7071062 -0.4917556 0.5081106 0.707107 -1.70996e-7 0 1 0 -1 1.26179e-5 0 -1 0 6.6104e-6 -1 -1.87907e-5 -1 0 0 1 -7.01628e-7 -3.02851e-7 1 -3.50814e-7 0 1.91311e-7 0 1 0 1 0 1 0 1.51425e-7 1 0 0 1 0 -1.51425e-7 1 1.75407e-7 -1.51425e-7 1 0 -3.02851e-7 -1 0 0 1 0 1.51425e-7 -1 1.75407e-7 -1.51425e-7 -1 0 -1.51425e-7 0 -1 6.30892e-6 0 -1 -3.4709e-5 0 0 1 -9.53226e-7 0 1 -4.3228e-7 0 1 1 -1.82302e-7 0 1 -2.73454e-7 0 -1 1.74458e-7 0 -1 0 0 -3.84519e-7 0 -1 3.63647e-5 0 -1 4.12282e-7 0 -1 -9.13896e-7 0 -1 4.37606e-7 0 -1 -2.41265e-7 0 -1 2.48112e-5 0 -1 9.13897e-7 0 -1 -1.77951e-7 0 -1 5.57993e-7 0 -1 -1 -1.82302e-7 0 -1 3.48915e-7 2.25909e-7 -1 0 0 -1 -3.48915e-7 0 -1 0 2.25909e-7 -1 0 -1.50606e-7 -1 3.48915e-7 0 -1 0 -1.50606e-7 1 0 -1.50606e-7 1 -1.74458e-7 0 1 0 1.50606e-7 1 2.61686e-7 -1.50606e-7 1 0 1.50606e-7 1 0 0 -1.04161e-4 0 1 -2.86813e-7 0 1 1 -1.75407e-7 0 0 0 -1 0 0 -1 -2.05466e-5 0 1 -5.0237e-6 -1 0 1.44137e-5 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 -1.96265e-7 0 1 0 0 -3.3031e-7 1 0 -3.3031e-7 1 0 -6.6062e-7 1 0 -6.6062e-7 1 0 0 -1 -2.32458e-5 -8.57603e-6 -1 2.3246e-5 -0.5663009 1.02645e-6 0.8241986 -0.5663006 0 0.8241988 -0.5663008 0 0.8241987 0.5663009 -3.17949e-7 0.8241986 0.5663 -4.23932e-7 0.8241993 -0.5663006 1.58975e-7 0.8241989 -0.5663008 0 0.8241987 -0.5663006 0 0.8241989 -0.5663003 0 0.824199 -0.5663007 0 0.8241987 -0.5663002 0 0.8241991 -0.5663003 0 0.8241991 -0.5663006 0 0.8241989 0.5662989 -1.20828e-7 0.8242 0.5663 0 0.8241991 0.5663019 -2.45611e-7 0.824198 0.5663002 0 0.8241991 0.5663006 0 0.8241989 0.5663006 0 0.8241989 0.5663001 0 0.8241992 0.5663002 0 0.8241991 0.5662998 0 0.8241994 0.5663006 1.58975e-7 0.8241989 0.5662993 0 0.8241998 -0.5555694 0.8314703 0 -0.5555698 0.83147 0 -0.555571 0.8314692 -2.03536e-6 -0.55557 0.8314698 0 -0.5555703 0.8314697 0 -0.5555699 0.8314698 -3.3805e-6 -0.1951152 0.9807804 0 0.195197 0.9807642 0 0.1951962 0.9807642 0 0.5555705 0.8314694 0 0.555571 0.8314692 0 0.5555695 0.8314701 0 0.5555721 0.8314684 0 0.5555698 0.83147 -9.83177e-7 0.5555709 0.8314692 -2.48229e-6 -0.930014 -0.367524 0 -0.9300139 -0.3675245 0 -0.9998663 0.01635259 0 -0.9174984 0.3977398 0 -0.9174985 0.3977394 0 -0.6954492 0.7185752 0 -0.3675243 0.9300139 0 -0.3675245 0.9300138 0 0.01635265 0.9998663 0 0.01635265 0.9998663 0 0.3977396 0.9174984 0 0.3977397 0.9174984 0 0.930014 0.3675242 0 0.9300139 0.3675246 0 0.9998663 -0.01635259 0 0.9998663 -0.01635211 0 0.9174985 -0.3977394 0 0.9174983 -0.3977398 0 0.6954492 -0.7185752 0 0.3675244 -0.9300139 0 0.3675245 -0.9300138 0 -0.01635265 -0.9998664 0 -0.01635265 -0.9998664 0 -0.3977397 -0.9174984 0 -0.3977397 -0.9174984 0 -0.7185753 -0.6954492 0 -0.7185752 -0.6954493 0 2.83943e-7 0 1 -1.34742e-6 0 1 1.89296e-7 0 1 -3.7859e-7 0 1 -1.13577e-6 0 1 6.7371e-7 0 1 1.26321e-7 0 1 3.78591e-7 0 1 1.23042e-6 0 1 -1.89295e-7 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 -3.7859e-7 0 1 -1.26321e-7 0 1 0.3977401 0.9174982 0 0.39774 0.9174983 0 8.73836e-7 0 1 2.46486e-6 0 1 -6.16215e-7 0 1 6.16216e-7 0 1 -1.98391e-6 0 1 4.22733e-6 0 1 6.30456e-7 0 1 3.00637e-7 0 1 -2.34646e-7 0 1 2.91279e-7 0 1 6.16215e-7 0 1 -1.23243e-6 0 1 -4.22732e-6 0 1 9.91959e-7 0 1 1.20255e-6 0 1 3.51968e-7 0 1 -3.00637e-7 0 1 -0.7185752 -0.6954493 0 -0.7185754 -0.6954491 0 0.9300138 0.3675247 0 0.930014 0.3675245 0 0.7185752 0.6954492 0 0.7185753 0.6954492 0 -0.9300138 -0.3675245 0 -0.9300138 -0.3675245 0 0.9998663 -0.01635235 0 0.9998664 -0.01635265 0 -0.9998664 0.01635235 0 -0.9998664 0.01635235 0 0.9174982 -0.3977398 0 0.9174982 -0.3977401 0 -0.9174984 0.3977396 0 0.6954491 -0.7185754 0 0.6954494 -0.7185752 0 -0.6954491 0.7185754 0 0.3675246 -0.9300138 0 0.3675246 -0.9300139 0 -0.3675245 0.9300138 0 -0.3675245 0.930014 0 -0.01635229 -0.9998663 0 0.01635229 0.9998663 0 -0.3977401 -0.9174982 0 -0.3977398 -0.9174982 0 -5.61982e-7 0 -1 9.75682e-7 0 -1 0 0 -1 -5.61982e-7 0 -1 1.84636e-6 0 -1 5.81742e-7 0 -1 2.29691e-7 0 -1 -1.83753e-7 0 -1 -1.55716e-6 0 -1 2.13564e-6 0 -1 1.06782e-6 0 -1 -7.78582e-7 0 -1 1.95137e-6 0 -1 9.75684e-7 0 -1 6.79168e-7 0 -1 7.78582e-7 0 -1 0 0 -1 -1.83752e-7 0 -1 3.67505e-7 0 -1 -1.59723e-6 0 -1 -0.1950901 -0.9807854 0 -0.1950902 -0.9807853 0 -0.5555704 -0.8314695 0 -0.5555704 -0.8314695 0 -0.5555701 -0.8314697 0 -0.8314696 -0.5555703 0 -0.8314699 -0.55557 0 -0.9807853 -0.1950905 0 -0.9807853 -0.1950906 0 -0.9807853 0.1950906 0 -0.9807854 0.1950899 0 -0.9807854 0.1950904 -1.88245e-7 -0.8314696 0.5555703 0 -0.8314698 0.5555701 0 -0.5555704 0.8314695 0 -0.5555704 0.8314695 0 -0.1950901 0.9807854 0 -0.1950899 0.9807854 0 0.1950902 0.9807853 0 0.1950901 0.9807854 0 0.5555704 0.8314695 0 0.5555707 0.8314693 0 0.5555698 0.83147 0 0.8314696 0.5555703 0 0.8314693 0.5555709 0 0.9807854 0.1950901 0 0.9807853 -0.1950905 0 0.9807853 -0.1950902 0 0.9807854 -0.1950898 -2.21972e-7 0.8314698 -0.5555702 0 0.8314698 -0.55557 0 0.5555704 -0.8314697 0 0.5555704 -0.8314695 0 0.1950899 -0.9807854 0 0.19509 -0.9807854 0 0.7127842 -0.7013834 0 0.7127819 -0.7013857 0 0.7127828 -0.7013849 0 -0.7127833 0.7013843 0 -0.7127836 0.7013841 0 -0.7127807 0.701387 3.99133e-7 -0.7013818 -0.7127858 0 -0.7013878 -0.7127799 0 0.7127835 -0.7013842 0 0.7127824 -0.7013853 0 0.7127807 -0.7013871 7.09159e-7 -0.7127846 0.7013831 0 -0.7127819 0.7013859 0 -0.7127814 0.7013863 -9.38778e-7 0.7013827 0.712785 0 0.7013906 0.7127771 0 -1.19945e-6 0 -1 -0.4959464 -0.5040152 -0.707111 -0.4959524 -0.5040099 -0.7071105 -0.7013871 -0.7127806 0 -0.7013764 -0.712791 0 -0.4959497 -0.5040273 0.7071 -0.4959513 -0.5040145 0.707108 6.8398e-7 0 1 -0.6954489 -0.7185757 0 -0.6954488 -0.7185758 0 -0.6954491 -0.7185755 0 0.69545 0.7185745 0 0.6954479 0.7185766 0 0.6954531 0.7185716 7.98274e-7 -0.7185749 0.6954497 0 -0.7185688 0.6954559 0 -0.6954453 -0.7185791 0 -0.6954485 -0.7185759 0 -0.6954512 -0.7185734 0 0.6954511 0.7185735 0 0.6954486 0.7185759 0 0.6954494 0.7185751 0 0.7185823 -0.695442 0 0.7185743 -0.6954502 0 1.19943e-6 0 -1 -0.5081086 0.4917579 -0.7071067 -0.5081101 0.4917587 -0.7071051 -0.718569 0.6954557 0 -0.7185797 0.6954446 0 -0.5081138 0.4917591 0.7071021 -0.5081086 0.4917545 0.707109 1.36796e-6 0 1 -8.54984e-7 0 1 1 0 -7.3115e-6 1 0 1.13572e-5 1.10471e-6 -1 0 1.10471e-6 -1 0 0 0 1 0 0 1 0 -1 -1.91965e-7 0 0 -1 0 0 -1 5.86466e-7 0 -1 0 1 3.69571e-7 0 0 -1 -5.66917e-6 0 1 -1 -1.01901e-6 0 1 -5.58369e-6 0 1 0 5.85603e-7 1.10471e-6 -1 0 1.10471e-6 -1 0 -1 1.87787e-6 0 -1 2.82485e-5 0 1 0 -1.24816e-5 -1 -2.82488e-5 0 -1.6423e-5 0.5662661 0.8242226 0 0.5663031 0.8241971 0 0.5663009 0.8241987 0 -0.5662971 0.8242012 6.69537e-7 -0.5663037 0.8241968 0 0.5662974 0.8242011 0 0.5663034 0.8241969 0 0.5663037 0.8241968 0 0.5662968 0.8242015 0 -0.5663089 0.8241931 0 -0.5662968 0.8242015 3.92974e-7 -0.5662972 0.8242012 0 -0.5662974 0.8242011 1 8.19451e-6 0 -0.8314558 0.5555908 0 -0.8314718 0.555567 0 -0.8314681 0.5555726 -2.44244e-5 -0.8314711 0.5555682 0 -0.8314747 0.5555629 0 -0.8314654 0.5555768 0 -0.9805393 0.1963231 0 -0.9810232 0.1938903 0 -0.9805394 -0.1963225 0 -0.9810231 -0.1938909 0 -0.8314718 -0.555567 0 -0.8314515 -0.5555974 0 -0.8314532 -0.5555949 0 -0.8314667 -0.5555747 0 -0.8314673 -0.5555739 0 -0.8314737 -0.5555644 -9.9293e-6 0.367525 0.9300137 0 0.3675262 0.9300132 0 -0.01635259 0.9998663 0 -0.3977403 0.9174981 0 -0.7185757 0.6954488 0 -0.930013 0.3675268 0 -0.9998664 -0.0163502 0 -0.9998663 -0.01635766 0 -0.9174993 -0.3977373 0 -0.9174979 -0.3977405 0 -0.6954489 -0.7185755 0 -0.367525 -0.9300137 0 -0.3675262 -0.9300132 0 0.01635265 -0.9998663 0 0.3977376 -0.9174993 0 0.3977403 -0.9174981 0 0.7185757 -0.6954488 0 0.930013 -0.3675268 0 0.9998664 0.01635026 0 0.9998663 0.01635396 0 0.9174983 0.3977397 0 0.6954489 0.7185755 0 -3.78597e-7 0 1 1.47371e-7 0 1 -5.67882e-7 0 1 0 0 1 1.51435e-6 0 1 3.78588e-7 0 1 -1.34745e-6 0 1 3.78594e-7 0 1 -1.47374e-7 0 1 7.57176e-7 0 1 -1.51437e-6 0 1 1.34743e-6 0 1 -3.78591e-7 0 1 1.34742e-6 0 1 -0.9174966 -0.3977438 0 -0.9175001 -0.3977354 0 1.23244e-6 0 1 -1.23244e-6 0 1 -3.43467e-7 0 1 0 0 1 1.26091e-6 0 1 4.72845e-7 0 1 -1.23244e-6 0 1 3.43467e-7 0 1 0 0 1 -1.26091e-6 0 1 -4.7284e-7 0 1 0.6954481 0.7185763 0 -0.3675239 -0.9300142 0 -0.6954481 -0.7185763 0 0.3675239 0.9300142 0 0.01635068 -0.9998664 0 0.01635056 -0.9998664 0 -0.01635062 0.9998664 0 -0.01635062 0.9998664 0 0.3977404 -0.9174981 0 0.3977404 -0.9174981 0 -0.3977404 0.9174981 0 -0.3977404 0.9174981 0 0.7185762 -0.6954483 0 0.7185762 -0.6954482 0 -0.7185762 0.6954483 0 -0.7185738 0.6954509 0 0.9300128 -0.3675273 0 0.9300146 -0.367523 0 -0.9300148 0.367522 0 -0.9300148 0.3675221 0 0.9998664 0.01635354 0 0.9998664 0.0163486 0 -0.9998663 -0.0163536 0 -0.9998664 -0.01634865 0 0.9174966 0.3977438 0 0.9175001 0.3977354 0 0 0 -1 9.23191e-7 0 -1 -1.94646e-7 0 -1 -1.95137e-6 0 -1 7.78579e-7 0 -1 -1.99653e-7 0 -1 9.99089e-7 0 -1 0.9807851 0.1950918 0 0.9807866 0.195084 0 0.8314734 0.5555646 0 0.8314704 0.5555693 0 0.8314692 0.555571 6.5567e-6 0.55557 0.8314699 0 0.5555662 0.8314723 0 0.1950894 0.9807856 0 0.1950893 0.9807856 0 -0.195091 0.9807852 0 -0.1950938 0.9807847 0 -0.1950855 0.9807863 3.7069e-6 -0.55557 0.8314699 0 -0.5555662 0.8314723 0 -0.8314698 0.5555702 0 -0.8314698 0.5555699 0 -0.9807851 0.1950918 0 -0.9807866 0.195084 0 -0.9807866 -0.195084 0 -0.9807851 -0.1950918 0 -0.8314698 -0.5555702 0 -0.831469 -0.5555712 0 -0.8314705 -0.5555691 3.70696e-6 -0.55557 -0.8314699 0 -0.1950893 -0.9807856 0 -0.1950894 -0.9807856 0 0.1950879 -0.9807858 0 0.1950883 -0.9807857 0 0.1950904 -0.9807853 0 0.55557 -0.8314699 0 0.8314735 -0.5555644 0 0.9807866 -0.195084 0 0.9807851 -0.1950918 0 -0.7127842 0.7013834 0 -0.7127819 0.7013857 0 -0.7127828 0.7013849 0 0.7127833 -0.7013843 0 0.7127836 -0.7013841 0 0.7127807 -0.701387 1.59653e-6 0.7013818 0.7127858 0 0.7013878 0.7127799 0 -0.7127835 0.7013842 0 -0.7127824 0.7013853 0 -0.7127807 0.7013871 0 0.7127846 -0.7013831 0 0.7127819 -0.7013859 0 0.7127814 -0.7013863 -9.38778e-7 -0.7013827 -0.712785 0 -0.7013906 -0.7127771 0 1.19944e-6 0 -1 0.4959502 0.5040191 -0.7071056 0.4959539 0.5040113 -0.7071085 0.7013871 0.7127806 0 0.7013764 0.712791 0 0.4959521 0.5040298 0.7070966 0.4959513 0.5040145 0.707108 -6.83984e-7 0 1 0.6954489 0.7185757 7.84291e-6 0.6954488 0.7185758 0 0.6954491 0.7185755 0 -0.69545 -0.7185745 0 -0.6954479 -0.7185766 0 -0.6954531 -0.7185716 0 0.7185749 -0.6954497 0 0.7185688 -0.6954559 0 0.6954453 0.7185791 0 0.6954485 0.7185759 0 0.6954512 0.7185734 -7.09161e-7 -0.6954511 -0.7185735 0 -0.6954486 -0.7185759 0 -0.6954494 -0.7185751 9.38781e-7 -0.7185823 0.695442 0 -0.7185743 0.6954502 0 -1.19943e-6 0 -1 0.5081086 -0.4917579 -0.7071067 0.5081111 -0.4917597 -0.7071037 0.718569 -0.6954557 0 0.7185797 -0.6954446 0 0.5081114 -0.4917567 0.7071055 0.5081086 -0.4917545 0.707109 -1.36797e-6 0 1 8.54986e-7 0 1 -1 0 -7.3115e-6 -1 0 1.13572e-5 -1.10471e-6 1 -2.80651e-6 -1.10471e-6 1 0 0 0 1 0 1 1.98813e-6 0 -1 2.79132e-6 0 0 -1 -5.8634e-7 0 -1 0 -1 9.92594e-7 0 0 -1 5.66795e-6 0 1 1 1.01901e-6 0 -1 5.58369e-6 0 -1 0 5.85603e-7 -1.10471e-6 1 0 -1.10471e-6 1 0 1 -1.87787e-6 0 1 -2.82485e-5 0 -1 0 -1.24816e-5 1 2.82488e-5 0 1.6423e-5 -0.5662661 0.8242226 0 -0.5663009 0.8241987 -6.69529e-7 0.5662974 0.8242011 0 0.5663089 0.8241931 -3.92974e-7 0.5662972 0.8242012 -1 -8.19451e-6 0 0.8314558 -0.5555908 0 0.8314718 -0.555567 0 0.8314681 -0.5555726 -3.25658e-5 0.8314711 -0.5555682 0 0.8314747 -0.5555629 0 0.8314654 -0.5555768 0 0.9805393 -0.1963231 0 0.9810232 -0.1938903 0 0.9805394 0.1963225 0 0.9810231 0.1938909 0 0.8314718 0.555567 0 0.8314515 0.5555974 0 0.8314532 0.5555949 0 0.8314667 0.5555747 0 0.8314673 0.5555739 0 0.8314737 0.5555644 -9.9293e-6 0.01635259 -0.9998663 0 0.9998664 0.0163502 0 0.9998663 0.01635766 0 0.9174993 0.3977373 0 0.9174979 0.3977405 0 -0.01635265 0.9998663 0 -0.3977376 0.9174993 0 -0.9998664 -0.01635026 0 -0.9998663 -0.01635396 0 -0.9174983 -0.3977397 0 -1.47371e-7 0 1 5.67886e-7 0 1 0 0 1 1.47374e-7 0 1 -7.57181e-7 0 1 -1.34743e-6 0 1 3.43471e-7 0 1 -3.43463e-7 0 1 4.7284e-7 0 1 -0.01635068 0.9998664 0 -0.01635056 0.9998664 0 0.01635062 -0.9998664 0 0.01635062 -0.9998664 0 -0.7185762 0.6954482 0 0.7185738 -0.6954509 0 -0.9300128 0.3675273 0 -0.9300146 0.367523 0 0.9300148 -0.367522 0 0.9300148 -0.3675221 0 -0.9998664 -0.01635354 0 -0.9998664 -0.0163486 0 0.9998663 0.0163536 0 0.9998664 0.01634865 0 0 0 -1 -9.2317e-7 0 -1 1.94646e-7 0 -1 1.95137e-6 0 -1 -7.78579e-7 0 -1 1.99652e-7 0 -1 -9.99089e-7 0 -1 -0.8314734 -0.5555646 0 -0.8314704 -0.5555693 0 -0.8314692 -0.555571 4.37113e-6 -0.5555662 -0.8314723 0 0.195091 -0.9807852 0 0.1950938 -0.9807847 0 0.1950855 -0.9807863 0 0.5555662 -0.8314723 0 0.8314698 -0.5555699 0 0.8314698 0.5555702 0 0.831469 0.5555712 0 0.8314705 0.5555691 5.56044e-6 -0.1950879 0.9807858 0 -0.1950883 0.9807857 0 -0.1950904 0.9807853 0 -0.8314735 0.5555644 0 -0.7013851 0.7127826 -1.56859e-5 -0.7013856 0.7127821 0 -0.7013855 0.7127822 0 0.7013839 -0.7127838 0 0.7013843 -0.7127835 0 0.7013829 -0.7127847 -1.59654e-6 -0.7127801 -0.7013877 0 -0.7013856 0.7127822 0 -0.7013856 0.712782 2.83665e-6 0.7013841 -0.7127836 0 0.701384 -0.7127837 0 0.7013837 -0.712784 0 0.7127836 0.701384 0 -0.5040076 -0.4959549 -0.7071104 -0.5040181 -0.4959505 -0.7071061 -0.7127806 -0.7013871 0 -0.7127798 -0.701388 0 -0.5039986 -0.4959433 0.7071249 -0.5040261 -0.4959602 0.7070934 -0.718575 -0.6954495 0 -0.7185746 -0.69545 0 -0.7185745 -0.69545 0 0.7185745 0.69545 0 0.7185747 0.6954498 0 0.7185744 0.6954502 7.9827e-7 0.6954474 -0.7185771 0 0.6954481 -0.7185764 0 -0.7185764 -0.6954481 0 -0.7185725 -0.695452 0 0.7185726 0.695452 0 0.7185755 0.695449 0 -0.6954475 0.718577 0 -0.6954481 0.7185764 0 0.4917559 -0.5081093 -0.7071076 0.4917549 -0.5081096 -0.7071081 0.6954478 -0.7185767 0 0.6954476 -0.7185768 0 0.4917593 -0.5081132 0.7071024 0.4917588 -0.5081139 0.7071022 -1.70995e-7 0 1 0 1 5.04712e-5 -1 1.05244e-6 0 -1 1.05244e-6 0 0 1 3.78536e-5 4.85978e-5 0 -1 -4.12284e-7 0 -1 3.61898e-7 0 -1 -4.66855e-5 0 -1 0 0 -1 1.66236e-6 0 1 0 0 -1 -1 1.07946e-6 0 -1 1.07946e-6 0 0 1 -4.64914e-5 0 1 -2.3246e-5 0.5663058 -1.5397e-5 0.8241953 0.5662984 0 0.8242003 0.5663009 0 0.8241987 -0.5663021 0 0.8241978 -0.5662997 6.35898e-7 0.8241994 0.5663006 0 0.8241989 0.566299 0 0.8241999 0.5663 0 0.8241993 -0.5662988 0 0.8242001 -0.5662984 0 0.8242003 -0.5663031 4.421e-7 0.8241972 -0.5663 0 0.8241993 -0.566299 0 0.8241999 0 1 -8.1945e-6 0.5555825 -0.8314615 0 0.5555688 -0.8314707 0 0.5555754 -0.8314662 -3.25657e-5 0.5555819 -0.8314617 0 0.5555734 -0.8314676 0 0.5555776 -0.8314648 0 0.1945151 -0.9808996 0 0.1945252 -0.9808976 0 -0.1945151 -0.9808996 0 -0.1945252 -0.9808976 0 -0.5555688 -0.8314707 0 -0.5555887 -0.8314573 0 -0.5555695 -0.8314702 0 -0.5555887 -0.8314573 0 -0.5555762 -0.8314657 0 -0.5555846 -0.8314599 -3.97166e-5 0.9300134 0.3675255 0 0.9300134 0.367526 0 0.9998663 -0.01635301 0 0.9998664 -0.01635253 0 0.9174984 -0.3977397 0 0.9174983 -0.3977397 0 0.6954502 -0.7185744 0 0.3675256 -0.9300134 0 0.3675256 -0.9300135 0 -0.01635497 -0.9998663 0 -0.3977398 -0.9174984 0 -0.3977398 -0.9174984 0 -0.7185756 -0.6954489 0 -0.7185757 -0.6954488 0 -0.9300134 -0.3675255 0 -0.9300134 -0.367526 0 -0.9998663 0.01635307 0 -0.9998663 0.01635265 0 -0.917499 0.397738 0 -0.9174991 0.397738 0 -0.6954502 0.7185744 0 -0.3675256 0.9300134 0 -0.3675256 0.9300135 0 0.01635503 0.9998663 0 0.3977389 0.9174987 0 0.3977389 0.9174987 0 0.7185756 0.6954489 0 0.7185757 0.6954488 0 1.89293e-7 0 1 1.34743e-6 0 1 1.34742e-6 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 1.13574e-6 0 1 3.78578e-7 0 1 -1.34739e-6 0 1 0 0 1 -1.89295e-7 0 1 -1.13575e-6 0 1 -3.78574e-7 0 1 1.34739e-6 0 1 0 0 1 -0.3977428 -0.917497 0 -0.3977428 -0.917497 0 2.91278e-7 0 1 1.23243e-6 0 1 -6.16213e-7 0 1 -6.30447e-7 0 1 6.30466e-7 0 1 3.00643e-7 0 1 2.34648e-7 0 1 -2.91272e-7 0 1 6.16237e-7 0 1 2.11366e-6 0 1 6.3046e-7 0 1 -3.00643e-7 0 1 -2.34641e-7 0 1 0.7185757 0.6954488 0 0.7185757 0.6954488 0 -0.9300144 -0.3675231 0 -0.7185757 -0.6954488 0 -0.7185757 -0.6954488 0 0.9300144 0.3675231 0 -0.9998664 0.0163508 0 -0.9998664 0.0163505 0 0.9998664 -0.0163508 0 0.9998664 -0.0163505 0 -0.917498 0.3977406 0 -0.9174981 0.3977404 0 0.917498 -0.3977406 0 0.9174981 -0.3977404 0 -0.6954474 0.7185771 0 -0.6954473 0.7185772 0 0.6954473 -0.7185772 0 -0.3675263 0.9300132 0 -0.3675264 0.9300131 0 0.3675253 -0.9300135 0 0.3675254 -0.9300135 0 0.01634788 0.9998664 0 -0.01634794 -0.9998664 0 0.3977428 0.917497 0 0.3977428 0.917497 0 -5.6198e-7 0 -1 -1.95137e-6 0 -1 9.75663e-7 0 -1 1.8294e-7 0 -1 -9.23177e-7 0 -1 2.29693e-7 0 -1 2.13558e-6 0 -1 1.06782e-6 0 -1 -7.78586e-7 0 -1 4.87832e-7 0 -1 6.79178e-7 0 -1 -2.66953e-7 0 -1 7.78583e-7 0 -1 0 0 -1 -3.99301e-7 0 -1 -4.99544e-7 0 -1 0.1950896 0.9807855 0 0.5555679 0.8314712 0 0.5555739 0.8314672 0 0.5555611 0.8314758 0 0.8314721 0.5555665 0 0.831472 0.5555666 0 0.9807853 0.1950905 0 0.9807854 0.19509 0 0.9807853 -0.1950905 0 0.9807853 -0.1950909 0 0.9807856 -0.1950892 1.85348e-6 0.8314723 -0.5555663 0 0.8314719 -0.5555669 0 0.5555681 -0.8314712 0 0.5555679 -0.8314712 0 0.1950896 -0.9807855 0 -0.1950896 -0.9807855 0 -0.5555681 -0.8314712 0 -0.5555608 -0.831476 0 -0.5555739 -0.8314672 -7.41388e-6 -0.8314701 -0.5555697 0 -0.8314703 -0.5555693 0 -0.9807855 -0.1950892 0 -0.9807857 -0.1950887 0 -0.9807857 0.1950887 0 -0.9807856 0.1950892 0 -0.9807856 0.1950894 2.18557e-6 -0.8314701 0.5555697 0 -0.8314703 0.5555693 0 -0.5555679 0.8314712 0 -0.5555681 0.8314712 0 -0.1950896 0.9807855 0</float_array>\n          <technique_common>\n            <accessor source=\"#motor_mount-mesh-normals-array\" count=\"881\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"motor_mount-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#motor_mount-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"Material_002-material\" count=\"1904\">\n          <input semantic=\"VERTEX\" source=\"#motor_mount-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#motor_mount-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 0 2 0 2 1 3 1 4 1 2 2 4 2 0 2 5 3 6 3 7 3 7 4 8 4 9 4 7 5 9 5 5 5 6 6 5 6 0 6 6 7 0 7 4 7 10 8 11 8 4 8 4 9 3 9 12 9 4 10 12 10 10 10 13 3 14 3 7 3 7 11 6 11 15 11 7 12 15 12 13 12 3 13 7 13 14 13 3 14 14 14 12 14 12 15 14 15 13 15 12 15 13 15 10 15 15 16 11 16 10 16 15 17 10 17 13 17 6 18 4 18 11 18 6 19 11 19 15 19 0 20 5 20 9 20 0 21 9 21 1 21 8 22 2 22 1 22 8 23 1 23 9 23 16 24 17 24 18 24 18 25 19 25 20 25 18 26 20 26 16 26 21 27 22 27 23 27 23 28 24 28 25 28 23 29 25 29 21 29 22 30 21 30 16 30 22 31 16 31 20 31 26 32 27 32 20 32 20 32 19 32 28 32 20 33 28 33 26 33 29 34 30 34 23 34 23 35 22 35 31 35 23 36 31 36 29 36 19 37 23 37 30 37 19 38 30 38 28 38 28 39 30 39 29 39 28 40 29 40 26 40 31 41 27 41 26 41 31 42 26 42 29 42 22 43 20 43 27 43 22 44 27 44 31 44 16 45 21 45 25 45 16 46 25 46 17 46 24 22 18 22 17 22 24 47 17 47 25 47 32 48 33 48 34 48 34 49 35 49 36 49 34 50 36 50 32 50 37 51 38 51 39 51 37 51 39 51 40 51 41 52 42 52 43 52 41 53 43 53 44 53 45 22 46 22 47 22 45 22 47 22 34 22 48 22 49 22 50 22 48 22 50 22 51 22 52 54 53 54 54 54 52 22 54 22 55 22 56 55 57 55 58 55 56 55 58 55 59 55 60 56 61 56 62 56 60 57 62 57 63 57 63 57 62 57 64 57 63 58 64 58 65 58 65 59 64 59 42 59 65 60 42 60 41 60 66 61 67 61 68 61 66 51 68 51 69 51 70 57 71 57 61 57 70 62 61 62 60 62 72 63 73 63 67 63 72 51 67 51 66 51 74 51 75 51 73 51 74 64 73 64 72 64 76 51 77 51 75 51 76 51 75 51 74 51 40 51 39 51 77 51 40 51 77 51 76 51 78 22 48 22 51 22 78 22 51 22 79 22 79 22 51 22 52 22 79 22 52 22 80 22 80 22 52 22 55 22 80 22 55 22 81 22 81 22 55 22 45 22 81 22 45 22 82 22 47 65 83 65 84 65 84 66 85 66 86 66 84 49 86 49 47 49 54 22 87 22 88 22 54 67 88 67 46 67 53 68 89 68 87 68 53 22 87 22 54 22 50 22 90 22 89 22 50 69 89 69 53 69 49 22 91 22 90 22 49 22 90 22 50 22 92 70 93 70 94 70 92 71 94 71 95 71 96 72 97 72 36 72 96 73 36 73 98 73 99 15 86 15 85 15 99 15 85 15 100 15 98 15 36 15 35 15 98 15 35 15 101 15 101 15 35 15 86 15 101 15 86 15 99 15 102 15 103 15 104 15 102 15 104 15 105 15 106 15 107 15 108 15 106 15 108 15 109 15 110 74 111 74 102 74 102 75 112 75 113 75 102 76 113 76 110 76 111 15 114 15 103 15 111 77 103 77 102 77 114 15 115 15 106 15 114 15 106 15 103 15 115 15 116 15 107 15 115 15 107 15 106 15 116 15 98 15 101 15 116 15 101 15 107 15 117 78 105 78 93 78 93 79 92 79 118 79 93 80 118 80 117 80 105 15 104 15 119 15 105 81 119 81 93 81 104 82 109 82 120 82 104 15 120 15 119 15 109 15 108 15 121 15 109 15 121 15 120 15 108 83 99 83 100 83 108 15 100 15 121 15 122 84 111 84 110 84 122 51 110 51 123 51 122 85 124 85 114 85 122 86 114 86 111 86 124 87 125 87 115 87 124 88 115 88 114 88 125 89 126 89 116 89 125 90 116 90 115 90 126 51 96 51 98 51 126 91 98 91 116 91 127 57 128 57 100 57 127 57 100 57 85 57 128 92 129 92 121 92 128 93 121 93 100 93 129 94 130 94 120 94 129 95 120 95 121 95 130 57 131 57 119 57 130 96 119 96 120 96 131 97 94 97 93 97 131 57 93 57 119 57 37 15 40 15 128 15 37 15 128 15 127 15 46 22 88 22 83 22 46 22 83 22 47 22 82 22 45 22 34 22 82 22 34 22 33 22 132 98 133 98 48 98 48 22 78 22 134 22 48 99 134 99 132 99 58 57 57 57 71 57 58 100 71 100 70 100 59 15 58 15 70 15 70 101 122 101 123 101 70 102 123 102 59 102 135 22 136 22 91 22 91 22 49 22 137 22 91 103 137 103 135 103 138 55 69 55 68 55 138 55 68 55 139 55 44 104 43 104 32 104 32 105 36 105 97 105 32 49 97 49 44 49 34 49 47 49 86 49 34 49 86 49 35 49 95 106 94 106 66 106 66 15 69 15 138 15 66 107 138 107 95 107 72 108 66 108 94 108 72 15 94 15 131 15 74 109 72 109 131 109 74 15 131 15 130 15 76 15 74 15 130 15 76 15 130 15 129 15 40 15 76 15 129 15 40 15 129 15 128 15 41 15 44 15 97 15 41 15 97 15 96 15 65 15 41 15 96 15 65 15 96 15 126 15 63 15 65 15 126 15 63 15 126 15 125 15 60 110 63 110 125 110 60 111 125 111 124 111 70 112 60 112 124 112 70 15 124 15 122 15 112 51 102 51 48 51 112 51 48 51 133 51 52 51 51 51 103 51 52 51 103 51 106 51 45 51 55 51 107 51 45 51 107 51 101 51 137 113 49 113 105 113 137 57 105 57 117 57 50 114 53 114 109 114 50 115 109 115 104 115 54 57 46 57 99 57 54 57 99 57 108 57 49 55 48 55 102 55 49 55 102 55 105 55 51 49 50 49 104 49 51 49 104 49 103 49 53 116 52 116 106 116 53 117 106 117 109 117 55 49 54 49 108 49 55 49 108 49 107 49 46 118 45 118 101 118 46 119 101 119 99 119 83 120 38 120 84 120 68 55 140 55 139 55 43 121 33 121 32 121 141 55 57 55 56 55 136 122 140 122 68 122 68 123 67 123 91 123 68 124 91 124 136 124 82 125 33 125 43 125 82 126 43 126 42 126 83 127 88 127 39 127 83 128 39 128 38 128 88 129 87 129 77 129 88 130 77 130 39 130 87 131 89 131 75 131 87 130 75 130 77 130 89 129 90 129 73 129 89 132 73 132 75 132 90 133 91 133 67 133 90 134 67 134 73 134 141 135 134 135 78 135 78 136 71 136 57 136 78 137 57 137 141 137 78 138 79 138 61 138 78 139 61 139 71 139 79 140 80 140 62 140 79 141 62 141 61 141 80 142 81 142 64 142 80 143 64 143 62 143 81 144 82 144 42 144 81 145 42 145 64 145 84 49 38 49 37 49 37 49 127 49 85 49 37 49 85 49 84 49 59 146 123 146 110 146 110 147 113 147 132 147 132 148 134 148 141 148 56 149 59 149 110 149 132 150 141 150 56 150 110 151 132 151 56 151 133 152 132 152 113 152 133 152 113 152 112 152 117 153 118 153 135 153 117 154 135 154 137 154 135 155 118 155 92 155 92 156 95 156 138 156 139 157 140 157 136 157 92 158 138 158 139 158 136 159 135 159 92 159 92 160 139 160 136 160 142 161 143 161 144 161 142 162 144 162 145 162 145 163 144 163 146 163 145 163 146 163 147 163 147 164 146 164 148 164 147 165 148 165 149 165 149 31 148 31 150 31 149 166 150 166 151 166 151 167 150 167 152 167 151 168 152 168 153 168 153 169 152 169 154 169 153 170 154 170 155 170 155 171 154 171 156 171 155 172 156 172 157 172 157 32 156 32 158 32 157 32 158 32 159 32 159 173 158 173 160 173 159 174 160 174 161 174 161 175 160 175 162 175 161 176 162 176 163 176 163 177 162 177 164 177 163 178 164 178 165 178 165 179 164 179 166 179 165 179 166 179 167 179 167 180 166 180 168 180 167 181 168 181 169 181 169 182 168 182 170 182 169 183 170 183 171 183 171 184 170 184 172 184 171 185 172 185 173 185 173 186 172 186 143 186 173 187 143 187 142 187 174 188 175 188 144 188 174 189 144 189 143 189 175 190 176 190 146 190 175 22 146 22 144 22 176 191 177 191 148 191 176 22 148 22 146 22 177 192 178 192 150 192 177 22 150 22 148 22 178 22 179 22 152 22 178 193 152 193 150 193 179 22 180 22 154 22 179 194 154 194 152 194 180 195 181 195 156 195 180 22 156 22 154 22 181 22 182 22 158 22 181 22 158 22 156 22 182 196 183 196 160 196 182 22 160 22 158 22 183 197 184 197 162 197 183 22 162 22 160 22 184 198 185 198 164 198 184 199 164 199 162 199 185 200 186 200 166 200 185 22 166 22 164 22 186 191 187 191 168 191 186 22 168 22 166 22 187 22 188 22 170 22 187 201 170 201 168 201 188 22 189 22 172 22 188 22 172 22 170 22 189 22 174 22 143 22 189 22 143 22 172 22 189 202 188 202 190 202 189 203 190 203 191 203 192 204 193 204 194 204 194 205 195 205 196 205 196 206 191 206 190 206 190 207 197 207 198 207 198 22 199 22 200 22 200 22 201 22 202 22 200 22 202 22 203 22 192 208 194 208 196 208 204 209 192 209 196 209 198 22 200 22 203 22 198 210 203 210 205 210 206 210 204 210 196 210 207 211 206 211 196 211 190 212 198 212 205 212 190 22 205 22 208 22 207 22 196 22 190 22 190 22 208 22 207 22 209 213 201 213 200 213 200 22 210 22 211 22 211 214 212 214 213 214 213 22 214 22 215 22 215 215 216 215 194 215 194 22 193 22 217 22 194 22 217 22 218 22 209 22 200 22 211 22 219 216 209 216 211 216 215 217 194 217 218 217 215 22 218 22 220 22 221 22 219 22 211 22 222 218 221 218 211 218 213 219 215 219 220 219 213 220 220 220 223 220 222 22 211 22 213 22 213 22 223 22 222 22 182 221 181 221 212 221 182 222 212 222 211 222 175 223 174 223 196 223 175 224 196 224 195 224 174 225 189 225 191 225 174 226 191 226 196 226 183 227 182 227 211 227 183 228 211 228 210 228 176 229 175 229 195 229 176 230 195 230 194 230 184 231 183 231 210 231 184 232 210 232 200 232 177 233 176 233 194 233 177 234 194 234 216 234 185 235 184 235 200 235 185 235 200 235 199 235 178 236 177 236 216 236 178 237 216 237 215 237 186 166 185 166 199 166 186 238 199 238 198 238 179 239 178 239 215 239 179 240 215 240 214 240 187 241 186 241 198 241 187 242 198 242 197 242 180 243 179 243 214 243 180 243 214 243 213 243 188 244 187 244 197 244 188 244 197 244 190 244 181 245 180 245 213 245 181 246 213 246 212 246 224 247 173 247 142 247 142 15 145 15 147 15 147 248 149 248 151 248 151 249 153 249 155 249 155 250 157 250 225 250 155 251 225 251 226 251 227 252 224 252 142 252 228 253 227 253 142 253 155 254 226 254 229 254 155 15 229 15 230 15 228 255 142 255 147 255 231 256 228 256 147 256 151 15 155 15 230 15 151 15 230 15 232 15 233 15 231 15 147 15 151 257 232 257 233 257 147 258 151 258 233 258 234 15 225 15 157 15 157 15 159 15 161 15 161 259 163 259 165 259 165 260 167 260 169 260 169 15 171 15 173 15 173 261 224 261 235 261 173 15 235 15 236 15 234 262 157 262 161 262 237 15 234 15 161 15 169 263 173 263 236 263 169 264 236 264 238 264 239 265 237 265 161 265 240 15 239 15 161 15 165 15 169 15 238 15 165 15 238 15 241 15 240 266 161 266 165 266 165 15 241 15 240 15 229 267 226 267 222 267 229 268 222 268 223 268 234 269 221 269 222 269 222 270 226 270 225 270 222 271 225 271 234 271 221 272 234 272 237 272 221 273 237 273 219 273 237 274 239 274 209 274 237 275 209 275 219 275 209 276 239 276 240 276 240 277 202 277 201 277 240 278 201 278 209 278 241 279 203 279 202 279 241 280 202 280 240 280 238 281 205 281 203 281 238 282 203 282 241 282 236 283 208 283 205 283 236 284 205 284 238 284 235 285 207 285 208 285 235 286 208 286 236 286 206 287 207 287 235 287 224 288 227 288 206 288 235 289 224 289 206 289 228 290 204 290 206 290 228 291 206 291 227 291 231 292 192 292 204 292 231 292 204 292 228 292 231 293 233 293 217 293 193 294 192 294 231 294 217 295 193 295 231 295 218 296 217 296 233 296 218 297 233 297 232 297 218 298 232 298 230 298 218 299 230 299 220 299 230 300 229 300 223 300 230 301 223 301 220 301 242 302 244 302 243 302 244 303 246 303 245 303 244 304 242 304 246 304 247 305 249 305 248 305 249 306 251 306 250 306 249 307 247 307 251 307 248 308 242 308 247 308 248 309 246 309 242 309 252 310 246 310 253 310 246 311 254 311 245 311 246 312 252 312 254 312 255 313 249 313 256 313 249 314 257 314 248 314 249 315 255 315 257 315 245 316 256 316 249 316 245 317 254 317 256 317 254 15 255 15 256 15 254 318 252 318 255 318 257 319 252 319 253 319 257 320 255 320 252 320 248 321 253 321 246 321 248 322 257 322 253 322 242 323 251 323 247 323 242 324 243 324 251 324 250 22 243 22 244 22 250 325 251 325 243 325 258 326 260 326 259 326 260 327 262 327 261 327 260 328 258 328 262 328 263 329 265 329 264 329 265 330 267 330 266 330 265 331 263 331 267 331 264 332 258 332 263 332 264 333 262 333 258 333 268 334 262 334 269 334 262 335 270 335 261 335 262 336 268 336 270 336 271 337 265 337 272 337 265 338 273 338 264 338 265 339 271 339 273 339 261 340 272 340 265 340 261 341 270 341 272 341 270 15 271 15 272 15 270 342 268 342 271 342 273 343 268 343 269 343 273 344 271 344 268 344 264 345 269 345 262 345 264 346 273 346 269 346 258 347 267 347 263 347 258 348 259 348 267 348 266 349 259 349 260 349 266 350 267 350 259 350 274 351 276 351 275 351 276 57 278 57 277 57 276 352 274 352 278 352 279 55 281 55 280 55 279 55 282 55 281 55 283 353 285 353 284 353 283 354 286 354 285 354 287 355 289 355 288 355 287 22 276 22 289 22 290 22 292 22 291 22 290 22 293 22 292 22 294 356 296 356 295 356 294 22 297 22 296 22 298 51 300 51 299 51 298 51 301 51 300 51 302 49 304 49 303 49 302 49 305 49 304 49 305 49 306 49 304 49 305 49 307 49 306 49 307 49 284 49 306 49 307 357 283 357 284 357 308 55 310 55 309 55 308 55 311 55 310 55 312 49 303 49 313 49 312 49 302 49 303 49 314 55 309 55 315 55 314 55 308 55 309 55 316 55 315 55 317 55 316 55 314 55 315 55 318 55 317 55 319 55 318 55 316 55 317 55 282 55 319 55 281 55 282 55 318 55 319 55 320 22 293 22 290 22 320 22 321 22 293 22 321 22 294 22 293 22 321 22 322 22 294 22 322 22 297 22 294 22 322 22 323 22 297 22 323 22 287 22 297 22 323 22 324 22 287 22 289 57 326 57 325 57 326 57 328 57 327 57 326 57 289 57 328 57 296 22 330 22 329 22 296 22 288 22 330 22 295 22 329 22 331 22 295 22 296 22 329 22 292 22 331 22 332 22 292 22 295 22 331 22 291 22 332 22 333 22 291 22 292 22 332 22 334 49 336 49 335 49 334 49 337 49 336 49 338 55 278 55 339 55 338 55 340 55 278 55 341 15 327 15 328 15 341 15 342 15 327 15 340 15 277 15 278 15 340 15 343 15 277 15 343 15 328 15 277 15 343 358 341 358 328 358 344 15 346 15 345 15 344 15 347 15 346 15 348 15 350 15 349 15 348 359 351 359 350 359 352 15 344 15 353 15 344 15 355 15 354 15 344 15 352 15 355 15 353 15 345 15 356 15 353 15 344 15 345 15 356 15 348 15 357 15 356 15 345 15 348 15 357 15 349 15 358 15 357 15 348 15 349 15 358 15 343 15 340 15 358 15 349 15 343 15 359 15 335 15 347 15 335 15 360 15 334 15 335 360 359 360 360 360 347 15 361 15 346 15 347 15 335 15 361 15 346 15 362 15 351 15 346 15 361 15 362 15 351 15 363 15 350 15 351 15 362 15 363 15 350 15 342 15 341 15 350 15 363 15 342 15 364 55 352 55 353 55 364 55 365 55 352 55 364 55 356 55 366 55 364 55 353 55 356 55 366 55 357 55 367 55 366 55 356 55 357 55 367 55 358 55 368 55 367 55 357 55 358 55 368 361 340 361 338 361 368 55 358 55 340 55 369 49 342 49 370 49 369 49 327 49 342 49 370 49 363 49 371 49 370 49 342 49 363 49 371 49 362 49 372 49 371 49 363 49 362 49 372 49 361 49 373 49 372 49 362 49 361 49 373 49 335 49 336 49 373 49 361 49 335 49 279 15 370 15 282 15 279 15 369 15 370 15 288 22 325 22 330 22 288 22 289 22 325 22 324 22 276 22 287 22 324 22 275 22 276 22 374 22 290 22 375 22 290 22 376 22 320 22 290 22 374 22 376 22 300 49 313 49 299 49 300 49 312 49 313 49 301 15 312 15 300 15 312 15 365 15 364 15 312 362 301 362 365 362 377 22 333 22 378 22 333 22 379 22 291 22 333 363 377 363 379 363 380 51 310 51 311 51 380 364 381 364 310 364 286 365 274 365 285 365 274 57 339 57 278 57 274 366 286 366 339 366 276 57 328 57 289 57 276 57 277 57 328 57 337 15 308 15 336 15 308 15 380 15 311 15 308 15 337 15 380 15 314 15 336 15 308 15 314 15 373 15 336 15 316 15 373 15 314 15 316 15 372 15 373 15 318 15 372 15 316 15 318 15 371 15 372 15 282 15 371 15 318 15 282 15 370 15 371 15 283 15 339 15 286 15 283 15 338 15 339 15 307 15 338 15 283 15 307 15 368 15 338 15 305 15 368 15 307 15 305 15 367 15 368 15 302 15 367 15 305 15 302 15 366 15 367 15 312 15 366 15 302 15 312 15 364 15 366 15 354 55 290 55 344 55 354 55 375 55 290 55 294 55 345 55 293 55 294 55 348 55 345 55 287 55 349 55 297 55 287 55 343 55 349 55 379 49 347 49 291 49 379 49 359 49 347 49 292 367 351 367 295 367 292 368 346 368 351 368 296 49 341 49 288 49 296 49 350 49 341 49 291 51 344 51 290 51 291 51 347 51 344 51 293 57 346 57 292 57 293 57 345 57 346 57 295 51 348 51 294 51 295 51 351 51 348 51 297 57 350 57 296 57 297 57 349 57 350 57 288 51 343 51 287 51 288 369 341 369 343 369 325 57 326 57 280 57 310 370 381 370 382 370 285 371 274 371 275 371 383 372 298 372 299 372 378 373 310 373 382 373 310 374 333 374 309 374 310 375 378 375 333 375 324 376 285 376 275 376 324 377 284 377 285 377 325 378 281 378 330 378 325 379 280 379 281 379 330 378 319 378 329 378 330 380 281 380 319 380 329 381 317 381 331 381 329 380 319 380 317 380 331 378 315 378 332 378 331 380 317 380 315 380 332 378 309 378 333 378 332 380 315 380 309 380 383 382 320 382 376 382 320 383 299 383 313 383 320 384 383 384 299 384 320 385 303 385 321 385 320 385 313 385 303 385 321 385 304 385 322 385 321 385 303 385 304 385 322 385 306 385 323 385 322 383 304 383 306 383 323 385 284 385 324 385 323 385 306 385 284 385 326 57 279 57 280 57 279 57 327 57 369 57 279 386 326 386 327 386 301 387 352 387 365 387 352 388 374 388 355 388 374 389 383 389 376 389 298 390 352 390 301 390 374 391 298 391 383 391 352 392 298 392 374 392 375 393 355 393 374 393 375 394 354 394 355 394 359 395 377 395 360 395 359 396 379 396 377 396 377 397 334 397 360 397 334 398 380 398 337 398 381 399 378 399 382 399 334 400 381 400 380 400 378 401 334 401 377 401 334 402 378 402 381 402 384 403 386 403 385 403 384 404 387 404 386 404 387 405 388 405 386 405 387 405 389 405 388 405 389 406 390 406 388 406 389 406 391 406 390 406 391 407 392 407 390 407 391 407 393 407 392 407 393 408 394 408 392 408 393 408 395 408 394 408 395 409 396 409 394 409 395 410 397 410 396 410 397 411 398 411 396 411 397 412 399 412 398 412 399 413 400 413 398 413 399 413 401 413 400 413 401 414 402 414 400 414 401 415 403 415 402 415 403 416 404 416 402 416 403 416 405 416 404 416 405 417 406 417 404 417 405 418 407 418 406 418 407 419 408 419 406 419 407 419 409 419 408 419 409 420 410 420 408 420 409 420 411 420 410 420 411 421 412 421 410 421 411 422 413 422 412 422 413 423 414 423 412 423 413 423 415 423 414 423 415 424 385 424 414 424 415 424 384 424 385 424 416 425 386 425 417 425 416 22 385 22 386 22 417 22 388 22 418 22 417 426 386 426 388 426 418 22 390 22 419 22 418 22 388 22 390 22 419 22 392 22 420 22 419 22 390 22 392 22 420 427 394 427 421 427 420 22 392 22 394 22 421 428 396 428 422 428 421 22 394 22 396 22 422 429 398 429 423 429 422 22 396 22 398 22 423 430 400 430 424 430 423 431 398 431 400 431 424 432 402 432 425 432 424 22 400 22 402 22 425 22 404 22 426 22 425 433 402 433 404 433 426 22 406 22 427 22 426 22 404 22 406 22 427 22 408 22 428 22 427 22 406 22 408 22 428 22 410 22 429 22 428 22 408 22 410 22 429 434 412 434 430 434 429 22 410 22 412 22 430 435 414 435 431 435 430 436 412 436 414 436 431 437 385 437 416 437 431 438 414 438 385 438 431 439 432 439 430 439 431 440 433 440 432 440 434 22 436 22 435 22 436 22 438 22 437 22 438 441 432 441 433 441 432 442 440 442 439 442 440 22 442 22 441 22 442 443 444 443 443 443 442 22 445 22 444 22 434 22 438 22 436 22 446 444 438 444 434 444 440 22 445 22 442 22 440 445 447 445 445 445 448 446 438 446 446 446 449 22 438 22 448 22 432 22 447 22 440 22 432 22 450 22 447 22 449 22 432 22 438 22 432 22 449 22 450 22 451 22 442 22 443 22 442 22 453 22 452 22 453 447 455 447 454 447 455 22 457 22 456 22 457 22 436 22 458 22 436 448 459 448 435 448 436 22 460 22 459 22 451 22 453 22 442 22 461 449 453 449 451 449 457 22 460 22 436 22 457 450 462 450 460 450 463 451 453 451 461 451 464 22 453 22 463 22 455 22 462 22 457 22 455 22 465 22 462 22 464 22 455 22 453 22 455 22 464 22 465 22 424 452 454 452 423 452 424 452 453 452 454 452 417 453 438 453 416 453 417 453 437 453 438 453 416 454 433 454 431 454 416 454 438 454 433 454 425 455 453 455 424 455 425 455 452 455 453 455 418 456 437 456 417 456 418 457 436 457 437 457 426 458 452 458 425 458 426 459 442 459 452 459 419 460 436 460 418 460 419 461 458 461 436 461 427 462 442 462 426 462 427 463 441 463 442 463 420 464 458 464 419 464 420 465 457 465 458 465 428 466 441 466 427 466 428 467 440 467 441 467 421 468 457 468 420 468 421 469 456 469 457 469 429 470 440 470 428 470 429 471 439 471 440 471 422 472 456 472 421 472 422 473 455 473 456 473 430 474 439 474 429 474 430 475 432 475 439 475 423 476 455 476 422 476 423 477 454 477 455 477 466 15 384 15 415 15 384 478 389 478 387 478 389 15 393 15 391 15 393 15 397 15 395 15 397 15 467 15 399 15 397 479 468 479 467 479 469 15 384 15 466 15 470 15 384 15 469 15 397 15 471 15 468 15 397 15 472 15 471 15 470 15 389 15 384 15 473 15 389 15 470 15 393 15 472 15 397 15 393 15 474 15 472 15 475 15 389 15 473 15 393 15 475 15 474 15 389 480 475 480 393 480 476 15 399 15 467 15 399 15 403 15 401 15 403 15 407 15 405 15 407 15 411 15 409 15 411 481 415 481 413 481 415 15 477 15 466 15 415 15 478 15 477 15 476 15 403 15 399 15 479 15 403 15 476 15 411 482 478 482 415 482 411 15 480 15 478 15 481 15 403 15 479 15 482 15 403 15 481 15 407 483 480 483 411 483 407 484 483 484 480 484 482 15 407 15 403 15 407 15 482 15 483 15 471 485 464 485 468 485 471 486 465 486 464 486 476 487 464 487 463 487 464 488 467 488 468 488 464 489 476 489 467 489 463 490 479 490 476 490 463 491 461 491 479 491 479 492 451 492 481 492 479 493 461 493 451 493 451 494 482 494 481 494 482 495 443 495 444 495 482 496 451 496 443 496 483 497 444 497 445 497 483 498 482 498 444 498 480 499 445 499 447 499 480 500 483 500 445 500 478 501 447 501 450 501 478 502 480 502 447 502 477 503 450 503 449 503 477 504 478 504 450 504 448 505 477 505 449 505 466 506 448 506 469 506 477 507 448 507 466 507 470 508 448 508 446 508 470 508 469 508 448 508 473 509 446 509 434 509 473 510 470 510 446 510 473 511 459 511 475 511 435 512 473 512 434 512 459 513 473 513 435 513 460 514 475 514 459 514 460 514 474 514 475 514 460 515 472 515 474 515 460 296 462 296 472 296 472 516 465 516 471 516 472 517 462 517 465 517 484 518 486 518 485 518 486 519 488 519 487 519 486 520 484 520 488 520 489 521 491 521 490 521 491 522 493 522 492 522 491 523 489 523 493 523 490 524 484 524 489 524 490 525 488 525 484 525 494 526 488 526 495 526 488 527 496 527 487 527 488 528 494 528 496 528 497 529 491 529 498 529 491 530 499 530 490 530 491 531 497 531 499 531 487 532 498 532 491 532 487 533 496 533 498 533 496 15 497 15 498 15 496 534 494 534 497 534 499 535 494 535 495 535 499 536 497 536 494 536 490 537 495 537 488 537 490 538 499 538 495 538 484 539 493 539 489 539 484 540 485 540 493 540 492 22 485 22 486 22 492 541 493 541 485 541 500 542 502 542 501 542 502 543 504 543 503 543 502 544 500 544 504 544 505 545 507 545 506 545 507 546 509 546 508 546 507 547 505 547 509 547 506 548 500 548 505 548 506 549 504 549 500 549 510 550 504 550 511 550 504 551 512 551 503 551 504 552 510 552 512 552 513 553 507 553 514 553 507 554 515 554 506 554 507 555 513 555 515 555 503 556 514 556 507 556 503 557 512 557 514 557 512 15 513 15 514 15 512 558 510 558 513 558 515 559 510 559 511 559 515 560 513 560 510 560 506 561 511 561 504 561 506 562 515 562 511 562 500 563 509 563 505 563 500 564 501 564 509 564 508 565 501 565 502 565 508 566 509 566 501 566 516 567 518 567 517 567 518 51 520 51 519 51 518 568 516 568 520 568 521 49 523 49 522 49 521 49 524 49 523 49 525 569 527 569 526 569 525 570 528 570 527 570 529 571 531 571 530 571 529 22 518 22 531 22 532 22 534 22 533 22 532 22 535 22 534 22 536 355 538 355 537 355 536 22 539 22 538 22 540 57 542 57 541 57 540 57 543 57 542 57 544 55 546 55 545 55 544 55 547 55 546 55 547 55 548 55 546 55 547 55 549 55 548 55 549 55 526 55 548 55 549 572 525 572 526 572 550 49 552 49 551 49 550 49 553 49 552 49 554 55 545 55 555 55 554 55 544 55 545 55 556 49 551 49 557 49 556 49 550 49 551 49 558 49 557 49 559 49 558 49 556 49 557 49 560 49 559 49 561 49 560 49 558 49 559 49 524 49 561 49 523 49 524 49 560 49 561 49 562 22 535 22 532 22 562 22 563 22 535 22 563 22 536 22 535 22 563 22 564 22 536 22 564 22 539 22 536 22 564 22 565 22 539 22 565 22 529 22 539 22 565 22 566 22 529 22 531 51 568 51 567 51 568 51 570 51 569 51 568 51 531 51 570 51 538 22 572 22 571 22 538 22 530 22 572 22 537 22 571 22 573 22 537 22 538 22 571 22 534 22 573 22 574 22 534 22 537 22 573 22 533 22 574 22 575 22 533 22 534 22 574 22 576 55 578 55 577 55 576 55 579 55 578 55 580 49 520 49 581 49 580 573 582 573 520 573 583 15 569 15 570 15 583 15 584 15 569 15 582 15 519 15 520 15 582 15 585 15 519 15 585 15 570 15 519 15 585 574 583 574 570 574 586 15 588 15 587 15 586 15 589 15 588 15 590 15 592 15 591 15 590 358 593 358 592 358 594 15 586 15 595 15 586 15 597 15 596 15 586 15 594 15 597 15 595 15 587 15 598 15 595 15 586 15 587 15 598 15 590 15 599 15 598 15 587 15 590 15 599 15 591 15 600 15 599 15 590 15 591 15 600 15 585 15 582 15 600 15 591 15 585 15 601 15 577 15 589 15 577 15 602 15 576 15 577 575 601 575 602 575 589 15 603 15 588 15 589 15 577 15 603 15 588 15 604 15 593 15 588 15 603 15 604 15 593 15 605 15 592 15 593 15 604 15 605 15 592 15 584 15 583 15 592 15 605 15 584 15 606 49 594 49 595 49 606 49 607 49 594 49 606 49 598 49 608 49 606 49 595 49 598 49 608 49 599 49 609 49 608 49 598 49 599 49 609 49 600 49 610 49 609 49 599 49 600 49 610 576 582 576 580 576 610 49 600 49 582 49 611 55 584 55 612 55 611 55 569 55 584 55 612 55 605 55 613 55 612 55 584 55 605 55 613 55 604 55 614 55 613 55 605 55 604 55 614 55 603 55 615 55 614 55 604 55 603 55 615 55 577 55 578 55 615 55 603 55 577 55 521 15 612 15 524 15 521 15 611 15 612 15 530 22 567 22 572 22 530 22 531 22 567 22 566 22 518 22 529 22 566 22 517 22 518 22 616 22 532 22 617 22 532 22 618 22 562 22 532 22 616 22 618 22 542 55 555 55 541 55 542 55 554 55 555 55 543 15 554 15 542 15 554 15 607 15 606 15 554 577 543 577 607 577 619 22 575 22 620 22 575 22 621 22 533 22 575 578 619 578 621 578 622 57 552 57 553 57 622 579 623 579 552 579 528 580 516 580 527 580 516 51 581 51 520 51 516 581 528 581 581 581 518 51 570 51 531 51 518 51 519 51 570 51 579 15 550 15 578 15 550 15 622 15 553 15 550 15 579 15 622 15 556 15 578 15 550 15 556 15 615 15 578 15 558 15 615 15 556 15 558 15 614 15 615 15 560 15 614 15 558 15 560 15 613 15 614 15 524 15 613 15 560 15 524 15 612 15 613 15 525 15 581 15 528 15 525 15 580 15 581 15 549 15 580 15 525 15 549 15 610 15 580 15 547 15 610 15 549 15 547 15 609 15 610 15 544 15 609 15 547 15 544 15 608 15 609 15 554 15 608 15 544 15 554 15 606 15 608 15 596 49 532 49 586 49 596 49 617 49 532 49 536 49 587 49 535 49 536 49 590 49 587 49 529 49 591 49 539 49 529 49 585 49 591 49 621 55 589 55 533 55 621 55 601 55 589 55 534 582 593 582 537 582 534 583 588 583 593 583 538 55 583 55 530 55 538 55 592 55 583 55 533 57 586 57 532 57 533 57 589 57 586 57 535 51 588 51 534 51 535 51 587 51 588 51 537 57 590 57 536 57 537 57 593 57 590 57 539 51 592 51 538 51 539 51 591 51 592 51 530 57 585 57 529 57 530 584 583 584 585 584 567 51 568 51 522 51 552 585 623 585 624 585 527 586 516 586 517 586 625 587 540 587 541 587 620 588 552 588 624 588 552 383 575 383 551 383 552 589 620 589 575 589 566 379 527 379 517 379 566 590 526 590 527 590 567 385 523 385 572 385 567 376 522 376 523 376 572 385 561 385 571 385 572 385 523 385 561 385 571 383 559 383 573 383 571 385 561 385 559 385 573 385 557 385 574 385 573 385 559 385 557 385 574 385 551 385 575 385 574 385 557 385 551 385 625 591 562 591 618 591 562 374 541 374 555 374 562 592 625 592 541 592 562 378 545 378 563 378 562 380 555 380 545 380 563 378 546 378 564 378 563 380 545 380 546 380 564 378 548 378 565 378 564 374 546 374 548 374 565 378 526 378 566 378 565 380 548 380 526 380 568 51 521 51 522 51 521 51 569 51 611 51 521 593 568 593 569 593 543 594 594 594 607 594 594 595 616 595 597 595 616 596 625 596 618 596 540 597 594 597 543 597 616 598 540 598 625 598 594 599 540 599 616 599 617 600 597 600 616 600 617 601 596 601 597 601 601 602 619 602 602 602 601 603 621 603 619 603 619 604 576 604 602 604 576 605 622 605 579 605 623 606 620 606 624 606 576 607 623 607 622 607 620 608 576 608 619 608 576 609 620 609 623 609 626 414 628 414 627 414 626 415 629 415 628 415 629 610 630 610 628 610 629 610 631 610 630 610 631 418 632 418 630 418 631 418 633 418 632 418 633 419 634 419 632 419 633 419 635 419 634 419 635 420 636 420 634 420 635 420 637 420 636 420 637 611 638 611 636 611 637 612 639 612 638 612 639 613 640 613 638 613 639 614 641 614 640 614 641 424 642 424 640 424 641 424 643 424 642 424 643 403 644 403 642 403 643 404 645 404 644 404 645 615 646 615 644 615 645 615 647 615 646 615 647 616 648 616 646 616 647 406 649 406 648 406 649 407 650 407 648 407 649 407 651 407 650 407 651 408 652 408 650 408 651 408 653 408 652 408 653 617 654 617 652 617 653 618 655 618 654 618 655 619 656 619 654 619 655 619 657 619 656 619 657 413 627 413 656 413 657 413 626 413 627 413 658 432 628 432 659 432 658 22 627 22 628 22 659 22 630 22 660 22 659 620 628 620 630 620 660 22 632 22 661 22 660 22 630 22 632 22 661 22 634 22 662 22 661 22 632 22 634 22 662 621 636 621 663 621 662 22 634 22 636 22 663 622 638 622 664 622 663 22 636 22 638 22 664 435 640 435 665 435 664 22 638 22 640 22 665 437 642 437 666 437 665 438 640 438 642 438 666 425 644 425 667 425 666 22 642 22 644 22 667 22 646 22 668 22 667 623 644 623 646 623 668 22 648 22 669 22 668 22 646 22 648 22 669 22 650 22 670 22 669 22 648 22 650 22 670 22 652 22 671 22 670 22 650 22 652 22 671 624 654 624 672 624 671 22 652 22 654 22 672 429 656 429 673 429 672 625 654 625 656 625 673 430 627 430 658 430 673 431 656 431 627 431 673 476 674 476 672 476 673 477 675 477 674 477 676 22 678 22 677 22 678 22 680 22 679 22 680 447 674 447 675 447 674 441 682 441 681 441 682 22 684 22 683 22 684 626 686 626 685 626 684 22 687 22 686 22 676 22 680 22 678 22 688 449 680 449 676 449 682 22 687 22 684 22 682 450 689 450 687 450 690 451 680 451 688 451 691 22 680 22 690 22 674 22 689 22 682 22 674 22 692 22 689 22 691 22 674 22 680 22 674 22 691 22 692 22 693 22 684 22 685 22 684 22 695 22 694 22 695 441 697 441 696 441 697 22 699 22 698 22 699 22 678 22 700 22 678 627 701 627 677 627 678 22 702 22 701 22 693 22 695 22 684 22 703 444 695 444 693 444 699 22 702 22 678 22 699 445 704 445 702 445 705 628 695 628 703 628 706 22 695 22 705 22 697 22 704 22 699 22 697 22 707 22 704 22 706 22 697 22 695 22 697 22 706 22 707 22 666 454 696 454 665 454 666 454 695 454 696 454 659 455 680 455 658 455 659 455 679 455 680 455 658 452 675 452 673 452 658 452 680 452 675 452 667 453 695 453 666 453 667 453 694 453 695 453 660 629 679 629 659 629 660 630 678 630 679 630 668 631 694 631 667 631 668 632 684 632 694 632 661 462 678 462 660 462 661 463 700 463 678 463 669 460 684 460 668 460 669 461 683 461 684 461 662 466 700 466 661 466 662 633 699 633 700 633 670 464 683 464 669 464 670 634 682 634 683 634 663 635 699 635 662 635 663 636 698 636 699 636 671 637 682 637 670 637 671 638 681 638 682 638 664 639 698 639 663 639 664 640 697 640 698 640 672 641 681 641 671 641 672 642 674 642 681 642 665 439 697 439 664 439 665 440 696 440 697 440 708 15 626 15 657 15 626 643 631 643 629 643 631 15 635 15 633 15 635 15 639 15 637 15 639 15 709 15 641 15 639 644 710 644 709 644 711 15 626 15 708 15 712 15 626 15 711 15 639 15 713 15 710 15 639 15 714 15 713 15 712 15 631 15 626 15 715 15 631 15 712 15 635 15 714 15 639 15 635 15 716 15 714 15 717 15 631 15 715 15 635 15 717 15 716 15 631 645 717 645 635 645 718 15 641 15 709 15 641 15 645 15 643 15 645 15 649 15 647 15 649 15 653 15 651 15 653 646 657 646 655 646 657 15 719 15 708 15 657 15 720 15 719 15 718 15 645 15 641 15 721 15 645 15 718 15 653 647 720 647 657 647 653 15 722 15 720 15 723 15 645 15 721 15 724 15 645 15 723 15 649 648 722 648 653 648 649 649 725 649 722 649 724 15 649 15 645 15 649 15 724 15 725 15 713 504 706 504 710 504 713 503 707 503 706 503 718 650 706 650 705 650 706 651 709 651 710 651 706 652 718 652 709 652 705 508 721 508 718 508 705 653 703 653 721 653 721 510 693 510 723 510 721 509 703 509 693 509 693 654 724 654 723 654 724 655 685 655 686 655 724 656 693 656 685 656 725 514 686 514 687 514 725 657 724 657 686 657 722 296 687 296 689 296 722 658 725 658 687 658 720 517 689 517 692 517 720 516 722 516 689 516 719 486 692 486 691 486 719 485 720 485 692 485 690 659 719 659 691 659 708 660 690 660 711 660 719 661 690 661 708 661 712 490 690 490 688 490 712 490 711 490 690 490 715 493 688 493 676 493 715 492 712 492 688 492 715 662 701 662 717 662 677 663 715 663 676 663 701 664 715 664 677 664 702 497 717 497 701 497 702 497 716 497 717 497 702 665 714 665 716 665 702 499 704 499 714 499 714 502 707 502 713 502 714 501 704 501 707 501 726 666 727 666 728 666 728 667 729 667 730 667 728 668 730 668 726 668 731 669 732 669 733 669 733 670 734 670 735 670 733 671 735 671 731 671 732 672 731 672 726 672 732 672 726 672 730 672 736 11 737 11 730 11 730 673 729 673 738 673 730 674 738 674 736 674 739 675 740 675 733 675 733 676 732 676 741 676 733 677 741 677 739 677 729 678 733 678 740 678 729 678 740 678 738 678 738 15 740 15 739 15 738 15 739 15 736 15 741 679 737 679 736 679 741 680 736 680 739 680 732 681 730 681 737 681 732 682 737 682 741 682 726 683 731 683 735 683 726 684 735 684 727 684 734 22 728 22 727 22 734 22 727 22 735 22 742 685 743 685 744 685 744 686 745 686 746 686 744 687 746 687 742 687 747 688 748 688 749 688 749 689 750 689 751 689 749 690 751 690 747 690 748 691 747 691 742 691 748 692 742 692 746 692 752 693 753 693 746 693 746 686 745 686 754 686 746 694 754 694 752 694 755 695 756 695 749 695 749 689 748 689 757 689 749 696 757 696 755 696 745 697 749 697 756 697 745 698 756 698 754 698 754 15 756 15 755 15 754 15 755 15 752 15 757 699 753 699 752 699 757 700 752 700 755 700 748 701 746 701 753 701 748 702 753 702 757 702 742 703 747 703 751 703 742 704 751 704 743 704 750 22 744 22 743 22 750 705 743 705 751 705 758 706 759 706 760 706 760 55 761 55 762 55 760 55 762 55 758 55 763 57 764 57 765 57 763 57 765 57 766 57 767 707 768 707 769 707 767 708 769 708 770 708 771 22 772 22 773 22 771 22 773 22 760 22 774 22 775 22 776 22 774 22 776 22 777 22 778 22 779 22 780 22 778 22 780 22 781 22 782 49 783 49 784 49 782 49 784 49 785 49 786 51 787 51 788 51 786 51 788 51 789 51 789 51 788 51 790 51 789 51 790 51 791 51 791 51 790 51 768 51 791 51 768 51 767 51 792 57 793 57 794 57 792 57 794 57 795 57 796 51 797 51 787 51 796 51 787 51 786 51 798 57 799 57 793 57 798 57 793 57 792 57 800 57 801 57 799 57 800 57 799 57 798 57 802 57 803 57 801 57 802 57 801 57 800 57 766 57 765 57 803 57 766 57 803 57 802 57 804 22 774 22 777 22 804 22 777 22 805 22 805 22 777 22 778 22 805 22 778 22 806 22 806 22 778 22 781 22 806 22 781 22 807 22 807 22 781 22 771 22 807 22 771 22 808 22 773 709 809 709 810 709 810 55 811 55 812 55 810 55 812 55 773 55 780 22 813 22 814 22 780 22 814 22 772 22 779 22 815 22 813 22 779 22 813 22 780 22 776 22 816 22 815 22 776 22 815 22 779 22 775 22 817 22 816 22 775 22 816 22 776 22 818 51 819 51 820 51 818 51 820 51 821 51 822 57 823 57 762 57 822 57 762 57 824 57 825 15 812 15 811 15 825 15 811 15 826 15 824 15 762 15 761 15 824 15 761 15 827 15 827 15 761 15 812 15 827 15 812 15 825 15 828 15 829 15 830 15 828 15 830 15 831 15 832 15 833 15 834 15 832 15 834 15 835 15 836 15 837 15 828 15 828 710 838 710 839 710 828 711 839 711 836 711 837 15 840 15 829 15 837 15 829 15 828 15 840 15 841 15 832 15 840 15 832 15 829 15 841 15 842 15 833 15 841 15 833 15 832 15 842 15 824 15 827 15 842 15 827 15 833 15 843 15 831 15 819 15 819 712 818 712 844 712 819 713 844 713 843 713 831 15 830 15 845 15 831 15 845 15 819 15 830 15 835 15 846 15 830 15 846 15 845 15 835 15 834 15 847 15 835 15 847 15 846 15 834 15 825 15 826 15 834 15 826 15 847 15 848 57 837 57 836 57 848 57 836 57 849 57 848 57 850 57 840 57 848 57 840 57 837 57 850 57 851 57 841 57 850 57 841 57 840 57 851 57 852 57 842 57 851 57 842 57 841 57 852 57 822 57 824 57 852 57 824 57 842 57 853 51 854 51 826 51 853 51 826 51 811 51 854 51 855 51 847 51 854 51 847 51 826 51 855 51 856 51 846 51 855 51 846 51 847 51 856 51 857 51 845 51 856 51 845 51 846 51 857 51 820 51 819 51 857 51 819 51 845 51 763 15 766 15 854 15 763 15 854 15 853 15 772 22 814 22 809 22 772 22 809 22 773 22 808 22 771 22 760 22 808 22 760 22 759 22 858 22 859 22 774 22 774 22 804 22 860 22 774 22 860 22 858 22 784 51 783 51 797 51 784 51 797 51 796 51 785 15 784 15 796 15 796 15 848 15 849 15 796 714 849 714 785 714 861 22 862 22 817 22 817 22 775 22 863 22 817 715 863 715 861 715 864 49 795 49 794 49 864 49 794 49 865 49 770 55 769 55 758 55 758 55 762 55 823 55 758 55 823 55 770 55 760 55 773 55 812 55 760 55 812 55 761 55 821 15 820 15 792 15 792 15 795 15 864 15 792 716 864 716 821 716 798 15 792 15 820 15 798 15 820 15 857 15 800 15 798 15 857 15 800 15 857 15 856 15 802 15 800 15 856 15 802 15 856 15 855 15 766 15 802 15 855 15 766 15 855 15 854 15 767 15 770 15 823 15 767 15 823 15 822 15 791 15 767 15 822 15 791 15 822 15 852 15 789 15 791 15 852 15 789 15 852 15 851 15 786 15 789 15 851 15 786 15 851 15 850 15 796 15 786 15 850 15 796 15 850 15 848 15 838 57 828 57 774 57 838 57 774 57 859 57 778 57 777 57 829 57 778 57 829 57 832 57 771 57 781 57 833 57 771 57 833 57 827 57 863 51 775 51 831 51 863 51 831 51 843 51 776 717 779 717 835 717 776 718 835 718 830 718 780 51 772 51 825 51 780 51 825 51 834 51 775 49 774 49 828 49 775 49 828 49 831 49 777 55 776 55 830 55 777 55 830 55 829 55 779 49 778 49 832 49 779 49 832 49 835 49 781 55 780 55 834 55 781 55 834 55 833 55 772 49 771 49 827 49 772 49 827 49 825 49 809 719 764 719 810 719 794 49 866 49 865 49 769 720 759 720 758 720 867 49 783 49 782 49 862 721 866 721 794 721 794 722 793 722 817 722 794 723 817 723 862 723 808 724 759 724 769 724 808 725 769 725 768 725 809 726 814 726 765 726 809 722 765 722 764 722 814 727 813 727 803 727 814 728 803 728 765 728 813 726 815 726 801 726 813 728 801 728 803 728 815 726 816 726 799 726 815 722 799 722 801 722 816 726 817 726 793 726 816 728 793 728 799 728 867 729 860 729 804 729 804 730 797 730 783 730 804 731 783 731 867 731 804 129 805 129 787 129 804 732 787 732 797 732 805 733 806 733 788 733 805 732 788 732 787 732 806 129 807 129 790 129 806 732 790 732 788 732 807 129 808 129 768 129 807 730 768 730 790 730 810 55 764 55 763 55 763 55 853 55 811 55 763 734 811 734 810 734 785 735 849 735 836 735 836 736 839 736 858 736 858 737 860 737 867 737 782 738 785 738 836 738 858 739 867 739 782 739 836 740 858 740 782 740 859 741 858 741 839 741 859 742 839 742 838 742 843 743 844 743 861 743 843 744 861 744 863 744 861 745 844 745 818 745 818 746 821 746 864 746 865 747 866 747 862 747 818 748 864 748 865 748 862 749 861 749 818 749 818 750 865 750 862 750 868 751 869 751 870 751 868 752 870 752 871 752 871 753 870 753 872 753 871 754 872 754 873 754 873 755 872 755 874 755 873 756 874 756 875 756 875 757 874 757 876 757 875 757 876 757 877 757 877 758 876 758 878 758 877 759 878 759 879 759 879 760 878 760 880 760 879 760 880 760 881 760 881 761 880 761 882 761 881 762 882 762 883 762 883 763 882 763 884 763 883 764 884 764 885 764 885 765 884 765 886 765 885 766 886 766 887 766 887 767 886 767 888 767 887 768 888 768 889 768 889 769 888 769 890 769 889 770 890 770 891 770 891 771 890 771 892 771 891 771 892 771 893 771 893 772 892 772 894 772 893 773 894 773 895 773 895 774 894 774 896 774 895 774 896 774 897 774 897 775 896 775 898 775 897 776 898 776 899 776 899 777 898 777 869 777 899 778 869 778 868 778 900 779 901 779 870 779 900 780 870 780 869 780 901 437 902 437 872 437 901 781 872 781 870 781 902 782 903 782 874 782 902 783 874 783 872 783 903 784 904 784 876 784 903 22 876 22 874 22 904 785 905 785 878 785 904 786 878 786 876 786 905 22 906 22 880 22 905 787 880 787 878 787 906 22 907 22 882 22 906 22 882 22 880 22 907 22 908 22 884 22 907 22 884 22 882 22 908 788 909 788 886 788 908 783 886 783 884 783 909 428 910 428 888 428 909 22 888 22 886 22 910 624 911 624 890 624 910 22 890 22 888 22 911 789 912 789 892 789 911 22 892 22 890 22 912 790 913 790 894 790 912 791 894 791 892 791 913 22 914 22 896 22 913 792 896 792 894 792 914 22 915 22 898 22 914 22 898 22 896 22 915 22 900 22 869 22 915 22 869 22 898 22 915 793 914 793 916 793 915 794 916 794 917 794 918 795 919 795 920 795 920 796 921 796 922 796 922 22 917 22 916 22 916 797 923 797 924 797 924 22 925 22 926 22 926 22 927 22 928 22 926 22 928 22 929 22 918 22 920 22 922 22 930 22 918 22 922 22 924 22 926 22 929 22 924 798 929 798 931 798 932 799 930 799 922 799 933 800 932 800 922 800 916 801 924 801 931 801 916 22 931 22 934 22 933 22 922 22 916 22 916 22 934 22 933 22 935 802 927 802 926 802 926 442 936 442 937 442 937 22 938 22 939 22 939 803 940 803 941 803 941 22 942 22 920 22 920 22 919 22 943 22 920 804 943 804 944 804 935 22 926 22 937 22 945 22 935 22 937 22 941 22 920 22 944 22 941 805 944 805 946 805 947 22 945 22 937 22 948 806 947 806 937 806 939 807 941 807 946 807 939 22 946 22 949 22 948 22 937 22 939 22 939 22 949 22 948 22 908 808 907 808 938 808 908 809 938 809 937 809 901 810 900 810 922 810 901 810 922 810 921 810 900 811 915 811 917 811 900 812 917 812 922 812 909 813 908 813 937 813 909 813 937 813 936 813 902 814 901 814 921 814 902 815 921 815 920 815 910 816 909 816 936 816 910 817 936 817 926 817 903 818 902 818 920 818 903 819 920 819 942 819 911 820 910 820 926 820 911 821 926 821 925 821 904 822 903 822 942 822 904 823 942 823 941 823 912 691 911 691 925 691 912 824 925 824 924 824 905 825 904 825 941 825 905 826 941 826 940 826 913 827 912 827 924 827 913 828 924 828 923 828 906 829 905 829 940 829 906 829 940 829 939 829 914 830 913 830 923 830 914 830 923 830 916 830 907 831 906 831 939 831 907 832 939 832 938 832 950 833 899 833 868 833 868 834 871 834 873 834 873 835 875 835 877 835 877 836 879 836 881 836 881 15 883 15 951 15 881 837 951 837 952 837 953 15 950 15 868 15 954 838 953 838 868 838 881 15 952 15 955 15 881 15 955 15 956 15 954 15 868 15 873 15 957 839 954 839 873 839 877 15 881 15 956 15 877 15 956 15 958 15 959 15 957 15 873 15 877 840 958 840 959 840 873 841 877 841 959 841 960 15 951 15 883 15 883 15 885 15 887 15 887 15 889 15 891 15 891 15 893 15 895 15 895 842 897 842 899 842 899 843 950 843 961 843 899 844 961 844 962 844 960 845 883 845 887 845 963 15 960 15 887 15 895 846 899 846 962 846 895 15 962 15 964 15 965 15 963 15 887 15 966 15 965 15 887 15 891 847 895 847 964 847 891 848 964 848 967 848 966 15 887 15 891 15 891 15 967 15 966 15 955 849 952 849 948 849 955 849 948 849 949 849 960 850 947 850 948 850 948 851 952 851 951 851 948 852 951 852 960 852 947 853 960 853 963 853 947 854 963 854 945 854 963 855 965 855 935 855 963 856 935 856 945 856 935 857 965 857 966 857 966 858 928 858 927 858 966 859 927 859 935 859 967 860 929 860 928 860 967 861 928 861 966 861 964 862 931 862 929 862 964 863 929 863 967 863 962 864 934 864 931 864 962 864 931 864 964 864 961 865 933 865 934 865 961 865 934 865 962 865 932 866 933 866 961 866 950 867 953 867 932 867 961 868 950 868 932 868 954 869 930 869 932 869 954 870 932 870 953 870 957 871 918 871 930 871 957 872 930 872 954 872 957 873 959 873 943 873 919 874 918 874 957 874 943 875 919 875 957 875 944 876 943 876 959 876 944 877 959 877 958 877 944 878 958 878 956 878 944 879 956 879 946 879 956 880 955 880 949 880 956 880 949 880 946 880</p>\n        </triangles>\n      </mesh>\n    </geometry>\n    <geometry id=\"cw_prop-mesh\" name=\"cw_prop\">\n      <mesh>\n        <source id=\"cw_prop-mesh-positions\">\n          <float_array id=\"cw_prop-mesh-positions-array\" count=\"1404\">0 -0.001999974 -0.001999974 0 -0.001999974 0.001421093 -7.65367e-4 -0.001847743 0.00131154 -7.65367e-4 -0.001847743 -0.001999974 -0.001414179 -0.001414179 9.99604e-4 -0.001414179 -0.001414179 -0.001999974 -0.001847743 -7.65367e-4 5.32729e-4 -0.001847743 -7.65367e-4 -0.001999974 -0.001999974 0 -1.79885e-5 -0.001999974 0 -0.001999974 -0.001847743 7.65367e-4 -5.68705e-4 -0.001847743 7.65367e-4 -0.001999974 -0.001414179 0.001414179 -0.001035571 -0.001414179 0.001414179 -0.001999974 -7.65367e-4 0.001847743 -0.001347482 -7.65367e-4 0.001847743 -0.001999974 0 0.001999974 -0.001457035 0 0.001999974 -0.001999974 7.65367e-4 0.001847743 -0.001999974 0 0.001999974 0.001999974 7.65367e-4 0.001847743 0.001999974 0.001414179 0.001414179 0.001999974 0.001414179 0.001414179 -0.001999974 0.001847743 7.65367e-4 0.001999974 0.001847743 7.65367e-4 -0.001999974 0.001999974 0 0.001999974 0.001999974 0 -0.001999974 0.001847743 -7.65367e-4 0.001999974 0.001847743 -7.65367e-4 -0.001999974 0.001414179 -0.001414179 0.001999974 0.001414179 -0.001414179 -0.001999974 -0.001414179 -0.001414179 0.001999974 -7.65367e-4 -0.001847743 0.001999974 0 -0.001999974 0.001999974 7.65367e-4 -0.001847743 0.001999974 -7.65367e-4 0.001847743 0.001999974 -0.001414179 0.001414179 0.001999974 -0.001847743 7.65367e-4 0.001999974 -0.001999974 0 0.001999974 -0.001847743 -7.65367e-4 0.001999974 7.65367e-4 -0.001847743 -0.001999974 7.65367e-4 -0.001847743 -0.001347482 0 -0.001999974 -0.001457035 0.01653528 -0.004334032 -9.65724e-4 0.02133989 -0.003939688 -4.56432e-4 0.001847743 7.65367e-4 5.32729e-4 0.001999974 0 -1.79885e-5 0.02345544 -4.78913e-4 0.001098155 0.0231958 7.50976e-4 0.001266658 0.001414179 0.001414179 9.99604e-4 0.02240127 0.002166092 0.001186668 7.65366e-4 0.001847743 0.00131154 0.02022266 0.003809988 0.001138865 0.001847743 -7.65367e-4 -5.68705e-4 0.02341061 -0.002114474 5.80571e-4 0 0.001999974 0.001421093 0.01448982 0.004217267 0.001118838 0.001414179 -0.001414179 -0.001035571 0.02314895 -0.003187358 1.38679e-4 0 0 0 -7.65368e-4 0.001847743 -0.001347482 0 0.001999974 -0.001457035 -0.01653528 0.004334032 -9.65724e-4 -0.02133989 0.003939688 -4.56432e-4 -0.001847743 -7.65367e-4 5.32729e-4 -0.001999974 0 -1.79885e-5 -0.02345544 4.78909e-4 0.001098155 -0.0231958 -7.50979e-4 0.001266658 -0.001414179 -0.001414179 9.99604e-4 -0.02240127 -0.002166092 0.001186668 -7.65366e-4 -0.001847743 0.00131154 -0.02022266 -0.003809988 0.001138865 -0.001847743 7.65367e-4 -5.68705e-4 -0.02341061 0.002114474 5.80571e-4 -0.01448982 -0.004217267 0.001118838 -0.001414179 0.001414179 -0.001035571 -0.02314895 0.003187358 1.38679e-4 8.03577e-4 -0.001669585 -0.001813113 0.02138286 -0.003702402 -8.94434e-4 0.01657199 -0.004173696 -0.001437842 3.67138e-5 -0.001839578 -0.001929223 0.001862168 8.94353e-4 4.98801e-5 0.02321308 8.96381e-4 7.88594e-4 0.02348321 -2.90873e-4 6.35759e-4 0.002027451 1.872e-4 -4.80802e-4 0.001414418 0.001484632 5.04594e-4 0.02240705 0.002253592 6.94454e-4 7.59125e-4 0.001859784 8.11758e-4 0.02021872 0.003864169 6.41829e-4 0.02344667 -0.001904726 1.28149e-4 0.001884579 -5.53324e-4 -0.001019954 -6.9277e-6 0.001999497 9.21166e-4 0.01448291 0.00421679 6.18956e-4 0.001456499 -0.001178562 -0.001474499 0.02318966 -0.002962052 -3.05808e-4 0 0 -5e-4 -8.03577e-4 0.001669585 -0.001813113 -0.02138286 0.003702402 -8.94434e-4 -0.01657199 0.004173696 -0.001437842 -3.67141e-5 0.001839578 -0.001929223 -0.001862168 -8.94354e-4 4.98801e-5 -0.02321308 -8.96385e-4 7.88594e-4 -0.02348321 2.90869e-4 6.35759e-4 -0.002027451 -1.87201e-4 -4.80802e-4 -0.001414418 -0.001484632 5.04594e-4 -0.02240705 -0.002253592 6.94454e-4 -7.59125e-4 -0.001859784 8.11758e-4 -0.02021872 -0.003864169 6.41829e-4 -0.02344667 0.001904726 1.28149e-4 -0.001884579 5.53324e-4 -0.001019954 6.928e-6 -0.001999497 9.21166e-4 -0.01448291 -0.00421679 6.18956e-4 -0.001456499 0.001178562 -0.001474499 -0.02318966 0.002962052 -3.05808e-4 -8.03577e-4 0.001669585 -0.001813113 -3.6714e-5 0.001839578 -0.001929223 -0.02318966 0.002962052 -3.05808e-4 -0.0408982 -0.04467964 -0.001999974 -0.0408982 -0.04467964 0.001421093 -0.04108291 -0.04392147 0.00131154 -0.04108291 -0.04392147 -0.001999974 -0.04154372 -0.04329168 9.99604e-4 -0.04154372 -0.04329168 -0.001999974 -0.04221045 -0.04288619 5.32729e-4 -0.04221045 -0.04288619 -0.001999974 -0.04298162 -0.04276669 -1.79885e-5 -0.04298162 -0.04276669 -0.001999974 -0.04373979 -0.0429514 -5.68705e-4 -0.04373979 -0.0429514 -0.001999974 -0.04436957 -0.0434122 -0.001035571 -0.04436957 -0.0434122 -0.001999974 -0.04477506 -0.04407894 -0.001347482 -0.04477506 -0.04407894 -0.001999974 -0.04489457 -0.04485011 -0.001457035 -0.04489457 -0.04485011 -0.001999974 -0.04470986 -0.04560828 -0.001999974 -0.04489457 -0.04485011 0.001999974 -0.04470986 -0.04560828 0.001999974 -0.04424905 -0.04623806 0.001999974 -0.04424905 -0.04623806 -0.001999974 -0.04358232 -0.04664355 0.001999974 -0.04358232 -0.04664355 -0.001999974 -0.04281115 -0.04676306 0.001999974 -0.04281115 -0.04676306 -0.001999974 -0.04205298 -0.04657834 0.001999974 -0.04205298 -0.04657834 -0.001999974 -0.0414232 -0.04611754 0.001999974 -0.0414232 -0.04611754 -0.001999974 -0.04154372 -0.04329168 0.001999974 -0.04108291 -0.04392147 0.001999974 -0.0408982 -0.04467964 0.001999974 -0.04101771 -0.0454508 0.001999974 -0.04477506 -0.04407894 0.001999974 -0.04436957 -0.0434122 0.001999974 -0.04373979 -0.0429514 0.001999974 -0.04298162 -0.04276669 0.001999974 -0.04221045 -0.04288619 0.001999974 -0.04101771 -0.0454508 -0.001999974 -0.04101771 -0.0454508 -0.001347482 -0.0408982 -0.04467964 -0.001457035 -0.03786164 -0.06110048 -9.65724e-4 -0.038051 -0.06591755 -4.56432e-4 -0.04358232 -0.04664355 5.32729e-4 -0.04281115 -0.04676306 -1.79885e-5 -0.04141849 -0.06817865 0.001098155 -0.04265832 -0.06797164 0.001266658 -0.04424905 -0.04623806 9.99604e-4 -0.044106 -0.06723815 0.001186668 -0.04470986 -0.04560828 0.00131154 -0.04584127 -0.06513154 0.001138865 -0.04205298 -0.04657834 -5.68705e-4 -0.03978627 -0.06806421 5.80571e-4 -0.04489457 -0.04485011 0.001421093 -0.04649245 -0.0594213 0.001118838 -0.0414232 -0.04611754 -0.001035571 -0.03872555 -0.06775707 1.38679e-4 -0.04289638 -0.04476487 0 -0.04477506 -0.04407894 -0.001347482 -0.04489457 -0.04485011 -0.001457035 -0.04793113 -0.02842926 -9.65724e-4 -0.04774183 -0.0236122 -4.56432e-4 -0.04221045 -0.04288619 5.32729e-4 -0.04298162 -0.04276669 -1.79885e-5 -0.04437434 -0.02135109 0.001098155 -0.04313451 -0.02155816 0.001266658 -0.04154372 -0.04329168 9.99604e-4 -0.04168677 -0.02229166 0.001186668 -0.04108291 -0.04392147 0.00131154 -0.03995156 -0.0243982 0.001138865 -0.04373979 -0.0429514 -5.68705e-4 -0.0460065 -0.02146559 5.80571e-4 -0.03930032 -0.03010851 0.001118838 -0.04436957 -0.0434122 -0.001035571 -0.04706722 -0.02177274 1.38679e-4 -0.04119402 -0.04549658 -0.001813113 -0.0382862 -0.06597059 -8.94434e-4 -0.03802031 -0.06114399 -0.001437842 -0.04105687 -0.04472315 -0.001929223 -0.04371058 -0.04666352 4.98801e-5 -0.04280287 -0.06799513 7.88594e-4 -0.04160517 -0.06821441 6.35759e-4 -0.04299706 -0.04679846 -4.80802e-4 -0.04431945 -0.04624134 5.04594e-4 -0.0441932 -0.06724768 6.94454e-4 -0.04472219 -0.04560256 8.11758e-4 -0.04589551 -0.06512993 6.41829e-4 -0.03999429 -0.06810909 1.28149e-4 -0.04226326 -0.04662424 -0.001019954 -0.04489439 -0.04484313 9.21166e-4 -0.04649227 -0.05941432 6.18956e-4 -0.04165679 -0.04616987 -0.001474499 -0.03894889 -0.06780731 -3.05808e-4 -0.04289638 -0.04476487 -5e-4 -0.04459875 -0.04403316 -0.001813113 -0.04750657 -0.02355915 -8.94434e-4 -0.04777246 -0.02838575 -0.001437842 -0.0447359 -0.04480659 -0.001929223 -0.04208219 -0.04286623 4.98801e-5 -0.04298996 -0.02153462 7.88594e-4 -0.0441876 -0.02131533 6.35759e-4 -0.04279577 -0.04273128 -4.80802e-4 -0.04147338 -0.0432884 5.04594e-4 -0.04159963 -0.02228212 6.94454e-4 -0.04107064 -0.04392719 8.11758e-4 -0.03989726 -0.02439987 6.41829e-4 -0.04579848 -0.02142065 1.28149e-4 -0.04352951 -0.04290556 -0.001019954 -0.04089838 -0.04468661 9.21166e-4 -0.0393005 -0.03011542 6.18956e-4 -0.04413598 -0.04335993 -0.001474499 -0.04684388 -0.02172249 -3.05808e-4 -0.04459875 -0.04403316 -0.001813113 -0.0447359 -0.04480659 -0.001929223 -0.04684388 -0.02172249 -3.05808e-4 0.04276669 -0.04298162 -0.001999974 0.04276669 -0.04298162 0.001421093 0.0429514 -0.04373979 0.00131154 0.0429514 -0.04373979 -0.001999974 0.0434122 -0.04436957 9.99604e-4 0.0434122 -0.04436957 -0.001999974 0.04407894 -0.04477506 5.32729e-4 0.04407894 -0.04477506 -0.001999974 0.04485011 -0.04489457 -1.79885e-5 0.04485011 -0.04489457 -0.001999974 0.04560828 -0.04470986 -5.68705e-4 0.04560828 -0.04470986 -0.001999974 0.04623806 -0.04424905 -0.001035571 0.04623806 -0.04424905 -0.001999974 0.04664355 -0.04358232 -0.001347482 0.04664355 -0.04358232 -0.001999974 0.04676306 -0.04281115 -0.001457035 0.04676306 -0.04281115 -0.001999974 0.04657834 -0.04205298 -0.001999974 0.04676306 -0.04281115 0.001999974 0.04657834 -0.04205298 0.001999974 0.04611754 -0.0414232 0.001999974 0.04611754 -0.0414232 -0.001999974 0.0454508 -0.04101771 0.001999974 0.0454508 -0.04101771 -0.001999974 0.04467964 -0.0408982 0.001999974 0.04467964 -0.0408982 -0.001999974 0.04392147 -0.04108291 0.001999974 0.04392147 -0.04108291 -0.001999974 0.04329168 -0.04154372 0.001999974 0.04329168 -0.04154372 -0.001999974 0.0434122 -0.04436957 0.001999974 0.0429514 -0.04373979 0.001999974 0.04276669 -0.04298162 0.001999974 0.04288619 -0.04221045 0.001999974 0.04664355 -0.04358232 0.001999974 0.04623806 -0.04424905 0.001999974 0.04560828 -0.04470986 0.001999974 0.04485011 -0.04489457 0.001999974 0.04407894 -0.04477506 0.001999974 0.04288619 -0.04221045 -0.001999974 0.04288619 -0.04221045 -0.001347482 0.04276669 -0.04298162 -0.001457035 0.03973013 -0.02656078 -9.65724e-4 0.03991949 -0.02174371 -4.56432e-4 0.0454508 -0.04101771 5.32729e-4 0.04467964 -0.0408982 -1.79885e-5 0.04328697 -0.01948261 0.001098155 0.04452681 -0.01968967 0.001266658 0.04611754 -0.0414232 9.99604e-4 0.04597449 -0.02042317 0.001186668 0.04657834 -0.04205298 0.00131154 0.04770976 -0.02252972 0.001138865 0.04392147 -0.04108291 -5.68705e-4 0.04165476 -0.01959711 5.80571e-4 0.04676306 -0.04281115 0.001421093 0.04836094 -0.02824002 0.001118838 0.04329168 -0.04154372 -0.001035571 0.04059404 -0.01990425 1.38679e-4 0.04476487 -0.04289638 0 0.04664355 -0.04358232 -0.001347482 0.04676306 -0.04281115 -0.001457035 0.04979962 -0.05923199 -9.65724e-4 0.04961031 -0.06404906 -4.56432e-4 0.04407894 -0.04477506 5.32729e-4 0.04485011 -0.04489457 -1.79885e-5 0.04624283 -0.06631016 0.001098155 0.04500299 -0.06610316 0.001266658 0.0434122 -0.04436957 9.99604e-4 0.04355525 -0.06536966 0.001186668 0.0429514 -0.04373979 0.00131154 0.04182004 -0.06326305 0.001138865 0.04560828 -0.04470986 -5.68705e-4 0.04787498 -0.06619572 5.80571e-4 0.0411688 -0.05755281 0.001118838 0.04623806 -0.04424905 -0.001035571 0.04893571 -0.06588858 1.38679e-4 0.0430625 -0.04216468 -0.001813113 0.04015469 -0.02169066 -8.94434e-4 0.03988879 -0.02651727 -0.001437842 0.04292535 -0.04293811 -0.001929223 0.04557907 -0.04099774 4.98801e-5 0.04467135 -0.01966613 7.88594e-4 0.04347366 -0.01944684 6.35759e-4 0.04486554 -0.04086279 -4.80802e-4 0.04618793 -0.04141992 5.04594e-4 0.04606169 -0.02041363 6.94454e-4 0.04659068 -0.0420587 8.11758e-4 0.047764 -0.02253139 6.41829e-4 0.04186278 -0.01955217 1.28149e-4 0.04413175 -0.04103708 -0.001019954 0.04676288 -0.04281812 9.21166e-4 0.04836076 -0.02824693 6.18956e-4 0.04352527 -0.04149144 -0.001474499 0.04081737 -0.019854 -3.05808e-4 0.04476487 -0.04289638 -5e-4 0.04646724 -0.04362809 -0.001813113 0.04937505 -0.06410211 -8.94434e-4 0.04964095 -0.0592755 -0.001437842 0.04660439 -0.04285466 -0.001929223 0.04395067 -0.04479503 4.98801e-5 0.04485845 -0.06612664 7.88594e-4 0.04605609 -0.06634593 6.35759e-4 0.04466426 -0.04492998 -4.80802e-4 0.04334187 -0.04437285 5.04594e-4 0.04346811 -0.0653792 6.94454e-4 0.04293912 -0.04373407 8.11758e-4 0.04176574 -0.06326144 6.41829e-4 0.04766696 -0.0662406 1.28149e-4 0.04539799 -0.04475575 -0.001019954 0.04276686 -0.04297465 9.21166e-4 0.04116898 -0.05754584 6.18956e-4 0.04600447 -0.04430139 -0.001474499 0.04871237 -0.06593883 -3.05808e-4 0.04646724 -0.04362809 -0.001813113 0.04660439 -0.04285466 -0.001929223 0.04871237 -0.06593883 -3.05808e-4 0.001868486 -0.08566129 -0.001999974 0.001868486 -0.08566129 0.001421093 0.00263381 -0.08581358 0.00131154 0.00263381 -0.08581358 -0.001999974 0.003282666 -0.08624708 9.99604e-4 0.003282666 -0.08624708 -0.001999974 0.00371623 -0.08689594 5.32729e-4 0.00371623 -0.08689594 -0.001999974 0.00386846 -0.08766132 -1.79885e-5 0.00386846 -0.08766132 -0.001999974 0.00371623 -0.0884267 -5.68705e-4 0.00371623 -0.0884267 -0.001999974 0.003282666 -0.0890755 -0.001035571 0.003282666 -0.0890755 -0.001999974 0.00263381 -0.08950906 -0.001347482 0.00263381 -0.08950906 -0.001999974 0.001868486 -0.0896613 -0.001457035 0.001868486 -0.0896613 -0.001999974 0.001103103 -0.08950906 -0.001999974 0.001868486 -0.0896613 0.001999974 0.001103103 -0.08950906 0.001999974 4.54273e-4 -0.0890755 0.001999974 4.54273e-4 -0.0890755 -0.001999974 2.07275e-5 -0.0884267 0.001999974 2.07275e-5 -0.0884267 -0.001999974 -1.31514e-4 -0.08766132 0.001999974 -1.31514e-4 -0.08766132 -0.001999974 2.07275e-5 -0.08689594 0.001999974 2.07275e-5 -0.08689594 -0.001999974 4.54273e-4 -0.08624708 0.001999974 4.54273e-4 -0.08624708 -0.001999974 0.003282666 -0.08624708 0.001999974 0.00263381 -0.08581358 0.001999974 0.001868486 -0.08566129 0.001999974 0.001103103 -0.08581358 0.001999974 0.00263381 -0.08950906 0.001999974 0.003282666 -0.0890755 0.001999974 0.00371623 -0.0884267 0.001999974 0.00386846 -0.08766132 0.001999974 0.00371623 -0.08689594 0.001999974 0.001103103 -0.08581358 -0.001999974 0.001103103 -0.08581358 -0.001347482 0.001868486 -0.08566129 -0.001457035 -0.01466679 -0.08332723 -9.65724e-4 -0.0194714 -0.08372163 -4.56432e-4 2.07275e-5 -0.0884267 5.32729e-4 -1.31514e-4 -0.08766132 -1.79885e-5 -0.02158695 -0.0871824 0.001098155 -0.02132731 -0.08841228 0.001266658 4.54273e-4 -0.0890755 9.99604e-4 -0.02053278 -0.08982741 0.001186668 0.001103103 -0.08950906 0.00131154 -0.01835417 -0.09147131 0.001138865 2.07275e-5 -0.08689594 -5.68705e-4 -0.02154213 -0.08554679 5.80571e-4 0.001868486 -0.0896613 0.001421093 -0.01262134 -0.09187865 0.001118838 4.54273e-4 -0.08624708 -0.001035571 -0.02128046 -0.08447396 1.38679e-4 0.001868486 -0.08766132 0 0.00263381 -0.08950906 -0.001347482 0.001868486 -0.0896613 -0.001457035 0.01840376 -0.09199541 -9.65724e-4 0.02320837 -0.09160101 -4.56432e-4 0.00371623 -0.08689594 5.32729e-4 0.00386846 -0.08766132 -1.79885e-5 0.02532392 -0.08814024 0.001098155 0.02506428 -0.0869103 0.001266658 0.003282666 -0.08624708 9.99604e-4 0.02426975 -0.08549523 0.001186668 0.00263381 -0.08581358 0.00131154 0.02209115 -0.08385127 0.001138865 0.00371623 -0.0884267 -5.68705e-4 0.0252791 -0.0897758 5.80571e-4 0.01635831 -0.08344399 0.001118838 0.003282666 -0.0890755 -0.001035571 0.02501744 -0.09084868 1.38679e-4 0.001064896 -0.08599168 -0.001813113 -0.01951438 -0.08395886 -8.94434e-4 -0.01470351 -0.08348762 -0.001437842 0.001831769 -0.08582168 -0.001929223 6.26221e-6 -0.08855569 4.98801e-5 -0.02134466 -0.08855772 7.88594e-4 -0.02161473 -0.08737045 6.35759e-4 -1.58966e-4 -0.08784854 -4.80802e-4 4.54016e-4 -0.08914595 5.04594e-4 -0.02053856 -0.08991491 6.94454e-4 0.001109361 -0.08952111 8.11758e-4 -0.01835024 -0.09152549 6.41829e-4 -0.02157819 -0.08575659 1.28149e-4 -1.6138e-5 -0.08710801 -0.001019954 0.0018754 -0.08966082 9.21166e-4 -0.01261442 -0.09187811 6.18956e-4 4.11976e-4 -0.0864827 -0.001474499 -0.02132117 -0.08469927 -3.05808e-4 0.001868486 -0.08766132 -5e-4 0.002672016 -0.08933097 -0.001813113 0.02325135 -0.09136372 -8.94434e-4 0.01844048 -0.09183502 -0.001437842 0.001905143 -0.08950096 -0.001929223 0.003730654 -0.08676695 4.98801e-5 0.02508163 -0.08676493 7.88594e-4 0.0253517 -0.08795219 6.35759e-4 0.003895938 -0.0874741 -4.80802e-4 0.003282904 -0.08617669 5.04594e-4 0.02427554 -0.08540773 6.94454e-4 0.002627611 -0.08580148 8.11758e-4 0.02208721 -0.08379715 6.41829e-4 0.02531516 -0.08956605 1.28149e-4 0.003753066 -0.08821463 -0.001019954 0.001861512 -0.08566182 9.21166e-4 0.0163514 -0.08344447 6.18956e-4 0.003324985 -0.08883988 -0.001474499 0.02505815 -0.09062337 -3.05808e-4 0.002672016 -0.08933097 -0.001813113 0.001905143 -0.08950096 -0.001929223 0.02505815 -0.09062337 -3.05808e-4</float_array>\n          <technique_common>\n            <accessor source=\"#cw_prop-mesh-positions-array\" count=\"468\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <source id=\"cw_prop-mesh-normals\">\n          <float_array id=\"cw_prop-mesh-normals-array\" count=\"1362\">0 -0.7462026 -0.665719 0.08095937 -0.9950895 0.05694371 -0.3826833 -0.9238796 0 -0.2855594 -0.6894015 -0.6657189 -0.6894015 -0.2855596 -0.6657187 -1 -2.17625e-7 0 -0.7462024 -1.22696e-7 -0.6657192 -0.9238796 0.3826835 0 -0.6894016 0.2855592 -0.6657187 -0.2855595 0.6894013 -0.6657189 -0.3826836 0.9238795 0 0 1 0 0 0.7462027 -0.6657189 0 0.7462028 0.6657188 0.2855593 0.6894014 0.6657189 0.7462024 2.09306e-7 -0.6657193 0.7462027 0 0.6657188 0.6894013 -0.2855595 0.6657189 0 -0.7462027 0.6657189 0.2855592 -0.6894014 0.665719 0.5276449 -0.5276449 0.665719 0.689402 0.2855592 0.6657183 0.5276449 0.5276451 0.665719 -0.5276449 -0.5276451 0.665719 -0.5276449 0.5276448 0.6657191 -0.7462028 0 0.6657188 -0.5276454 -0.5276448 -0.6657187 0.2855593 0.6894015 -0.6657189 0.6894013 0.2855597 -0.6657189 0.6894015 -0.2855592 -0.6657189 0.2855596 -0.6894013 -0.6657189 -0.7071067 -0.707107 0 -0.2855594 -0.6894015 0.6657189 -0.707107 0.7071067 0 -0.6894018 0.2855592 0.6657186 -0.9238794 -0.3826838 0 -0.6894017 -0.2855594 0.6657186 -0.2855592 0.6894014 0.665719 -0.3748962 -0.7816502 0.4984736 0.6311947 0.1767534 0.7552164 0.5248991 0.4826806 0.7010709 -0.1582986 -0.7873222 0.5958736 0.2573913 0.6935871 0.67282 -0.7081931 -0.4253229 0.5635272 -0.7082605 -0.1986545 0.6774241 0.6699832 -0.3351253 0.6624301 -0.817855 0.0142318 0.5752485 -0.02832227 0.7650859 0.6433052 -0.5823978 0.01877319 0.8126872 -0.357304 0.2884959 0.8883153 0.1679158 -0.9497295 0.2642319 0.5648971 -0.7122579 0.4166294 0.41309 -0.5338768 0.7377888 0.9653253 0.1375148 0.2218936 0.07708626 0.9719986 0.2219831 -0.1679159 0.9497294 0.2642319 0.5878704 0.6405184 0.49411 0.7081931 0.4253231 0.5635272 -0.6717817 0.1170585 0.7314416 -0.6311947 -0.1767534 0.7552163 0.374896 0.7816503 0.4984737 0.7082605 0.1986545 0.6774241 -0.8025102 0.3241897 0.500878 0.1582985 0.7873218 0.5958741 -0.2573911 -0.6935855 0.6728217 0.5823978 -0.01877266 0.8126872 -0.7079404 0.6868429 0.1645214 -0.227101 0.8081443 -0.5434408 0.04681378 -0.4709634 -0.8809098 -0.7987827 0.1411343 -0.584831 -0.6431276 0.2793524 -0.7129861 0.7421983 0.3454436 -0.5742912 0.783652 0.2218073 -0.580251 -0.6109308 0.4729923 -0.6348559 -0.6039934 0.01654142 -0.7968177 0.5849545 0.5077975 -0.6324319 -0.384606 -0.37048 -0.845472 0.2669962 0.7314997 -0.6273924 0.772009 0.1294873 -0.6222823 -0.863177 0.02027082 -0.5044946 -0.03747242 0.6877762 -0.7249551 -0.4273026 0.7637783 -0.4837924 0.2818456 -0.3080278 -0.9086704 0.2271012 -0.8081442 -0.5434409 -0.2334834 0.02328401 -0.972082 -0.02981293 0.340254 -0.9398608 0.7987845 -0.1411336 -0.5848289 0.6431276 -0.2793523 -0.7129862 -0.7421985 -0.3454434 -0.5742911 -0.7836518 -0.2218074 -0.5802511 0.6039935 -0.0165416 -0.7968176 -0.5849545 -0.5077975 -0.6324318 0.2584314 -0.7192381 -0.6449108 -0.667337 0.2068901 -0.7154424 0.3683512 -0.6397519 -0.6745628 -0.7687523 -0.1133454 -0.6294226 -0.8743168 -0.2032756 0.4407372 0.6717818 -0.1170586 0.7314414 -0.05454945 -0.9115495 0.4075561 0.3846062 0.3704797 -0.845472 0.6109308 -0.472992 -0.6348561 -0.5248991 -0.482681 0.7010706 0.02832239 -0.7650857 0.6433054 -0.2669953 -0.7314993 -0.6273933 0.03747254 -0.6877762 -0.724955 -0.5276448 0.527645 -0.665719 0.5276448 0.5276451 -0.6657189 0.5276453 -0.5276447 -0.6657188 -0.5878705 -0.6405183 0.4941098 -0.5396548 0.6347205 -0.5530848 0.6673443 -0.2068942 -0.7154344 0.2271012 -0.8081443 -0.5434408 0.7987844 -0.1411337 -0.584829 0.863176 -0.02027118 -0.5044961 -0.6673444 0.206894 -0.7154344 0.7455248 0.03179866 -0.6657189 0.906734 0.4217031 0 0.9976353 -0.03848809 0.05694246 0.676608 0.3146756 -0.6657184 0.2559248 0.7009432 -0.6657185 -0.0317952 0.7455247 -0.6657192 -0.04261016 0.9990919 0 -0.3146753 0.6766077 -0.6657188 -0.4217045 0.9067333 0 -0.7009429 0.2559249 -0.6657187 -0.9990918 -0.04261201 0 -0.9393478 0.3429663 0 -0.745525 -0.03179585 -0.6657188 -0.6766076 -0.3146756 0.6657188 -0.7455248 -0.03179281 0.6657193 0.03179609 -0.7455247 -0.6657192 0.3146747 -0.676608 0.6657187 0.0317955 -0.7455248 0.6657191 0.745525 0.03179413 0.665719 0.5496467 -0.5046846 0.6657192 0.7009418 -0.2559272 0.665719 -0.5046818 -0.5496491 0.6657193 -0.2559243 -0.7009434 0.6657186 0.504682 0.5496488 0.6657193 -0.5496481 0.5046825 0.6657196 -0.03179591 0.7455247 0.6657192 0.5046839 0.549647 -0.6657195 -0.6766074 -0.3146761 -0.6657187 -0.2559258 -0.7009428 -0.6657187 0.314677 -0.6766068 -0.6657189 0.700944 -0.2559227 -0.6657186 0.6763354 0.7365938 0 0.6766076 0.3146761 0.6657186 -0.7365952 0.6763339 0 -0.314675 0.676608 0.6657186 0.3429685 0.9393469 0 0.2559235 0.7009438 0.6657184 -0.7009431 0.2559249 0.6657186 0.7649651 0.4078625 0.4984744 -0.459876 -0.5449901 0.7010705 -0.1496988 -0.6381551 0.7552141 0.7798629 0.1917027 0.5958725 -0.681987 -0.2867105 0.6728231 0.3947595 0.7256764 0.5635235 0.3633663 -0.6550991 0.6624275 0.1682943 0.716083 0.6774232 -0.04906916 0.8165074 0.5752459 -0.765596 -0.004304528 0.6433073 -0.04357326 0.5810694 0.8126868 0.9560213 -0.1272945 0.2642339 -0.3034556 0.344686 0.8883165 0.7356837 -0.5340338 0.4166263 0.5509896 -0.3899658 0.7377922 -0.9678309 -0.1184346 0.2219837 -0.09625303 -0.9703084 0.2218946 -0.9560213 0.1273009 0.2642307 -0.6148878 -0.6146292 0.4941093 -0.1455783 0.6661823 0.7314425 -0.3947584 -0.725676 0.5635249 0.1496996 0.6381526 0.7552161 -0.7649654 -0.407863 0.4984735 -0.3580898 0.7879662 0.5008803 -0.1682934 -0.7160825 0.6774241 0.6819889 0.2867107 0.6728211 -0.7798627 -0.1917032 0.5958728 -0.716387 0.678029 0.1645187 0.0435726 -0.5810685 0.8126874 -0.8170879 0.1924597 -0.5434396 -0.175049 0.792034 -0.5848421 0.4725317 -0.02670288 -0.8809091 -0.3065029 0.630638 -0.712988 -0.1882129 -0.7923859 -0.5802591 -0.3135039 -0.7562432 -0.5742923 -0.4985941 0.5902202 -0.6348577 -0.04226207 0.602741 -0.796817 -0.482411 -0.60606 -0.6324326 0.3537545 0.4000416 -0.8454729 -0.7194592 -0.2979241 -0.6273913 -0.09648007 -0.7768225 -0.6222849 -0.05703401 0.8615258 -0.5045002 -0.6887509 0.008130908 -0.7249525 -0.7812932 0.39437 -0.4837904 0.3197576 -0.2684645 -0.9086704 0.8170879 -0.1924601 -0.5434395 -0.3412169 0.01528608 -0.9398603 -0.03320986 0.2322808 -0.9720817 0.1750516 -0.7920293 -0.5848476 0.3065037 -0.6306387 -0.712987 0.1882125 0.7923927 -0.58025 0.3135063 0.7562432 -0.5742909 0.04226112 -0.6027407 -0.7968172 0.4824105 0.6060616 -0.6324313 0.7295984 -0.22755 -0.6449087 -0.235139 0.657912 -0.715445 0.6548674 -0.3407562 -0.6745621 0.08048552 0.7728857 -0.6294202 0.1658352 0.8821812 0.4407438 0.1455777 -0.6661909 0.7314348 0.9083966 0.09334158 0.4075574 -0.3537541 -0.4000416 -0.8454732 0.4985966 -0.5902203 -0.6348556 0.4598743 0.5449897 0.701072 0.7655984 0.004303276 0.6433045 0.6887478 -0.008132696 -0.7249554 0.7194588 0.2979215 -0.6273929 -0.5496482 0.5046826 -0.6657195 -0.504683 -0.5496483 -0.6657191 0.5496493 -0.5046815 -0.6657193 0.6148877 0.6146301 0.4941083 -0.6571398 0.512119 -0.5530837 0.2351419 -0.657922 -0.7154348 0.05703675 -0.8615267 -0.5044986 -0.2351435 0.657919 -0.715437 -0.7455248 -0.03179848 -0.6657189 -0.906734 -0.4217032 0 -0.9976354 0.03848469 0.05694341 -0.6766065 -0.3146781 -0.6657187 -0.2559248 -0.7009432 -0.6657185 0.03179579 -0.7455246 -0.6657192 0.04261058 -0.9990918 0 0.3146759 -0.6766076 -0.6657187 0.4217039 -0.9067336 0 0.7009436 -0.255924 -0.6657184 0.9990918 0.04261124 0 0.9393488 -0.3429638 0 0.7455245 0.03179579 -0.6657194 0.6766064 0.3146775 0.6657192 0.7455248 0.03179281 0.6657193 -0.03179615 0.7455246 -0.6657192 -0.3146754 0.6766078 0.6657186 -0.03179633 0.7455247 0.6657192 -0.7455248 -0.03179454 0.665719 -0.5496484 0.5046824 0.6657195 -0.7009429 0.2559248 0.6657188 0.5046803 0.5496507 0.6657191 0.2559241 0.7009434 0.6657186 -0.5046829 -0.5496482 0.6657192 0.5496463 -0.5046849 0.6657193 0.03179556 -0.7455247 0.6657191 -0.5046815 -0.5496497 -0.6657191 0.6766088 0.3146734 -0.6657186 0.2559241 0.7009435 -0.6657185 -0.3146755 0.6766077 -0.6657187 -0.700944 0.2559227 -0.6657186 -0.6763349 -0.7365944 0 -0.6766079 -0.3146745 0.6657189 0.7365942 -0.676335 0 0.3146744 -0.6766083 0.6657186 -0.3429695 -0.9393466 0 -0.2559258 -0.7009428 0.6657187 0.7009417 -0.2559276 0.665719 -0.764965 -0.4078633 0.4984737 0.4598755 0.5449894 0.7010715 0.1496992 0.6381525 0.7552164 -0.7798621 -0.1917039 0.5958732 0.681988 0.2867115 0.6728216 -0.3947595 -0.7256749 0.5635256 -0.3633685 0.6550941 0.6624312 -0.1682949 -0.7160849 0.677421 0.04906517 -0.8165042 0.5752508 0.765596 0.00430423 0.6433073 0.04357218 -0.5810691 0.812687 -0.9560216 0.127295 0.2642325 0.3034564 -0.3446887 0.8883152 -0.7356817 0.5340346 0.4166288 -0.5509892 0.3899695 0.7377905 0.9678309 0.1184343 0.2219837 0.0962544 0.9703086 0.2218928 0.9560208 -0.1272993 0.2642333 0.6148896 0.6146296 0.4941064 0.1455783 -0.6661955 0.7314305 0.3947587 0.7256748 0.563526 -0.1496989 -0.6381545 0.7552147 0.7649644 0.4078623 0.4984756 0.3580877 -0.7879719 0.5008729 0.1682946 0.7160839 0.6774223 -0.6819881 -0.2867103 0.6728221 0.7798626 0.191703 0.5958727 0.7163875 -0.6780288 0.1645177 -0.04357349 0.5810688 0.8126873 0.8170869 -0.1924606 -0.543441 0.1750447 -0.7920413 -0.5848334 -0.472532 0.02670228 -0.8809089 0.3065026 -0.6306371 -0.7129888 0.1882129 0.7923938 -0.5802484 0.3135059 0.7562437 -0.5742905 0.4985944 -0.5902203 -0.6348572 0.04226189 -0.6027392 -0.7968183 0.4824109 0.6060609 -0.6324318 -0.3537521 -0.4000453 -0.8454722 0.7194578 0.2979224 -0.6273937 0.09647488 0.7768262 -0.6222811 0.05703181 -0.8615217 -0.5045075 0.6887508 -0.008131206 -0.7249526 0.7812935 -0.3943697 -0.4837903 -0.3197572 0.2684646 -0.9086706 -0.8170876 0.1924616 -0.5434395 0.3412169 -0.01528638 -0.9398604 0.03321045 -0.2322807 -0.9720817 -0.1750495 0.792033 -0.5848432 -0.3065018 0.6306356 -0.7129905 -0.1882119 -0.7923818 -0.5802651 -0.313505 -0.7562438 -0.574291 -0.04226082 0.6027417 -0.7968164 -0.4824106 -0.6060609 -0.632432 -0.7295985 0.22755 -0.6449086 0.2351387 -0.6579131 -0.7154441 -0.6548658 0.3407555 -0.674564 -0.08048909 -0.7728805 -0.6294261 -0.1658367 -0.8821825 0.4407408 -0.145578 0.6661812 0.7314436 -0.9083964 -0.09334224 0.4075578 0.3537537 0.4000431 -0.8454726 -0.4985963 0.5902209 -0.6348551 -0.4598749 -0.5449903 0.7010712 -0.7655987 -0.004303872 0.6433042 -0.688747 0.008132338 -0.7249562 -0.7194598 -0.2979237 -0.6273908 0.5496483 -0.5046825 -0.6657195 0.5046837 0.5496472 -0.6657195 -0.549648 0.5046826 -0.6657196 -0.6148885 -0.6146296 0.4941079 0.657138 -0.5121173 -0.5530872 -0.2351421 0.657922 -0.7154347 -0.05703562 0.8615291 -0.5044946 0.2351422 -0.6579188 -0.7154377 -3.10351e-7 0.7462036 -0.6657178 -0.08096092 0.9950889 0.05695182 0.3826845 0.9238792 0 0.2855598 0.6894004 -0.6657196 0.6894008 0.2855597 -0.6657193 1 1.54151e-6 0 0.7462028 1.52108e-6 -0.6657188 0.923879 -0.3826848 0 0.6894016 -0.2855603 -0.6657183 0.28556 -0.6894021 -0.6657179 0.3826839 -0.9238794 0 0 -1 0 0 -0.7462019 -0.6657198 0 -0.7462019 0.6657198 -0.2855598 -0.6894021 0.665718 -0.7462027 0 -0.6657189 -0.7462028 0 0.6657187 -0.6894011 0.2855591 0.6657193 -3.60873e-7 0.7462036 0.665718 -0.2855589 0.6894004 0.6657202 -0.5276443 0.5276465 0.6657183 -0.689401 -0.285561 0.6657186 -0.5276447 -0.527644 0.6657199 0.5276448 0.5276455 0.6657186 0.5276448 -0.5276439 0.6657199 0.7462028 1.56618e-6 0.6657188 0.5276442 0.5276459 -0.6657187 -0.2855599 -0.6894021 -0.665718 -0.6894011 -0.285561 -0.6657185 -0.6894015 0.285559 -0.665719 -0.2855592 0.6894005 -0.6657199 0.7071064 0.7071072 0 0.2855596 0.6894004 0.6657198 0.7071072 -0.7071065 0 0.6894012 -0.2855603 0.6657187 0.9238795 0.3826836 0 0.689401 0.2855598 0.6657192 0.2855601 -0.689402 0.665718 0.3748966 0.781649 0.498475 -0.6311954 -0.1767513 0.7552161 -0.5248981 -0.4826796 0.7010725 0.1582983 0.7873291 0.5958645 -0.2573927 -0.6935856 0.672821 0.7081932 0.4253179 0.5635309 0.7082578 0.1986523 0.6774277 -0.6699869 0.3351221 0.662428 0.8179191 -0.01422673 0.5751573 0.0283221 -0.7650799 0.6433123 0.582392 -0.01877611 0.8126913 0.3573055 -0.288505 0.8883117 -0.167915 0.9497284 0.2642359 -0.5648927 0.7122582 0.4166351 -0.4130837 0.5338729 0.7377951 -0.9653531 -0.1374804 0.2217944 -0.07708686 -0.9719977 0.2219867 0.167918 -0.9497307 0.2642259 -0.5878692 -0.6405211 0.4941079 -0.7081959 -0.4253249 0.5635223 0.6717795 -0.1170623 0.7314429 0.6311936 0.1767559 0.7552165 -0.3748962 -0.7816454 0.498481 -0.7082607 -0.1986582 0.6774228 0.8025099 -0.3241881 0.5008794 -0.1583018 -0.7873246 0.5958697 0.2573919 0.6935891 0.6728177 -0.5823986 0.01877582 0.8126866 0.7079401 -0.6868436 0.1645199 0.2270929 -0.8081509 -0.5434345 -0.04681378 0.4709674 -0.8809076 0.7987381 -0.1411775 -0.5848817 0.6431273 -0.2793527 -0.7129862 -0.742201 -0.3454418 -0.5742889 -0.7836484 -0.2218055 -0.5802565 0.6109306 -0.4729927 -0.6348558 0.6039939 -0.01653212 -0.7968176 -0.5849552 -0.5077995 -0.6324295 0.3846091 0.3704743 -0.8454731 -0.2669942 -0.7315006 -0.6273923 -0.7720052 -0.1294935 -0.6222857 0.8631245 -0.02027738 -0.5045839 0.03747326 -0.6877831 -0.7249485 0.4273028 -0.7637795 -0.4837906 -0.2818462 0.308034 -0.9086682 -0.2271057 0.8081416 -0.543443 0.2334829 -0.02328026 -0.9720821 0.02981233 -0.340258 -0.9398595 -0.7987309 0.1411525 -0.5848974 -0.6431262 0.2793472 -0.7129895 0.7421988 0.3454467 -0.5742887 0.7836537 0.2218036 -0.5802502 -0.6039999 0.01653999 -0.7968128 0.5849588 0.5078008 -0.6324253 -0.2584329 0.7192396 -0.6449084 0.667337 -0.2068899 -0.7154424 -0.3683511 0.6397474 -0.6745671 0.7687532 0.1133442 -0.6294216 0.8743509 0.2032626 0.4406754 -0.6717849 0.1170606 0.7314382 0.05455005 0.9115486 0.4075579 -0.3845989 -0.3704783 -0.8454759 -0.6109272 0.4729974 -0.6348554 0.5248938 0.4826764 0.7010778 -0.02832227 0.7650817 0.6433103 0.2669939 0.7314968 -0.6273969 -0.03747266 0.6877813 -0.7249501 0.5276443 -0.5276443 -0.6657201 -0.5276443 -0.5276442 -0.6657201 -0.5276439 0.5276466 -0.6657185 0.5878688 0.64052 0.4941098 0.5396559 -0.6347213 -0.5530827 -0.6673502 0.2068974 -0.715428 -0.8631843 0.02027374 -0.5044817 0.667343 -0.206893 -0.715436</float_array>\n          <technique_common>\n            <accessor source=\"#cw_prop-mesh-normals-array\" count=\"454\" stride=\"3\">\n              <param name=\"X\" type=\"float\"/>\n              <param name=\"Y\" type=\"float\"/>\n              <param name=\"Z\" type=\"float\"/>\n            </accessor>\n          </technique_common>\n        </source>\n        <vertices id=\"cw_prop-mesh-vertices\">\n          <input semantic=\"POSITION\" source=\"#cw_prop-mesh-positions\"/>\n        </vertices>\n        <triangles material=\"pcb-material\" count=\"912\">\n          <input semantic=\"VERTEX\" source=\"#cw_prop-mesh-vertices\" offset=\"0\"/>\n          <input semantic=\"NORMAL\" source=\"#cw_prop-mesh-normals\" offset=\"1\"/>\n          <p>0 0 1 1 2 2 0 0 2 2 3 3 7 4 8 5 9 6 9 6 10 7 11 8 15 9 14 10 16 11 15 9 16 11 17 12 16 11 19 13 20 14 26 15 25 16 27 17 33 18 34 19 29 20 29 20 27 17 25 16 25 16 23 21 21 22 21 22 20 14 19 13 31 23 33 18 29 20 21 22 19 13 36 24 36 24 38 25 31 23 21 22 36 24 31 23 34 19 1 1 0 0 3 3 5 26 7 4 15 9 17 12 18 27 24 28 26 15 28 29 40 30 3 3 7 4 15 9 18 27 24 28 4 31 2 2 32 32 12 33 10 7 37 34 12 33 37 34 36 24 6 35 4 31 31 23 6 35 31 23 39 36 8 5 39 36 38 25 2 2 1 1 33 18 2 2 33 18 32 32 16 11 14 10 35 37 10 7 8 5 38 25 49 38 48 39 50 40 51 41 49 38 50 40 51 41 50 40 52 42 46 43 53 44 54 45 55 46 52 42 56 47 57 48 41 49 44 50 57 48 44 50 58 51 53 44 57 48 58 51 53 44 58 51 54 45 60 52 61 53 62 54 60 52 62 54 63 55 64 56 65 57 66 58 64 56 66 58 67 59 68 60 64 56 67 59 65 57 72 61 73 62 1 1 70 63 71 64 72 61 75 65 76 66 77 67 79 68 80 69 81 70 82 71 83 72 81 70 83 72 84 73 85 74 86 75 82 71 85 74 82 71 81 70 87 76 88 77 86 75 84 73 83 72 89 78 91 79 92 80 88 77 93 81 78 82 77 67 96 83 97 84 98 85 96 83 98 85 99 86 100 87 101 88 102 89 104 90 105 91 101 88 104 90 101 88 100 87 112 92 113 93 97 84 112 92 97 84 96 83 109 94 108 95 113 93 109 94 113 93 112 92 41 49 93 81 77 67 51 41 55 46 91 79 51 41 91 79 87 76 42 96 77 67 80 69 53 44 46 43 84 73 52 42 50 40 86 75 52 42 86 75 88 77 50 40 48 39 82 71 50 40 82 71 86 75 48 39 47 97 83 72 44 50 43 98 79 68 47 97 54 45 89 78 47 97 89 78 83 72 43 98 42 96 80 69 55 46 92 80 91 79 68 60 70 63 106 99 64 56 68 60 104 90 60 52 112 92 96 83 65 57 100 87 103 100 61 53 60 52 96 83 61 53 96 83 99 86 72 61 65 57 103 100 72 61 103 100 109 94 73 62 76 66 113 93 73 62 113 93 108 95 69 101 67 59 101 88 76 66 97 84 113 93 74 102 107 103 111 104 63 55 62 54 98 85 66 58 108 95 102 89 62 54 61 53 99 86 62 54 99 86 98 85 3 3 2 2 4 31 3 3 4 31 5 26 5 26 4 31 6 35 5 26 6 35 7 4 7 4 6 35 8 5 9 6 8 5 10 7 11 8 10 7 12 33 11 8 12 33 13 105 13 105 12 33 14 10 13 105 14 10 15 9 18 27 17 12 16 11 16 11 20 14 18 27 18 27 20 14 21 22 18 27 21 22 22 106 22 106 21 22 23 21 22 106 23 21 24 28 24 28 23 21 25 16 24 28 25 16 26 15 26 15 27 17 28 29 28 29 27 17 29 20 28 29 29 20 30 107 31 23 32 32 33 18 19 13 35 37 36 24 36 24 37 34 38 25 38 25 39 36 31 23 29 20 25 16 21 22 31 23 29 20 21 22 30 107 29 20 34 19 30 107 34 19 40 30 0 0 40 30 34 19 34 19 33 18 1 1 40 30 0 0 3 3 7 4 9 6 11 8 11 8 13 105 15 9 18 27 22 106 24 28 28 29 30 107 40 30 7 4 11 8 15 9 24 28 28 29 40 30 40 30 7 4 15 9 15 9 24 28 40 30 4 31 32 32 31 23 14 10 12 33 36 24 14 10 36 24 35 37 8 5 6 35 39 36 16 11 35 37 19 13 10 7 38 25 37 34 41 49 42 96 43 98 41 49 43 98 44 50 45 108 46 43 47 97 45 108 47 97 48 39 49 38 45 108 48 39 46 43 54 45 47 97 55 46 51 41 52 42 77 67 78 82 79 68 87 76 86 75 85 74 84 73 89 78 90 109 91 79 88 77 87 76 93 81 94 110 78 82 90 109 89 78 94 110 90 109 94 110 93 81 49 38 51 41 87 76 49 38 87 76 85 74 57 48 53 44 90 109 57 48 90 109 93 81 45 108 49 38 85 74 45 108 85 74 81 70 41 49 57 48 93 81 46 43 45 108 81 70 46 43 81 70 84 73 42 96 41 49 77 67 53 44 84 73 90 109 54 45 58 51 94 110 54 45 94 110 89 78 58 51 44 50 78 82 58 51 78 82 94 110 48 39 83 72 82 71 56 47 52 42 88 77 56 47 88 77 92 80 44 50 79 68 78 82 43 98 80 69 79 68 55 46 56 47 92 80 68 60 67 59 69 101 70 63 68 60 69 101 70 63 69 101 71 64 65 57 73 62 66 58 1 1 71 64 74 102 75 65 60 52 63 55 75 65 63 55 76 66 72 61 76 66 73 62 114 111 97 84 98 85 114 111 98 85 115 112 100 87 102 89 103 100 106 99 107 103 105 91 106 99 105 91 104 90 103 100 102 89 108 95 103 100 108 95 109 94 110 113 111 104 107 103 110 113 107 103 106 99 112 92 116 114 97 84 112 92 97 84 114 111 109 94 108 95 116 114 109 94 116 114 112 92 68 60 106 99 104 90 75 65 72 61 109 94 75 65 109 94 112 92 64 56 104 90 100 87 60 52 75 65 112 92 60 52 112 92 114 111 65 57 64 56 100 87 70 63 1 1 110 113 70 63 110 113 106 99 61 53 60 52 114 111 61 53 114 111 115 112 71 64 69 101 105 91 71 64 105 91 107 103 73 62 76 66 116 114 73 62 116 114 108 95 69 101 101 88 105 91 76 66 63 55 97 84 76 66 97 84 116 114 67 59 66 58 102 89 67 59 102 89 101 88 74 102 71 64 107 103 63 55 98 85 97 84 66 58 73 62 108 95 62 54 61 53 115 112 62 54 115 112 98 85 1 1 74 102 111 104 1 1 111 104 110 113 117 115 119 116 118 117 117 115 120 118 119 116 124 119 126 120 125 121 126 120 128 122 127 123 132 124 133 125 131 126 132 124 134 127 133 125 133 125 137 128 136 129 143 130 144 131 142 132 150 133 146 134 151 135 146 134 142 132 144 131 142 132 138 136 140 137 138 136 136 129 137 128 148 138 146 134 150 133 138 136 153 139 136 129 153 139 148 138 155 140 138 136 148 138 153 139 151 135 117 115 118 117 120 118 124 119 122 141 132 124 135 142 134 127 141 143 145 144 143 130 157 145 124 119 120 118 132 124 141 143 135 142 121 146 149 147 119 116 129 148 154 149 127 123 129 148 153 139 154 149 123 150 148 138 121 146 123 150 156 151 148 138 125 121 155 140 156 151 119 116 150 133 118 117 119 116 149 147 150 133 133 125 152 152 131 126 127 123 155 140 125 121 166 153 167 154 165 155 168 156 167 154 166 153 168 156 169 157 167 154 163 158 171 159 170 160 172 161 173 162 169 157 174 163 161 164 158 165 174 163 175 166 161 164 170 160 175 166 174 163 170 160 171 159 175 166 177 167 179 168 178 169 177 167 180 170 179 168 181 171 183 172 182 173 181 171 184 174 183 172 185 175 184 174 181 171 182 173 190 176 189 177 118 117 188 178 187 179 189 177 193 180 192 181 194 182 197 183 196 184 198 185 200 186 199 187 198 185 201 188 200 186 202 189 199 187 203 190 202 189 198 185 199 187 204 191 203 190 205 192 201 188 206 193 200 186 208 194 205 192 209 195 210 196 194 182 195 197 213 198 215 199 214 200 213 198 216 201 215 199 217 202 219 203 218 204 221 205 218 204 222 206 221 205 217 202 218 204 229 207 214 200 230 208 229 207 213 198 214 200 226 209 230 208 225 210 226 209 229 207 230 208 158 165 194 182 210 196 168 156 208 194 172 161 168 156 204 191 208 194 159 211 197 183 194 182 170 160 201 188 163 158 169 157 203 190 167 154 169 157 205 192 203 190 167 154 199 187 165 155 167 154 203 190 199 187 165 155 200 186 164 212 161 164 196 184 160 213 164 212 206 193 171 159 164 212 200 186 206 193 160 213 197 183 159 211 172 161 208 194 209 195 185 175 223 214 187 179 181 171 221 205 185 175 177 167 213 198 229 207 182 173 220 215 217 202 178 169 213 198 177 167 178 169 216 201 213 198 189 177 220 215 182 173 189 177 226 209 220 215 190 176 230 208 193 180 190 176 225 210 230 208 186 216 218 204 184 174 193 180 230 208 214 200 191 217 228 218 224 219 180 170 215 199 179 168 183 172 219 203 225 210 179 168 216 201 178 169 179 168 215 199 216 201 120 118 121 146 119 116 120 118 122 141 121 146 122 141 123 150 121 146 122 141 124 119 123 150 124 119 125 121 123 150 126 120 127 123 125 121 128 122 129 148 127 123 128 122 130 220 129 148 130 220 131 126 129 148 130 220 132 124 131 126 135 142 133 125 134 127 133 125 135 142 137 128 135 142 138 136 137 128 135 142 139 221 138 136 139 221 140 137 138 136 139 221 141 143 140 137 141 143 142 132 140 137 141 143 143 130 142 132 143 130 145 144 144 131 145 144 146 134 144 131 145 144 147 222 146 134 148 138 150 133 149 147 136 129 153 139 152 152 153 139 155 140 154 149 155 140 148 138 156 151 146 134 138 136 142 132 148 138 138 136 146 134 147 222 151 135 146 134 147 222 157 145 151 135 117 115 151 135 157 145 151 135 118 117 150 133 157 145 120 118 117 115 124 119 128 122 126 120 128 122 132 124 130 220 135 142 141 143 139 221 145 144 157 145 147 222 124 119 132 124 128 122 141 143 157 145 145 144 157 145 132 124 124 119 132 124 157 145 141 143 121 146 148 138 149 147 131 126 153 139 129 148 131 126 152 152 153 139 125 121 156 151 123 150 133 125 136 129 152 152 127 123 154 149 155 140 158 165 160 213 159 211 158 165 161 164 160 213 162 223 164 212 163 158 162 223 165 155 164 212 166 153 165 155 162 223 163 158 164 212 171 159 172 161 169 157 168 156 194 182 196 184 195 197 204 191 202 189 203 190 201 188 207 224 206 193 208 194 204 191 205 192 210 196 195 197 211 225 207 224 211 225 206 193 207 224 210 196 211 225 166 153 204 191 168 156 166 153 202 189 204 191 174 163 207 224 170 160 174 163 210 196 207 224 162 223 202 189 166 153 162 223 198 185 202 189 158 165 210 196 174 163 163 158 198 185 162 223 163 158 201 188 198 185 159 211 194 182 158 165 170 160 207 224 201 188 171 159 211 225 175 166 171 159 206 193 211 225 175 166 195 197 161 164 175 166 211 225 195 197 165 155 199 187 200 186 173 162 205 192 169 157 173 162 209 195 205 192 161 164 195 197 196 184 160 213 196 184 197 183 172 161 209 195 173 162 185 175 186 216 184 174 187 179 186 216 185 175 187 179 188 178 186 216 182 173 183 172 190 176 118 117 191 217 188 178 192 181 180 170 177 167 192 181 193 180 180 170 189 177 190 176 193 180 231 198 215 199 214 200 231 198 232 201 215 199 217 202 220 215 219 203 223 214 222 206 224 219 223 214 221 205 222 206 220 215 225 210 219 203 220 215 226 209 225 210 227 226 224 219 228 218 227 226 223 214 224 219 229 207 214 200 233 227 229 207 231 198 214 200 226 209 233 227 225 210 226 209 229 207 233 227 185 175 221 205 223 214 192 181 226 209 189 177 192 181 229 207 226 209 181 171 217 202 221 205 177 167 229 207 192 181 177 167 231 198 229 207 182 173 217 202 181 171 187 179 227 226 118 117 187 179 223 214 227 226 178 169 231 198 177 167 178 169 232 201 231 198 188 178 222 206 186 216 188 178 224 219 222 206 190 176 233 227 193 180 190 176 225 210 233 227 186 216 222 206 218 204 193 180 214 200 180 170 193 180 233 227 214 200 184 174 219 203 183 172 184 174 218 204 219 203 191 217 224 219 188 178 180 170 214 200 215 199 183 172 225 210 190 176 179 168 232 201 178 169 179 168 215 199 232 201 118 117 228 218 191 217 118 117 227 226 228 218 234 228 236 229 235 230 234 228 237 231 236 229 241 232 243 233 242 234 243 233 245 235 244 236 249 237 250 238 248 239 249 237 251 240 250 238 250 238 254 241 253 242 260 243 261 244 259 245 267 246 263 247 268 248 263 247 259 245 261 244 259 245 255 249 257 250 255 249 253 242 254 241 265 251 263 247 267 246 255 249 270 252 253 242 270 252 265 251 272 253 255 249 265 251 270 252 268 248 234 228 235 230 237 231 241 232 239 254 249 237 252 255 251 240 258 256 262 257 260 243 274 258 241 232 237 231 249 237 258 256 252 255 238 259 266 260 236 229 246 261 271 262 244 236 246 261 270 252 271 262 240 263 265 251 238 259 240 263 273 264 265 251 242 234 272 253 273 264 236 229 267 246 235 230 236 229 266 260 267 246 250 238 269 265 248 239 244 236 272 253 242 234 283 266 284 267 282 268 285 269 284 267 283 266 285 269 286 270 284 267 280 271 288 272 287 273 289 274 290 275 286 270 291 276 278 277 275 278 291 276 292 279 278 277 287 273 292 279 291 276 287 273 288 272 292 279 294 280 296 281 295 282 294 280 297 283 296 281 298 284 300 285 299 286 298 284 301 287 300 285 302 288 301 287 298 284 299 286 307 289 306 290 235 230 305 291 304 292 306 290 310 293 309 294 311 295 314 296 313 297 315 298 317 299 316 300 315 298 318 301 317 299 319 302 316 300 320 303 319 302 315 298 316 300 321 304 320 303 322 305 318 301 323 306 317 299 325 307 322 305 326 308 327 309 311 295 312 310 330 311 332 312 331 313 330 311 333 314 332 312 334 315 336 316 335 317 338 318 335 317 339 319 338 318 334 315 335 317 346 320 331 313 347 321 346 320 330 311 331 313 343 322 347 321 342 323 343 322 346 320 347 321 275 278 311 295 327 309 285 269 325 307 289 274 285 269 321 304 325 307 276 324 314 296 311 295 287 273 318 301 280 271 286 270 320 303 284 267 286 270 322 305 320 303 284 267 316 300 282 268 284 267 320 303 316 300 282 268 317 299 281 325 278 277 313 297 277 326 281 325 323 306 288 272 281 325 317 299 323 306 277 326 314 296 276 324 289 274 325 307 326 308 302 288 340 327 304 292 298 284 338 318 302 288 294 280 330 311 346 320 299 286 337 328 334 315 295 282 330 311 294 280 295 282 333 314 330 311 306 290 337 328 299 286 306 290 343 322 337 328 307 289 347 321 310 293 307 289 342 323 347 321 303 329 335 317 301 287 310 293 347 321 331 313 308 330 345 331 341 332 297 283 332 312 296 281 300 285 336 316 342 323 296 281 333 314 295 282 296 281 332 312 333 314 237 231 238 259 236 229 237 231 239 254 238 259 239 254 240 263 238 259 239 254 241 232 240 263 241 232 242 234 240 263 243 233 244 236 242 234 245 235 246 261 244 236 245 235 247 333 246 261 247 333 248 239 246 261 247 333 249 237 248 239 252 255 250 238 251 240 250 238 252 255 254 241 252 255 255 249 254 241 252 255 256 334 255 249 256 334 257 250 255 249 256 334 258 256 257 250 258 256 259 245 257 250 258 256 260 243 259 245 260 243 262 257 261 244 262 257 263 247 261 244 262 257 264 335 263 247 265 251 267 246 266 260 253 242 270 252 269 265 270 252 272 253 271 262 272 253 265 251 273 264 263 247 255 249 259 245 265 251 255 249 263 247 264 335 268 248 263 247 264 335 274 258 268 248 234 228 268 248 274 258 268 248 235 230 267 246 274 258 237 231 234 228 241 232 245 235 243 233 245 235 249 237 247 333 252 255 258 256 256 334 262 257 274 258 264 335 241 232 249 237 245 235 258 256 274 258 262 257 274 258 249 237 241 232 249 237 274 258 258 256 238 259 265 251 266 260 248 239 270 252 246 261 248 239 269 265 270 252 242 234 273 264 240 263 250 238 253 242 269 265 244 236 271 262 272 253 275 278 277 326 276 324 275 278 278 277 277 326 279 336 281 325 280 271 279 336 282 268 281 325 283 266 282 268 279 336 280 271 281 325 288 272 289 274 286 270 285 269 311 295 313 297 312 310 321 304 319 302 320 303 318 301 324 337 323 306 325 307 321 304 322 305 327 309 312 310 328 338 324 337 328 338 323 306 324 337 327 309 328 338 283 266 321 304 285 269 283 266 319 302 321 304 291 276 324 337 287 273 291 276 327 309 324 337 279 336 319 302 283 266 279 336 315 298 319 302 275 278 327 309 291 276 280 271 315 298 279 336 280 271 318 301 315 298 276 324 311 295 275 278 287 273 324 337 318 301 288 272 328 338 292 279 288 272 323 306 328 338 292 279 312 310 278 277 292 279 328 338 312 310 282 268 316 300 317 299 290 275 322 305 286 270 290 275 326 308 322 305 278 277 312 310 313 297 277 326 313 297 314 296 289 274 326 308 290 275 302 288 303 329 301 287 304 292 303 329 302 288 304 292 305 291 303 329 299 286 300 285 307 289 235 230 308 330 305 291 309 294 297 283 294 280 309 294 310 293 297 283 306 290 307 289 310 293 348 311 332 312 331 313 348 311 349 314 332 312 334 315 337 328 336 316 340 327 339 319 341 332 340 327 338 318 339 319 337 328 342 323 336 316 337 328 343 322 342 323 344 339 341 332 345 331 344 339 340 327 341 332 346 320 331 313 350 340 346 320 348 311 331 313 343 322 350 340 342 323 343 322 346 320 350 340 302 288 338 318 340 327 309 294 343 322 306 290 309 294 346 320 343 322 298 284 334 315 338 318 294 280 346 320 309 294 294 280 348 311 346 320 299 286 334 315 298 284 304 292 344 339 235 230 304 292 340 327 344 339 295 282 348 311 294 280 295 282 349 314 348 311 305 291 339 319 303 329 305 291 341 332 339 319 307 289 350 340 310 293 307 289 342 323 350 340 303 329 339 319 335 317 310 293 331 313 297 283 310 293 350 340 331 313 301 287 336 316 300 285 301 287 335 317 336 316 308 330 341 332 305 291 297 283 331 313 332 312 300 285 342 323 307 289 296 281 349 314 295 282 296 281 332 312 349 314 235 230 345 331 308 330 235 230 344 339 345 331 351 341 352 342 353 343 351 341 353 343 354 344 358 345 359 346 360 347 360 347 361 348 362 349 366 350 365 351 367 352 366 350 367 352 368 353 367 352 370 354 371 355 377 356 376 357 378 358 384 359 385 360 380 361 380 361 378 358 376 357 376 357 374 362 372 363 372 363 371 355 370 354 382 364 384 359 380 361 372 363 370 354 387 365 387 365 389 366 382 364 372 363 387 365 382 364 385 360 352 342 351 341 354 344 356 367 358 345 366 350 368 353 369 368 375 369 377 356 379 370 391 371 354 344 358 345 366 350 369 368 375 369 355 372 353 343 383 373 363 374 361 348 388 375 363 374 388 375 387 365 357 376 355 372 382 364 357 376 382 364 390 377 359 346 390 377 389 366 353 343 352 342 384 359 353 343 384 359 383 373 367 352 365 351 386 378 361 348 359 346 389 366 400 379 399 380 401 381 402 382 400 379 401 381 402 382 401 381 403 383 397 384 404 385 405 386 406 387 403 383 407 388 408 389 392 390 395 391 408 389 395 391 409 392 404 385 408 389 409 392 404 385 409 392 405 386 411 393 412 394 413 395 411 393 413 395 414 396 415 397 416 398 417 399 415 397 417 399 418 400 419 401 415 397 418 400 416 398 423 402 424 403 352 342 421 404 422 405 423 402 426 406 427 407 428 408 430 409 431 410 432 411 433 412 434 413 432 411 434 413 435 414 436 415 437 416 433 412 436 415 433 412 432 411 438 417 439 418 437 416 435 414 434 413 440 419 442 420 443 421 439 418 444 422 429 423 428 408 447 424 448 425 449 426 447 424 449 426 450 427 451 428 452 429 453 430 455 431 456 432 452 429 455 431 452 429 451 428 463 433 464 434 448 425 463 433 448 425 447 424 460 435 459 436 464 434 460 435 464 434 463 433 392 390 444 422 428 408 402 382 406 387 442 420 402 382 442 420 438 417 393 437 428 408 431 410 404 385 397 384 435 414 403 383 401 381 437 416 403 383 437 416 439 418 401 381 399 380 433 412 401 381 433 412 437 416 399 380 398 438 434 413 395 391 394 439 430 409 398 438 405 386 440 419 398 438 440 419 434 413 394 439 393 437 431 410 406 387 443 421 442 420 419 401 421 404 457 440 415 397 419 401 455 431 411 393 463 433 447 424 416 398 451 428 454 441 412 394 411 393 447 424 412 394 447 424 450 427 423 402 416 398 454 441 423 402 454 441 460 435 424 403 427 407 464 434 424 403 464 434 459 436 420 442 418 400 452 429 427 407 448 425 464 434 425 443 458 444 462 445 414 396 413 395 449 426 417 399 459 436 453 430 413 395 412 394 450 427 413 395 450 427 449 426 354 344 353 343 355 372 354 344 355 372 356 367 356 367 355 372 357 376 356 367 357 376 358 345 358 345 357 376 359 346 360 347 359 346 361 348 362 349 361 348 363 374 362 349 363 374 364 446 364 446 363 374 365 351 364 446 365 351 366 350 369 368 368 353 367 352 367 352 371 355 369 368 369 368 371 355 372 363 369 368 372 363 373 447 373 447 372 363 374 362 373 447 374 362 375 369 375 369 374 362 376 357 375 369 376 357 377 356 377 356 378 358 379 370 379 370 378 358 380 361 379 370 380 361 381 448 382 364 383 373 384 359 370 354 386 378 387 365 387 365 388 375 389 366 389 366 390 377 382 364 380 361 376 357 372 363 382 364 380 361 372 363 381 448 380 361 385 360 381 448 385 360 391 371 351 341 391 371 385 360 385 360 384 359 352 342 391 371 351 341 354 344 358 345 360 347 362 349 362 349 364 446 366 350 369 368 373 447 375 369 379 370 381 448 391 371 358 345 362 349 366 350 375 369 379 370 391 371 391 371 358 345 366 350 366 350 375 369 391 371 355 372 383 373 382 364 365 351 363 374 387 365 365 351 387 365 386 378 359 346 357 376 390 377 367 352 386 378 370 354 361 348 389 366 388 375 392 390 393 437 394 439 392 390 394 439 395 391 396 449 397 384 398 438 396 449 398 438 399 380 400 379 396 449 399 380 397 384 405 386 398 438 406 387 402 382 403 383 428 408 429 423 430 409 438 417 437 416 436 415 435 414 440 419 441 450 442 420 439 418 438 417 444 422 445 451 429 423 441 450 440 419 445 451 441 450 445 451 444 422 400 379 402 382 438 417 400 379 438 417 436 415 408 389 404 385 441 450 408 389 441 450 444 422 396 449 400 379 436 415 396 449 436 415 432 411 392 390 408 389 444 422 397 384 396 449 432 411 397 384 432 411 435 414 393 437 392 390 428 408 404 385 435 414 441 450 405 386 409 392 445 451 405 386 445 451 440 419 409 392 395 391 429 423 409 392 429 423 445 451 399 380 434 413 433 412 407 388 403 383 439 418 407 388 439 418 443 421 395 391 430 409 429 423 394 439 431 410 430 409 406 387 407 388 443 421 419 401 418 400 420 442 421 404 419 401 420 442 421 404 420 442 422 405 416 398 424 403 417 399 352 342 422 405 425 443 426 406 411 393 414 396 426 406 414 396 427 407 423 402 427 407 424 403 465 424 448 425 449 426 465 424 449 426 466 427 451 428 453 430 454 441 457 440 458 444 456 432 457 440 456 432 455 431 454 441 453 430 459 436 454 441 459 436 460 435 461 452 462 445 458 444 461 452 458 444 457 440 463 433 467 453 448 425 463 433 448 425 465 424 460 435 459 436 467 453 460 435 467 453 463 433 419 401 457 440 455 431 426 406 423 402 460 435 426 406 460 435 463 433 415 397 455 431 451 428 411 393 426 406 463 433 411 393 463 433 465 424 416 398 415 397 451 428 421 404 352 342 461 452 421 404 461 452 457 440 412 394 411 393 465 424 412 394 465 424 466 427 422 405 420 442 456 432 422 405 456 432 458 444 424 403 427 407 467 453 424 403 467 453 459 436 420 442 452 429 456 432 427 407 414 396 448 425 427 407 448 425 467 453 418 400 417 399 453 430 418 400 453 430 452 429 425 443 422 405 458 444 414 396 449 426 448 425 417 399 424 403 459 436 413 395 412 394 466 427 413 395 466 427 449 426 352 342 425 443 462 445 352 342 462 445 461 452</p>\n        </triangles>\n      </mesh>\n    </geometry>\n  </library_geometries>\n  <library_visual_scenes>\n    <visual_scene id=\"Scene\" name=\"Scene\">\n      <node id=\"battery_holder\" name=\"battery_holder\" type=\"NODE\">\n        <matrix sid=\"transform\">1 0 0 0 0 1 0 0 0 0 1 0.025 0 0 0 1</matrix>\n        <instance_geometry url=\"#battery_holder-mesh\" name=\"battery_holder\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"pcb-material\" target=\"#pcb-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"pin_headers\" name=\"pin_headers\" type=\"NODE\">\n        <matrix sid=\"transform\">1 0 0 0 0 1 0 0.011 0 0 1 0.014 0 0 0 1</matrix>\n        <instance_geometry url=\"#pin_headers_001-mesh\" name=\"pin_headers\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"metal-material\" target=\"#metal-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"battery\" name=\"battery\" type=\"NODE\">\n        <matrix sid=\"transform\">1 0 0 0 0 1 0 0 0 0 1.229657 0.02 0 0 0 1</matrix>\n        <instance_geometry url=\"#battery-mesh\" name=\"battery\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"Material_001-material\" target=\"#Material_001-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"cf_body_001\" name=\"cf_body.001\" type=\"NODE\">\n        <matrix sid=\"transform\">1 0 0 0 0 1 0 0 0 0 1 0.015 0 0 0 1</matrix>\n        <instance_geometry url=\"#cf_body_001-mesh\" name=\"cf_body.001\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"pcb-material\" target=\"#pcb-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"Empty\" name=\"Empty\" type=\"NODE\">\n        <matrix sid=\"transform\">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>\n      </node>\n      <node id=\"Cylinder\" name=\"Cylinder\" type=\"NODE\">\n        <matrix sid=\"transform\">0.705359 0 0 0.031 0 0.705359 0 0.031 0 0 0.705359 0.014 0 0 0 1</matrix>\n        <instance_geometry url=\"#Cylinder-mesh\" name=\"Cylinder\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"metal-material\" target=\"#metal-material\">\n                <bind_vertex_input semantic=\"UVMap\" input_semantic=\"TEXCOORD\" input_set=\"0\"/>\n              </instance_material>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"motor_mount\" name=\"motor_mount\" type=\"NODE\">\n        <matrix sid=\"transform\">0.7071068 0.7071068 0 0.031 -0.7071068 0.7071068 0 0.031 0 0 1 0.014 0 0 0 1</matrix>\n        <instance_geometry url=\"#motor_mount-mesh\" name=\"motor_mount\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"Material_002-material\" target=\"#Material_002-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n      <node id=\"cw_prop\" name=\"cw_prop\" type=\"NODE\">\n        <matrix sid=\"transform\">0.6918778 0.7220147 0 0.031 -0.7220147 0.6918778 0 0.031 0 0 1 0.022 0 0 0 1</matrix>\n        <instance_geometry url=\"#cw_prop-mesh\" name=\"cw_prop\">\n          <bind_material>\n            <technique_common>\n              <instance_material symbol=\"pcb-material\" target=\"#pcb-material\"/>\n            </technique_common>\n          </bind_material>\n        </instance_geometry>\n      </node>\n    </visual_scene>\n  </library_visual_scenes>\n  <scene>\n    <instance_visual_scene url=\"#Scene\"/>\n  </scene>\n</COLLADA>"
  },
  {
    "path": "crazyflie/urdf/crazyflie_description.urdf",
    "content": "<?xml version=\"1.0\"?>\n<robot name=\"$NAME\">\n  <link name=\"$NAME\">\n    <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\" />\n    <visual>\n        <geometry>\n          <mesh filename=\"package://crazyflie/urdf/cf2_assembly_with_props.dae\" scale=\"1.0 1.0 1.0\"/>\n        </geometry>\n    </visual>\n  </link>\n</robot>"
  },
  {
    "path": "crazyflie_examples/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package crazyflie_examples\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.0.3 (2025-07-09)\n------------------\n* Improve package.xml (separate maintainer tags, update year)\n* Contributors: Kimberly N. McGuire\n\n1.0.2 (2025-07-02)\n------------------\n\n1.0.1 (2025-06-30)\n------------------\n\n\n1.0.0 (2025-06-21)\n------------------\n* First official release.\n* Contributors: Julien Thevenoz, Khaled Wahba, Kimberly N. McGuire, Pablo Robles, Wolfgang Hönig, phanfeld\n"
  },
  {
    "path": "crazyflie_examples/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(crazyflie_examples)\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_python REQUIRED)\n\n# Install Python modules\nament_python_install_package(${PROJECT_NAME} SCRIPTS_DESTINATION lib/${PROJECT_NAME})\n\n# Install launch and config files.\ninstall(DIRECTORY\n  config\n  data\n  launch\n  DESTINATION share/${PROJECT_NAME}/\n)\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_pytest REQUIRED)\n  set(_pytest_tests\n    test/test_flake8.py\n    test/test_pep257.py\n  )\n  foreach(_test_path ${_pytest_tests})\n    get_filename_component(_test_name ${_test_path} NAME_WE)\n    ament_add_pytest_test(${_test_name} ${_test_path}\n      APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}\n      TIMEOUT 60\n      WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}\n    )\n  endforeach()\nendif()\n\nament_package()\n"
  },
  {
    "path": "crazyflie_examples/config/nav2_params.yaml",
    "content": "controller_server:\n  ros__parameters:\n    use_sim_time: True\n    controller_frequency: 20.0\n    min_x_velocity_threshold: 0.001\n    min_y_velocity_threshold: 0.5\n    min_theta_velocity_threshold: 0.001\n    failure_tolerance: 0.3\n    progress_checker_plugin: \"progress_checker\"\n    goal_checker_plugins: [\"general_goal_checker\"] # \"precise_goal_checker\"\n    controller_plugins: [\"FollowPath\"]\n\n    # Progress checker parameters\n    progress_checker:\n      plugin: \"nav2_controller::SimpleProgressChecker\"\n      required_movement_radius: 0.5\n      movement_time_allowance: 10.0\n    # Goal checker parameters\n  #precise_goal_checker:\n    #  plugin: \"nav2_controller::SimpleGoalChecker\"\n    #  xy_goal_tolerance: 0.25\n    #  yaw_goal_tolerance: 0.25\n    #  stateful: True\n    general_goal_checker:\n      stateful: True\n      plugin: \"nav2_controller::SimpleGoalChecker\"\n      xy_goal_tolerance: 0.25\n      yaw_goal_tolerance: 0.25\n    # FollowPath:\n    #   plugin: \"nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController\"\n    #   desired_linear_vel: 0.5\n    #   lookahead_dist: 0.6\n    #   min_lookahead_dist: 0.3\n    #   max_lookahead_dist: 0.9\n    #   lookahead_time: 1.5\n    #   rotate_to_heading_angular_vel: 1.8\n    #   transform_tolerance: 0.1\n    #   use_velocity_scaled_lookahead_dist: false\n    #   min_approach_linear_velocity: 0.05\n    #   max_allowed_time_to_collision_up_to_carrot: 1.0\n    #   use_regulated_linear_velocity_scaling: true\n    #   use_cost_regulated_linear_velocity_scaling: true\n    #   regulated_linear_scaling_min_radius: 0.9\n    #   regulated_linear_scaling_min_speed: 0.25\n    #   use_rotate_to_heading: false\n    #   allow_reversing: true\n    #   rotate_to_heading_min_angle: 0.2\n    #   max_angular_accel: 3.2\n    #   max_robot_pose_search_dist: 10.0\n    # DWB parameters\n    FollowPath:\n      plugin: \"dwb_core::DWBLocalPlanner\"\n      debug_trajectory_details: True\n      min_vel_x: -0.26\n      min_vel_y: 0.0\n      max_vel_x: 0.26\n      max_vel_y: 0.0\n      max_vel_theta: 1.0\n      min_speed_xy: 0.0\n      max_speed_xy: 0.26\n      min_speed_theta: 0.0\n      # Add high threshold velocity for turtlebot 3 issue.\n      # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75\n      acc_lim_x: 2.5\n      acc_lim_y: 0.0\n      acc_lim_theta: 3.2\n      decel_lim_x: -2.5\n      decel_lim_y: 0.0\n      decel_lim_theta: -3.2\n      vx_samples: 20\n      vy_samples: 5\n      vtheta_samples: 40\n      sim_time: 3.0\n      linear_granularity: 0.05\n      angular_granularity: 0.025\n      transform_tolerance: 0.2\n      xy_goal_tolerance: 0.25\n      trans_stopped_velocity: 0.25\n      short_circuit_trajectory_evaluation: True\n      stateful: True\n      critics: [\"RotateToGoal\", \"Oscillation\", \"BaseObstacle\", \"GoalAlign\", \"PathAlign\", \"PathDist\", \"GoalDist\"]\n      BaseObstacle.scale: 0.02\n      PathAlign.scale: 80.0\n      PathAlign.forward_point_distance: 0.1\n      GoalAlign.scale: 24.0\n      GoalAlign.forward_point_distance: 0.1\n      PathDist.scale: 80.0\n      GoalDist.scale: 24.0\n      RotateToGoal.scale: 32.0\n      RotateToGoal.slowing_factor: 5.0\n      RotateToGoal.lookahead_time: -1.0\n\n\ncontroller_server_rclcpp_node:\n  ros__parameters:\n    use_sim_time: True\n\nlocal_costmap:\n  local_costmap:\n    ros__parameters:\n      update_frequency: 5.0\n      publish_frequency: 2.0\n      global_frame: cf231/odom\n      robot_base_frame: cf231\n      use_sim_time: true\n      rolling_window: true\n      width: 10\n      height: 10\n      resolution: 0.05\n      robot_radius: 0.25\n      plugins: [\"voxel_layer\", \"inflation_layer\"]\n      inflation_layer:\n        plugin: \"nav2_costmap_2d::InflationLayer\"\n        cost_scaling_factor: 1.0\n        inflation_radius: 0.3\n      voxel_layer:\n        plugin: \"nav2_costmap_2d::VoxelLayer\"\n        enabled: True\n        publish_voxel_map: True\n        origin_z: 0.0\n        z_resolution: 0.05\n        z_voxels: 16\n        max_obstacle_height: 2.0\n        mark_threshold: 0\n        observation_sources: scan\n        scan:\n          topic: /scan\n          max_obstacle_height: 2.0\n          clearing: True\n          marking: True\n          data_type: \"LaserScan\"\n          raytrace_max_range: 3.5\n          raytrace_min_range: 0.0\n          obstacle_max_range: 3.2\n          obstacle_min_range: 0.0\n      static_layer:\n        map_subscribe_transient_local: True\n      always_send_full_costmap: True\n  local_costmap_client:\n    ros__parameters:\n      use_sim_time: True\n  local_costmap_rclcpp_node:\n    ros__parameters:\n      use_sim_time: True\n\nglobal_costmap:\n  global_costmap:\n    ros__parameters:\n      update_frequency: 1.0\n      publish_frequency: 1.0\n      global_frame: map\n      robot_base_frame: cf231\n      use_sim_time: True\n      robot_radius: 0.25\n      resolution: 0.05\n      track_unknown_space: true\n      plugins: [\"static_layer\", \"obstacle_layer\", \"inflation_layer\"]\n      obstacle_layer:\n        plugin: \"nav2_costmap_2d::ObstacleLayer\"\n        enabled: True\n        observation_sources: scan\n        scan:\n          topic: /scan\n          max_obstacle_height: 2.0\n          clearing: True\n          marking: True\n          data_type: \"LaserScan\"\n          raytrace_max_range: 3.0\n          raytrace_min_range: 0.0\n          obstacle_max_range: 2.5\n          obstacle_min_range: 0.0\n      static_layer:\n        plugin: \"nav2_costmap_2d::StaticLayer\"\n        map_subscribe_transient_local: True\n      inflation_layer:\n        plugin: \"nav2_costmap_2d::InflationLayer\"\n        cost_scaling_factor: 1.0\n        inflation_radius: 0.3\n      always_send_full_costmap: True\n  global_costmap_client:\n    ros__parameters:\n      use_sim_time: True\n  global_costmap_rclcpp_node:\n    ros__parameters:\n      use_sim_time: True\n\nplanner_server:\n  ros__parameters:\n    planner_plugins: ['GridBased']\n    GridBased:\n      plugin: 'nav2_navfn_planner/NavfnPlanner'\n      use_astar: True\n      allow_unknown: True\n      tolerance: 1.0\n\nplanner_server_rclcpp_node:\n  ros__parameters:\n    use_sim_time: True\n\nrecoveries_server:\n  ros__parameters:\n    costmap_topic: local_costmap/costmap_raw\n    footprint_topic: local_costmap/published_footprint\n    cycle_frequency: 10.0\n    recovery_plugins: [\"spin\", \"backup\", \"wait\"]\n    spin:\n      plugin: \"nav2_recoveries/Spin\"\n    backup:\n      plugin: \"nav2_recoveries/BackUp\"\n    wait:\n      plugin: \"nav2_recoveries/Wait\"\n    global_frame: cf231/odom\n    robot_base_frame: cf231\n    transform_timeout: 0.1\n    use_sim_time: true\n    simulate_ahead_time: 2.0\n    max_rotational_vel: 1.0\n    min_rotational_vel: 0.4\n    rotational_acc_lim: 3.2\n\nwaypoint_follower:\n  ros__parameters:\n    loop_rate: 20\n    stop_on_failure: false\n    waypoint_task_executor_plugin: \"wait_at_waypoint\"\n    wait_at_waypoint:\n      plugin: \"nav2_waypoint_follower::WaitAtWaypoint\"\n      enabled: True\n      waypoint_pause_duration: 200\n"
  },
  {
    "path": "crazyflie_examples/config/nav2_view.rviz",
    "content": "Panels:\n  - Class: rviz_common/Displays\n    Help Height: 0\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /TF1/Frames1\n        - /TF1/Tree1\n      Splitter Ratio: 0.5833333134651184\n    Tree Height: 606\n  - Class: rviz_common/Selection\n    Name: Selection\n  - Class: rviz_common/Tool Properties\n    Expanded:\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.5886790156364441\n  - Class: rviz_common/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: nav2_rviz_plugins/Navigation 2\n    Name: Navigation 2\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz_default_plugins/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.029999999329447746\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Class: rviz_default_plugins/RobotModel\n      Collision Enabled: false\n      Description File: \"\"\n      Description Source: Topic\n      Description Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /robot_description\n      Enabled: false\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: \"\"\n      Mass Properties:\n        Inertia: false\n        Mass: false\n      Name: RobotModel\n      TF Prefix: \"\"\n      Update Interval: 0\n      Value: false\n      Visual Enabled: true\n    - Class: rviz_default_plugins/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        base_footprint:\n          Value: true\n        base_link:\n          Value: true\n        base_scan:\n          Value: true\n        camera_depth_frame:\n          Value: true\n        camera_depth_optical_frame:\n          Value: true\n        camera_link:\n          Value: true\n        camera_rgb_frame:\n          Value: true\n        camera_rgb_optical_frame:\n          Value: true\n        caster_back_left_link:\n          Value: true\n        caster_back_right_link:\n          Value: true\n        imu_link:\n          Value: true\n        map:\n          Value: true\n        odom:\n          Value: true\n        wheel_left_link:\n          Value: true\n        wheel_right_link:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: false\n      Tree:\n        map:\n          odom:\n            base_footprint:\n              base_link:\n                base_scan:\n                  {}\n                camera_link:\n                  camera_depth_frame:\n                    camera_depth_optical_frame:\n                      {}\n                  camera_rgb_frame:\n                    camera_rgb_optical_frame:\n                      {}\n                caster_back_left_link:\n                  {}\n                caster_back_right_link:\n                  {}\n                imu_link:\n                  {}\n                wheel_left_link:\n                  {}\n                wheel_right_link:\n                  {}\n      Update Interval: 0\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_default_plugins/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      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.009999999776482582\n      Style: Points\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        Filter size: 10\n        History Policy: Keep Last\n        Reliability Policy: Best Effort\n        Value: /scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz_default_plugins/PointCloud2\n      Color: 255; 255; 255\n      Color Transformer: \"\"\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: Bumper Hit\n      Position Transformer: \"\"\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.07999999821186066\n      Style: Spheres\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        Filter size: 10\n        History Policy: Keep Last\n        Reliability Policy: Best Effort\n        Value: /mobile_base/sensors/bumper_pointcloud\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 1\n      Class: rviz_default_plugins/Map\n      Color Scheme: map\n      Draw Behind: true\n      Enabled: true\n      Name: Map\n      Topic:\n        Depth: 1\n        Durability Policy: Transient Local\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /map\n      Use Timestamp: false\n      Value: true\n    - Alpha: 1\n      Class: nav2_rviz_plugins/ParticleCloud\n      Color: 0; 180; 0\n      Enabled: true\n      Max Arrow Length: 0.3\n      Min Arrow Length: 0.02\n      Name: Amcl Particle Swarm\n      Shape: Arrow (Flat)\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Best Effort\n        Value: /particle_cloud\n      Value: true\n    - Class: rviz_common/Group\n      Displays:\n        - Alpha: 0.3\n          Class: rviz_default_plugins/Map\n          Color Scheme: costmap\n          Draw Behind: false\n          Enabled: true\n          Name: Global Costmap\n          Topic:\n            Depth: 1\n            Durability Policy: Transient Local\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /global_costmap/costmap\n          Use Timestamp: false\n          Value: true\n        - Alpha: 0.3\n          Class: rviz_default_plugins/Map\n          Color Scheme: costmap\n          Draw Behind: false\n          Enabled: true\n          Name: Downsampled Costmap\n          Topic:\n            Depth: 1\n            Durability Policy: Transient Local\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /downsampled_costmap\n          Update Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /downsampled_costmap_updates\n          Use Timestamp: false\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz_default_plugins/Path\n          Color: 255; 0; 0\n          Enabled: true\n          Head Diameter: 0.019999999552965164\n          Head Length: 0.019999999552965164\n          Length: 0.30000001192092896\n          Line Style: Lines\n          Line Width: 0.029999999329447746\n          Name: Path\n          Offset:\n            X: 0\n            Y: 0\n            Z: 0\n          Pose Color: 255; 85; 255\n          Pose Style: Arrows\n          Radius: 0.029999999329447746\n          Shaft Diameter: 0.004999999888241291\n          Shaft Length: 0.019999999552965164\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /plan\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_default_plugins/PointCloud2\n          Color: 125; 125; 125\n          Color Transformer: FlatColor\n          Decay Time: 0\n          Enabled: true\n          Invert Rainbow: false\n          Max Color: 255; 255; 255\n          Max Intensity: 4096\n          Min Color: 0; 0; 0\n          Min Intensity: 0\n          Name: VoxelGrid\n          Position Transformer: XYZ\n          Selectable: true\n          Size (Pixels): 3\n          Size (m): 0.05000000074505806\n          Style: Boxes\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /global_costmap/voxel_marked_cloud\n          Use Fixed Frame: true\n          Use rainbow: true\n          Value: true\n        - Alpha: 1\n          Class: rviz_default_plugins/Polygon\n          Color: 25; 255; 0\n          Enabled: false\n          Name: Polygon\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /global_costmap/published_footprint\n          Value: false\n      Enabled: true\n      Name: Global Planner\n    - Class: rviz_common/Group\n      Displays:\n        - Alpha: 0.699999988079071\n          Class: rviz_default_plugins/Map\n          Color Scheme: costmap\n          Draw Behind: false\n          Enabled: true\n          Name: Local Costmap\n          Topic:\n            Depth: 1\n            Durability Policy: Transient Local\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /local_costmap/costmap\n          Update Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /local_costmap/costmap_updates\n          Use Timestamp: false\n          Value: true\n        - Alpha: 1\n          Buffer Length: 1\n          Class: rviz_default_plugins/Path\n          Color: 0; 12; 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: 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:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /local_plan\n          Value: true\n        - Class: rviz_default_plugins/MarkerArray\n          Enabled: false\n          Name: Trajectories\n          Namespaces:\n            {}\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /marker\n          Value: false\n        - Alpha: 1\n          Class: rviz_default_plugins/Polygon\n          Color: 25; 255; 0\n          Enabled: true\n          Name: Polygon\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /local_costmap/published_footprint\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_default_plugins/PointCloud2\n          Color: 255; 255; 255\n          Color Transformer: RGB8\n          Decay Time: 0\n          Enabled: true\n          Invert Rainbow: false\n          Max Color: 255; 255; 255\n          Max Intensity: 4096\n          Min Color: 0; 0; 0\n          Min Intensity: 0\n          Name: VoxelGrid\n          Position Transformer: XYZ\n          Selectable: true\n          Size (Pixels): 3\n          Size (m): 0.009999999776482582\n          Style: Flat Squares\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /local_costmap/voxel_marked_cloud\n          Use Fixed Frame: true\n          Use rainbow: true\n          Value: true\n      Enabled: true\n      Name: Controller\n    - Class: rviz_common/Group\n      Displays:\n        - Class: rviz_default_plugins/Image\n          Enabled: true\n          Max Value: 1\n          Median window: 5\n          Min Value: 0\n          Name: RealsenseCamera\n          Normalize Range: true\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /intel_realsense_r200_depth/image_raw\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_default_plugins/PointCloud2\n          Color: 255; 255; 255\n          Color Transformer: RGB8\n          Decay Time: 0\n          Enabled: true\n          Invert Rainbow: false\n          Max Color: 255; 255; 255\n          Max Intensity: 4096\n          Min Color: 0; 0; 0\n          Min Intensity: 0\n          Name: RealsenseDepthImage\n          Position Transformer: XYZ\n          Selectable: true\n          Size (Pixels): 3\n          Size (m): 0.009999999776482582\n          Style: Flat Squares\n          Topic:\n            Depth: 5\n            Durability Policy: Volatile\n            Filter size: 10\n            History Policy: Keep Last\n            Reliability Policy: Reliable\n            Value: /intel_realsense_r200_depth/points\n          Use Fixed Frame: true\n          Use rainbow: true\n          Value: true\n      Enabled: false\n      Name: Realsense\n    - Class: rviz_default_plugins/MarkerArray\n      Enabled: true\n      Name: MarkerArray\n      Namespaces:\n        {}\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /waypoints\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: world\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz_default_plugins/MoveCamera\n    - Class: rviz_default_plugins/Select\n    - Class: rviz_default_plugins/FocusCamera\n    - Class: rviz_default_plugins/Measure\n      Line color: 128; 128; 0\n    - Class: rviz_default_plugins/SetInitialPose\n      Covariance x: 0.25\n      Covariance y: 0.25\n      Covariance yaw: 0.06853891909122467\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /initialpose\n    - Class: rviz_default_plugins/PublishPoint\n      Single click: true\n      Topic:\n        Depth: 5\n        Durability Policy: Volatile\n        History Policy: Keep Last\n        Reliability Policy: Reliable\n        Value: /clicked_point\n    - Class: nav2_rviz_plugins/GoalTool\n  Transformation:\n    Current:\n      Class: rviz_default_plugins/TF\n  Value: true\n  Views:\n    Current:\n      Angle: -1.6150002479553223\n      Class: rviz_default_plugins/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: 127.88431549072266\n      Target Frame: <Fixed Frame>\n      Value: TopDownOrtho (rviz_default_plugins)\n      X: -0.044467076659202576\n      Y: -0.38726311922073364\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 932\n  Hide Left Dock: false\n  Hide Right Dock: true\n  Navigation 2:\n    collapsed: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000034afc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000029b000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e0020003201000002de000000a90000008100fffffffb0000001e005200650061006c00730065006e0073006500430061006d00650072006100000002c6000000c10000002800ffffff000000010000010f0000034afc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d0000034a000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004990000034a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  RealsenseCamera:\n    collapsed: false\n  Selection:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: true\n  Width: 1545\n  X: 696\n  Y: 229"
  },
  {
    "path": "crazyflie_examples/config/slam_params.yaml",
    "content": "slam_toolbox:\n  ros__parameters:\n\n    # Plugin params\n    solver_plugin: solver_plugins::CeresSolver\n    ceres_linear_solver: SPARSE_NORMAL_CHOLESKY\n    ceres_preconditioner: SCHUR_JACOBI\n    ceres_trust_strategy: LEVENBERG_MARQUARDT\n    ceres_dogleg_type: TRADITIONAL_DOGLEG\n    ceres_loss_function: None\n\n    # ROS Parameters\n    odom_frame: cf231/odom\n    map_frame: map\n    base_frame: cf231\n    scan_topic: /cf231/scan\n    use_map_saver: true\n    mode: mapping #localization\n\n    # if you'd like to immediately start continuing a map at a given pose\n    # or at the dock, but they are mutually exclusive, if pose is given\n    # will use pose\n    #map_file_name: test_steve\n    # map_start_pose: [0.0, 0.0, 0.0]\n    #map_start_at_dock: true\n\n    debug_logging: false\n    throttle_scans: 1\n    transform_publish_period: 0.02 #if 0 never publishes odometry\n    map_update_interval: 0.1\n    resolution: 0.1\n    min_laser_range: 0.0 #for rastering images\n    max_laser_range: 3.5 #for rastering images\n    minimum_time_interval: 0.5\n    transform_timeout: 0.2\n    tf_buffer_duration: 30.0\n    stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps\n    enable_interactive_mode: true\n\n    # General Parameters\n    use_scan_matching: false\n    use_scan_barycenter: true\n    minimum_travel_distance: 0.01\n    minimum_travel_heading: 0.001\n    scan_buffer_size: 10\n    scan_buffer_maximum_scan_distance: 10.0\n    link_match_minimum_response_fine: 0.1  \n    link_scan_maximum_distance: 1.5\n    loop_search_maximum_distance: 3.0\n    do_loop_closing: true \n    loop_match_minimum_chain_size: 10           \n    loop_match_maximum_variance_coarse: 3.0  \n    loop_match_minimum_response_coarse: 0.35    \n    loop_match_minimum_response_fine: 0.45\n\n    # Correlation Parameters - Correlation Parameters\n    correlation_search_space_dimension: 0.5\n    correlation_search_space_resolution: 0.01\n    correlation_search_space_smear_deviation: 0.1 \n\n    # Correlation Parameters - Loop Closure Parameters\n    loop_search_space_dimension: 8.0\n    loop_search_space_resolution: 0.05\n    loop_search_space_smear_deviation: 0.03\n\n    # Scan Matcher Parameters\n    distance_variance_penalty: 0.5      \n    angle_variance_penalty: 1.0    \n\n    fine_search_angle_offset: 0.00349     \n    coarse_search_angle_offset: 0.349   \n    coarse_angle_resolution: 0.0349        \n    minimum_angle_penalty: 0.9\n    minimum_distance_penalty: 0.5\n    use_response_expansion: true"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/__init__.py",
    "content": ""
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/arming.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    # arm (one by one)\n    for cf in allcfs.crazyflies:\n        cf.arm(True)\n        timeHelper.sleep(1.0)\n\n    timeHelper.sleep(2.0)\n\n    # disarm (broadcast)\n    allcfs.arm(False)\n    timeHelper.sleep(5.0)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/cmd_full_state.py",
    "content": "#!/usr/bin/env python\n\nfrom pathlib import Path\n\nfrom crazyflie_py import Crazyswarm\nfrom crazyflie_py.uav_trajectory import Trajectory\nimport numpy as np\n\n\ndef executeTrajectory(timeHelper, cf, trajpath, rate=100, offset=np.zeros(3)):\n    traj = Trajectory()\n    traj.loadcsv(trajpath)\n\n    start_time = timeHelper.time()\n    while not timeHelper.isShutdown():\n        t = timeHelper.time() - start_time\n        if t > traj.duration:\n            break\n\n        e = traj.eval(t)\n        cf.cmdFullState(\n            e.pos + np.array(cf.initialPosition) + offset,\n            e.vel,\n            e.acc,\n            e.yaw,\n            e.omega)\n\n        timeHelper.sleepForRate(rate)\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    cf = swarm.allcfs.crazyflies[0]\n\n    rate = 30.0\n    Z = 0.5\n\n    cf.takeoff(targetHeight=Z, duration=Z+1.0)\n    timeHelper.sleep(Z+2.0)\n\n    executeTrajectory(timeHelper, cf,\n                      Path(__file__).parent / 'data/figure8.csv',\n                      rate,\n                      offset=np.array([0, 0, 0.5]))\n\n    cf.notifySetpointsStop()\n    cf.land(targetHeight=0.03, duration=Z+1.0)\n    timeHelper.sleep(Z+2.0)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/data/figure8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.050000,0.000000,-0.000000,0.000000,-0.000000,0.830443,-0.276140,-0.384219,0.180493,-0.000000,0.000000,-0.000000,0.000000,-1.356107,0.688430,0.587426,-0.329106,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,0.396058,0.918033,0.128965,-0.773546,0.339704,0.034310,-0.026417,-0.030049,-0.445604,-0.684403,0.888433,1.493630,-1.361618,-0.139316,0.158875,0.095799,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,0.922409,0.405715,-0.582968,-0.092188,-0.114670,0.101046,0.075834,-0.037926,-0.291165,0.967514,0.421451,-1.086348,0.545211,0.030109,-0.050046,-0.068177,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,0.923174,-0.431533,-0.682975,0.177173,0.319468,-0.043852,-0.111269,0.023166,0.289869,0.724722,-0.512011,-0.209623,-0.218710,0.108797,0.128756,-0.055461,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.405364,-0.834716,0.158939,0.288175,-0.373738,-0.054995,0.036090,0.078627,0.450742,-0.385534,-0.954089,0.128288,0.442620,0.055630,-0.060142,-0.076163,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.001062,-0.646270,-0.012560,-0.324065,0.125327,0.119738,0.034567,-0.063130,0.001593,-1.031457,0.015159,0.820816,-0.152665,-0.130729,-0.045679,0.080444,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,-0.402804,-0.820508,-0.132914,0.236278,0.235164,-0.053551,-0.088687,0.031253,-0.449354,-0.411507,0.902946,0.185335,-0.239125,-0.041696,0.016857,0.016709,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,-0.921641,-0.464596,0.661875,0.286582,-0.228921,-0.051987,0.004669,0.038463,-0.292459,0.777682,0.565788,-0.432472,-0.060568,-0.082048,-0.009439,0.041158,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,-0.923935,0.447832,0.627381,-0.259808,-0.042325,-0.032258,0.001420,0.005294,0.288570,0.873350,-0.515586,-0.730207,-0.026023,0.288755,0.215678,-0.148061,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.053185,-0.398611,0.850510,-0.144007,-0.485368,-0.079781,0.176330,0.234482,-0.153567,0.447039,-0.532729,-0.855023,0.878509,0.775168,-0.391051,-0.713519,0.391628,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj0.csv",
    "content": "Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7\n0.960464,0.0,0,0,0,-2.11233,4.6768,-3.73784,1.04989,0.0,0,0,0,3.30457,-7.9007,6.65669,-1.94082,0.0,0,0,0,-0.297773,0.623628,-0.493335,0.138654,0,0,0,0,0,0,0,0\n1.57331,0.176622,-0.147985,0.0532986,0.0623229,0.343746,-0.500924,0.241338,-0.0403025,0.289553,0.0742267,-0.0522539,-0.0351683,-0.975361,1.50407,-0.788135,0.141456,0.043558,-0.0592408,-0.0401473,-0.00342225,-1.05145,1.64557,-0.878344,0.159958,0,0,0,0,0,0,0,0\n1.68226,0.294342,0.17123,-0.0334701,-0.0192207,-0.0992382,0.118149,-0.0472082,0.00658999,0.084993,-0.0345305,0.0714366,0.00548031,0.800464,-1.18606,0.592827,-0.10086,-0.246232,0.00212717,0.0685892,0.0024846,1.23285,-1.76366,0.869779,-0.147011,0,0,0,0,0,0,0,0\n1.92896,0.374489,-0.0338637,0.00252255,0.00888171,0.0111398,-0.0108929,0.00298726,-0.000251823,0.276975,-0.0784884,-0.0934159,0.000645144,-1.04135,1.33809,-0.584077,0.0868443,0.183524,0.0937667,-0.0541849,-0.00524925,-0.318377,0.393297,-0.166638,0.0242508,0,0,0,0,0,0,0,0\n2.03711,0.374489,0.0286391,-6.1852e-05,-0.00368623,0.00253097,-0.0050055,0.00272644,-0.000441277,-0.358361,0.0262046,0.110055,-0.00620508,0.544041,-0.672761,0.279349,-0.0393627,0.0461,-0.0452504,0.0303272,0.00292994,0.0964916,-0.116635,0.047237,-0.00652766,0,0,0,0,0,0,0,0\n1.08507,0.4,-0.00978883,-0.00352811,0.00421159,-0.147076,0.385891,-0.320935,0.0884478,0.1,-0.0261795,-0.0932209,0.0135473,-3.39392,7.64989,-5.90562,1.55714,0.1,0.0120733,-0.0160302,0.00109914,-0.170679,0.405338,-0.316775,0.0837347,0,0,0,0,0,0,0,0\n1.46341,0.4,0.0345966,0.0216228,0.00040938,0.113468,-0.193811,0.109932,-0.021215,-0.1,-0.00953811,0.0938259,0.00686414,1.78784,-3.00192,1.71647,-0.335021,0.1,0.0162005,0.0183118,0.001431,0.543281,-0.905734,0.51742,-0.101032,0,0,0,0,0,0,0,0\n2.19353,0.492638,0.0469231,-0.0199807,-0.000892996,-0.0338512,0.0362701,-0.0130911,0.00162474,0.203839,-0.0288206,-0.11848,-0.00554452,-0.630569,0.72139,-0.276928,0.0361384,0.209968,0.00986131,-0.0243065,-0.00119445,-0.0998581,0.115095,-0.0441976,0.00576199,0,0,0,0,0,0,0,0\n2.40126,0.48694,-0.00615544,0.0115191,0.000423929,0.00796213,-0.00925373,0.00321793,-0.000373305,-0.469909,0.0557579,0.149918,-0.00106415,0.538482,-0.564538,0.198219,-0.0236403,0.119622,0.0192151,0.028845,-0.000113746,0.115626,-0.12072,0.0423492,-0.00505007,0,0,0,0,0,0,0,0\n2.46094,0.515442,-0.000365976,-0.0122673,2.25527e-05,4.3861e-06,0.00181356,-0.000737567,8.47618e-05,0.463845,-0.0412104,-0.17329,0.000264977,-0.593703,0.60121,-0.20494,0.023781,0.330891,0.000348253,-0.0330759,0.000313802,-0.0979748,0.0999974,-0.0342066,0.00397451,0,0,0,0,0,0,0,0\n2.68427,0.48694,0.00486563,0.0132321,-0.00114426,0.0129524,-0.0144619,0.00482814,-0.000528691,-0.71593,-0.0408684,0.184692,0.00619732,0.442694,-0.405637,0.125531,-0.0132641,0.142929,-0.00451953,0.0270264,-0.00218942,0.0121858,-0.0179685,0.00647746,-0.000732907,0,0,0,0,0,0,0,0\n1.92558,0.505486,-0.0481952,-0.0204291,0.00284946,-0.0470553,0.0773259,-0.0377233,0.00598077,0.718761,0.267399,-0.141554,-0.0117975,-0.800345,0.963882,-0.403221,0.0582575,0.098904,-0.131338,-0.0396354,0.00782912,-0.4965,0.661823,-0.295209,0.0445271,0,0,0,0,0,0,0,0\n2.0699,0.421491,0.0186218,0.0156054,-0.00129697,0.07458,-0.0953844,0.0399616,-0.00562765,0.302142,-0.266958,0.0381168,0.0177516,-0.0552536,0.0911841,-0.0450511,0.00702141,-0.228372,0.115857,0.0879918,-0.00554767,0.814447,-0.973674,0.396022,-0.0548837,0,0,0,0,0,0,0,0\n1.9596,0.48694,-0.0304046,-0.0213345,0.00170875,-0.231304,0.295149,-0.127553,0.0187408,0.120541,0.123032,0.0122544,-0.012462,0.149347,-0.218046,0.101473,-0.0155924,0.505486,0.00192474,-0.107286,0.000790515,-1.01863,1.26183,-0.536142,0.0779269,0,0,0,0,0,0,0,0\n1.70183,0.333009,0.0183142,0.028215,-0.00185434,0.43896,-0.63547,0.3139,-0.0528803,0.232223,-0.140993,-0.0449547,0.00936592,-1.12957,1.6455,-0.81818,0.138527,-0.167385,-0.101997,0.0790866,0.00096767,0.497639,-0.719611,0.351991,-0.0587304,0,0,0,0,0,0,0,0\n1.34472,0.48694,-0.00625689,-0.0317257,0.000382684,-1.03393,1.83762,-1.13117,0.238966,-0.226478,0.0101228,0.0610516,-0.00764983,1.25229,-2.30188,1.44081,-0.307367,-0.082374,-0.033286,-0.0550669,0.00313228,-1.52482,2.7969,-1.74891,0.372958,0,0,0,0,0,0,0,0\n2.1222,0.333009,-0.0545061,0.0199991,0.00480515,0.107972,-0.116334,0.0436145,-0.00566624,-0.072397,-0.0307885,-0.0689067,-0.00236443,-0.48434,0.57055,-0.226496,0.0305878,-0.282503,0.028035,0.0816772,0.00612047,0.73381,-0.837942,0.327938,-0.0439369,0,0,0,0,0,0,0,0\n2.22722,0.421491,0.0660872,-0.00287208,-0.00340824,0.062709,-0.0713995,0.0277343,-0.00364623,-0.495874,0.0534612,0.0981472,0.00118253,0.675836,-0.73877,0.276221,-0.03532,0.457563,0.131649,-0.0799577,-0.00792167,-0.366161,0.385528,-0.140404,0.0176255,0,0,0,0,0,0,0,0\n1.85734,0.540865,-0.00634081,-0.00724899,0.00147892,-0.0808568,0.10675,-0.0483186,0.00746342,0.379252,0.132248,-0.0957692,-0.00873243,-1.07307,1.34465,-0.588112,0.0887744,0.038957,-0.200084,0.0246642,0.00970083,-0.25658,0.36452,-0.173423,0.0277121,0,0,0,0,0,0,0,0\n1.69138,0.496281,-0.00160133,0.00618968,0.000136705,0.124512,-0.174729,0.0851269,-0.0142547,-0.1853,-0.289684,0.024136,0.0175717,-0.384504,0.663858,-0.362455,0.0651215,-0.18831,0.0702784,0.0295687,-0.00247486,1.21881,-1.70715,0.833757,-0.139995,0,0,0,0,0,0,0,0\n2.19933,0.540865,0.0144117,-0.00391837,-0.00119932,-0.0275664,0.0268387,-0.00940817,0.0011576,-0.385893,0.235345,0.0702187,-0.0148152,0.588274,-0.67496,0.261551,-0.0343838,0.323729,0.185085,-0.00841054,-0.00925475,0.039381,-0.0748132,0.0351087,-0.00510156,0,0,0,0,0,0,0,0\n2.68201,0.500322,-0.0412104,-0.00763103,0.000713901,-0.0520821,0.0470691,-0.0146416,0.00155911,0.387882,-0.0842107,-0.121138,0.00454433,-0.324702,0.302031,-0.0946549,0.0100916,0.366876,-0.264264,-0.0765883,0.0107036,-0.298247,0.281606,-0.0893991,0.00961875,0,0,0,0,0,0,0,0\n2.21932,0.292621,-0.0377479,0.0107761,0.00185615,0.0523879,-0.0498758,0.0171324,-0.002072,-0.664787,-0.0756608,0.114634,0.000204595,0.482644,-0.530616,0.198653,-0.0254146,-0.710774,0.0179677,0.111474,-0.00732309,0.507412,-0.56779,0.21534,-0.0277882,0,0,0,0,0,0,0,0\n0.826943,0.365479,0.0796986,0.011073,-0.00345361,6.10559,-17.7498,17.8943,-6.18313,-0.128196,0.0924843,-0.0686475,0.000538459,-0.967377,2.3937,-2.12002,0.661123,-0.100394,0.03983,-0.0650002,0.0145722,-1.19604,3.65303,-3.72378,1.2885,0,0,0,0,0,0,0,0\n1.70943,0.515442,0.0778242,-0.0130839,-0.00452718,-0.0331128,0.0135171,0.00336571,-0.00165812,-0.128196,-0.0503162,-0.00225906,0.0131073,0.046757,-0.0481522,0.016617,-0.00196654,-0.100394,0.0424298,0.0647269,0.0125499,1.45743,-2.08038,1.01596,-0.169609,0,0,0,0,0,0,0,0\n2.0764,0.515442,-0.0859543,-0.0188315,0.00474201,-0.258721,0.311102,-0.127276,0.0176996,-0.128196,0.0471026,0.00501662,-0.00187713,0.203127,-0.228639,0.0905749,-0.0123697,0.418091,0.0269611,-0.0986299,-0.00460336,-0.709972,0.831305,-0.332664,0.0455369,0,0,0,0,0,0,0,0\n1.34033,0.241704,0.00169625,0.0267376,-0.0040746,0.496448,-0.922,0.581167,-0.124661,0.125962,0.103337,0.00817997,-0.00308402,1.45034,-2.64983,1.66366,-0.356691,-0.186694,-0.0951879,0.0808931,0.00400333,1.56751,-2.73421,1.6614,-0.348002,0,0,0,0,0,0,0,0\n1.27955,0.296893,-0.0207413,-0.0288722,0.000206756,-1.45292,2.73635,-1.78001,0.396694,0.363893,0.0205828,-0.0396241,-0.00426978,-2.18054,3.96089,-2.52441,0.555328,0.000432,0.116162,-0.0271769,-0.0121203,-0.0967398,0.0511672,0.0231312,-0.0137364,0,0,0,0,0,0,0,0\n1.25924,0.129979,-0.0386626,0.0254433,0.00229348,0.314605,-0.568015,0.359101,-0.0786867,0.096373,-0.177655,-0.00188175,0.0162637,-1.43193,2.92354,-2.00733,0.465729,0.019741,-0.0837562,-0.0114419,0.0108961,-0.89746,1.80018,-1.22397,0.282268,0,0,0,0,0,0,0,0\n1.35118,0.155486,0.0338914,-0.00270101,-0.0039661,0.202739,-0.374799,0.237823,-0.0512712,-0.106737,0.0769914,0.0704076,-0.0152089,1.54198,-2.90366,1.8396,-0.394692,-0.101778,0.0286494,0.0412961,-0.00329222,1.31264,-2.35215,1.45212,-0.306802,0,0,0,0,0,0,0,0\n1.14424,0.2,0.0015442,-0.00224162,0.00123466,-0.00661606,0.0134679,-0.00982511,0.00245085,0.0,-0.0953098,-0.0830381,0.0218392,-2.55729,5.66335,-4.2252,1.06822,0.1,0.0445589,-0.0317429,-0.000623191,-0.213517,0.427027,-0.293881,0.0698972,0,0,0,0,0,0,0,0\n1.06974,0.0,-7.36408e-05,0.000107209,-5.42089e-05,0.000468972,-0.00106323,0.000841569,-0.000226684,0.0,0.0736875,0.104178,-0.0410587,3.38468,-7.9737,6.38949,-1.73737,0.1,-0.0104492,0.00871066,0.00133714,0.089598,-0.209747,0.164384,-0.043835,0,0,0,0,0,0,0,0\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/data/multi_trajectory/traj1.csv",
    "content": "Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7\n1.58689,0.443644,0,0,0,0.176458,-0.277346,0.146502,-0.0263413,0.27403,0,0,0,-0.969348,1.31026,-0.635009,0.107834,-0.324817,0,0,0,0.947831,-1.39538,0.718022,-0.127373,0,0,0,0,0,0,0,0\n0.890989,0.443644,-0.0721746,-0.0481265,-0.00174274,-2.38876,6.48143,-6.05271,1.93458,-0.095532,-0.236947,0.0988665,0.0243629,-0.0287529,0.818184,-1.21706,0.489085,-0.1177,0.0224222,-0.0579883,-0.00635038,-3.18687,8.58966,-7.97789,2.54091,0,0,0,0,0,0,0,0\n1.53486,0.308067,-0.114025,0.00833839,-0.0136027,-0.190236,0.400005,-0.245,0.0487226,-0.16051,0.106521,0.0762848,-0.0118869,0.869275,-1.4546,0.813715,-0.153918,-0.192154,-0.0255297,0.0471242,0.013469,1.47286,-2.28343,1.22543,-0.225956,0,0,0,0,0,0,0,0\n1.20574,0.229597,0.101098,0.0403443,-0.0117554,0.612049,-1.29557,0.91739,-0.219889,0.12349,-0.0326791,-0.0810358,0.00511437,-0.0119636,-0.129645,0.159859,-0.0493012,0.139088,0.105186,-0.0429857,-0.00824644,-0.426611,0.708134,-0.424241,0.0899061,0,0,0,0,0,0,0,0\n1.61049,0.385722,0.0449782,-0.0568855,0.00100221,-0.296267,0.456138,-0.235473,0.0414109,-0.071886,-0.275848,-0.00982319,0.0199655,-0.418333,0.743297,-0.41853,0.0779387,0.121433,-0.0953079,-0.0195188,0.00672895,-0.986485,1.4776,-0.766424,0.136151,0,0,0,0,0,0,0,0\n1.77241,0.318676,0.0130755,0.051379,0.00163186,0.254729,-0.369028,0.176366,-0.0285284,-0.331996,0.172545,0.124058,-0.0102556,0.574069,-0.845607,0.409659,-0.066924,-0.229303,-0.0799599,0.0201996,0.00425707,0.270074,-0.320376,0.137753,-0.0208602,0,0,0,0,0,0,0,0\n1.68623,0.471478,-0.00700139,-0.0574223,0.000824084,-0.170779,0.252884,-0.123989,0.020684,0.203789,0.0456429,-0.133416,-0.00125178,-0.378444,0.549314,-0.267369,0.0444547,-0.098031,0.168331,0.024297,-0.0106439,0.812651,-1.23173,0.628333,-0.108462,0,0,0,0,0,0,0,0\n1.70797,0.318676,-0.059821,0.0432232,0.00275935,0.183704,-0.261882,0.125489,-0.0205664,-0.098623,-0.183905,0.0438798,0.00600693,0.386813,-0.511056,0.236722,-0.0380493,0.221884,-0.104132,-0.0742226,0.00877222,-1.29322,1.8771,-0.928089,0.156274,0,0,0,0,0,0,0,0\n1.63072,0.356497,-4.11291e-05,-0.034393,-0.00252704,-0.155851,0.227376,-0.112491,0.0191201,-0.127795,0.0145994,-0.014578,-0.0034302,-0.264733,0.385885,-0.194233,0.0336069,-0.264538,0.0346118,0.0912638,-0.00556921,1.41951,-2.14363,1.10444,-0.194067,0,0,0,0,0,0,0,0\n1.36212,0.244883,-0.0626288,0.024624,0.00339865,0.126193,-0.182001,0.09351,-0.0169228,-0.201757,-0.0234969,0.0139891,0.00349774,0.431956,-0.716345,0.42073,-0.0857819,0.146726,-0.012711,-0.0893087,0.00469889,-2.12562,3.80966,-2.33878,0.49062,0,0,0,0,0,0,0,0\n1.82196,0.244883,0.0406549,0.00586313,0.00168572,-0.0433553,0.0676795,-0.0338441,0.00560961,-0.130024,0.0725214,0.0112112,-0.00351014,0.365606,-0.493117,0.228276,-0.0360459,-0.147678,-0.00974881,0.091086,0.0052085,1.01471,-1.36469,0.625516,-0.0979204,0,0,0,0,0,0,0,0\n1.88536,0.365523,0.118336,0.0158494,0.00203578,0.080822,-0.129217,0.062358,-0.00989321,0.094463,0.022789,-0.0157712,0.00228477,0.0609547,-0.0643368,0.0256745,-0.00366509,0.306101,0.00948163,-0.100541,-0.00357356,-1.12554,1.45138,-0.640955,0.096821,0,0,0,0,0,0,0,0\n1.94706,0.564559,0.00555788,-0.0392888,0.00142042,0.006412,-0.017967,0.0109462,-0.0019523,0.176998,0.0745836,0.0180371,-0.00449013,0.199562,-0.274845,0.123797,-0.0186869,-0.292833,-0.0609497,0.0982547,0.0060789,0.927323,-1.13875,0.482089,-0.070056,0,0,0,0,0,0,0,0\n1.88285,0.415593,-0.139809,0.00117123,0.00414341,0.0419276,-0.0419051,0.0153057,-0.00199524,0.297181,-0.10615,-0.0494363,0.00620643,-0.695472,0.917833,-0.412205,0.0630074,0.302198,0.163252,-0.0679965,-0.012082,-0.531283,0.639569,-0.269952,0.0395536,0,0,0,0,0,0,0,0\n1.20694,0.234044,-0.0543444,0.0131665,-4.5766e-05,-0.0100483,0.0552389,-0.05356,0.0151644,-0.138033,0.00668935,0.0593357,-0.00674105,1.62275,-3.25059,2.24221,-0.529396,0.035707,-0.20806,0.0183932,0.0206181,-1.20696,2.68208,-1.96635,0.482653,0,0,0,0,0,0,0,0\n1.25143,0.198719,-0.00226065,0.0071516,-0.000967712,-0.0195028,0.027796,-0.0152482,0.00304013,0.018795,0.0443757,-0.0359919,0.000876143,-0.286412,0.566448,-0.379526,0.0866483,-0.121958,0.122244,0.0690287,-0.0330272,2.4237,-4.86269,3.3279,-0.773391,0,0,0,0,0,0,0,0\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/figure8.py",
    "content": "#!/usr/bin/env python\n\nfrom pathlib import Path\n\nfrom crazyflie_py import Crazyswarm\nfrom crazyflie_py.uav_trajectory import Trajectory\nimport numpy as np\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    traj1 = Trajectory()\n    traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv')\n\n    # enable logging\n    allcfs.setParam('usd.logging', 1)\n\n    TRIALS = 1\n    TIMESCALE = 1.0\n    for i in range(TRIALS):\n        for cf in allcfs.crazyflies:\n            cf.uploadTrajectory(0, 0, traj1)\n\n        allcfs.takeoff(targetHeight=1.0, duration=2.0)\n        timeHelper.sleep(2.5)\n        for cf in allcfs.crazyflies:\n            pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0])\n            cf.goTo(pos, 0, 2.0)\n        timeHelper.sleep(2.5)\n\n        allcfs.startTrajectory(0, timescale=TIMESCALE)\n        timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)\n        # allcfs.startTrajectory(0, timescale=TIMESCALE, reverse=True)\n        # timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)\n\n        allcfs.land(targetHeight=0.06, duration=2.0)\n        timeHelper.sleep(3.0)\n\n    # disable logging\n    allcfs.setParam('usd.logging', 0)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/goto_unicast.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\nimport numpy as np\n\n\ndef main():\n    Z = 0.5\n\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    for cf in allcfs.crazyflies:\n        cf.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n\n    relative_positions = [\n        [0, 0, Z],\n        [0.5, 0, Z],\n        [0.5, 0.5, Z],\n        [0.0, 0.5, Z],\n        [0.0, 0.0, Z],\n    ]\n\n    for relative_position in relative_positions:\n        for cf in allcfs.crazyflies:\n            pos = np.array(cf.initialPosition) + np.array(relative_position)\n            cf.goTo(pos, 0, 3.0)\n        timeHelper.sleep(3.5)\n\n    for cf in allcfs.crazyflies:\n        cf.land(targetHeight=0.02, duration=1.0+Z)\n    timeHelper.sleep(1.0+Z)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/group_mask.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    # set group mask to enable group 1 and 4 (one by one)\n    for cf in allcfs.crazyflies:\n        cf.setGroupMask(0b00001001)\n\n    print('Takeoff with a different mask (2) -> nothing should happen')\n    allcfs.takeoff(targetHeight=0.5, duration=3.0, groupMask=2)\n    timeHelper.sleep(3)\n\n    print('Takeoff with correct mask (1) -> should work')\n    allcfs.takeoff(targetHeight=0.5, duration=3.0, groupMask=1)\n    timeHelper.sleep(3)\n    allcfs.land(targetHeight=0.02, duration=3.0)\n    timeHelper.sleep(3)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/hello_world.py",
    "content": "\"\"\"Takeoff-hover-land for one CF. Useful to validate hardware config.\"\"\"\n\nfrom crazyflie_py import Crazyswarm\n\n\nTAKEOFF_DURATION = 2.5\nHOVER_DURATION = 5.0\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    cf = swarm.allcfs.crazyflies[0]\n\n    cf.takeoff(targetHeight=1.0, duration=TAKEOFF_DURATION)\n    timeHelper.sleep(TAKEOFF_DURATION + HOVER_DURATION)\n    cf.land(targetHeight=0.04, duration=2.5)\n    timeHelper.sleep(TAKEOFF_DURATION)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/infinite_flight.py",
    "content": "#!/usr/bin/env python\n\nfrom pathlib import Path\n\nfrom crazyflie_py import Crazyswarm\nfrom crazyflie_py.uav_trajectory import Trajectory\nimport numpy as np\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    traj1 = Trajectory()\n    traj1.loadcsv(Path(__file__).parent / 'data/figure8.csv')\n\n    TIMESCALE = 1.0\n    for cf in allcfs.crazyflies:\n        cf.uploadTrajectory(0, 0, traj1)\n    timeHelper.sleep(1)\n\n    # pm_state : 0 = on battery  1 = charging  2 = charged  3 = low power  4 = shutdown\n    flight_counter = 1\n\n    while True:\n        print('takeoff')\n        allcfs.takeoff(targetHeight=1.0, duration=2.0)\n        timeHelper.sleep(2.5)\n        for cf in allcfs.crazyflies:\n            pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0])\n            cf.goTo(pos, 0, 2.0)\n        timeHelper.sleep(2.5)\n\n        # fly figure8 until battery is low\n        fig8_counter = 0\n        status = allcfs.crazyflies[0].get_status()\n        # while status['battery'] > 3.8:\n        while status['pm_state'] == 0:\n            fig8_counter += 1\n            print(f'starting figure8 number {fig8_counter} of flight number {flight_counter}')\n            allcfs.startTrajectory(0, timescale=TIMESCALE)\n            timeHelper.sleep(traj1.duration * TIMESCALE + 2.0)\n            status = allcfs.crazyflies[0].get_status()\n            print(f'pm state : {status[\"pm_state\"]}, battery left : {status[\"battery\"]}')\n            timeHelper.sleep(1)\n\n        # not sure if useful\n        # check if pm = 3 just to be sure, if not abort test\n        if status['pm_state'] != 3:\n            print(f'power state is not 3 (low) but {status[\"pm_state\"]}. Landing and aborting')\n            allcfs.land(targetHeight=0.06, duration=2.0)\n            timeHelper.sleep(3)\n            return 1\n\n        # now that battery is low, we try to land on the pad and see if it's charging\n        allcfs.land(targetHeight=0.06, duration=2.0)\n        timeHelper.sleep(5)\n        status = allcfs.crazyflies[0].get_status()\n\n        # if not charging, take off and land back again until it charges\n        while status['pm_state'] != 1:\n            print('Not charging, retrying')\n            allcfs.takeoff(targetHeight=1.0, duration=2.0)\n            timeHelper.sleep(2.5)\n            for cf in allcfs.crazyflies:\n                pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0])\n            cf.goTo(pos, 0, 2.0)\n            timeHelper.sleep(2.5)\n            allcfs.land(targetHeight=0.06, duration=2.0)\n            timeHelper.sleep(5)\n            status = allcfs.crazyflies[0].get_status()\n\n        # now we wait until the crazyflie is charged\n        # while status['battery'] < 4.1:\n        while status['pm_state'] != 2:\n            print(f'Charging in progress, battery at {status[\"battery\"]}V')\n            timeHelper.sleep(60)\n            status = allcfs.crazyflies[0].get_status()\n            # check if it's still charging ###not sure if this check is useful\n            if status['pm_state'] != 1:\n                print(f'charging interrupted, pm state : {status[\"pm_state\"]}')\n\n        print('Charging finished, time to fly again')\n        flight_counter += 1\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/multi_trajectory.py",
    "content": "#!/usr/bin/env python\n\nfrom pathlib import Path\n\nfrom crazyflie_py import Crazyswarm\nfrom crazyflie_py.uav_trajectory import Trajectory\nimport numpy as np\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n    trajs = []\n    n = 2  # number of distinct trajectories\n\n    # enable logging\n    allcfs.setParam('usd.logging', 1)\n\n    for i in range(n):\n        traj = Trajectory()\n        traj.loadcsv(Path(__file__).parent / f'data/multi_trajectory/traj{i}.csv')\n        trajs.append(traj)\n\n    TRIALS = 1\n    TIMESCALE = 1.0\n    for i in range(TRIALS):\n        for idx, cf in enumerate(allcfs.crazyflies):\n            cf.uploadTrajectory(0, 0, trajs[idx % len(trajs)])\n\n        allcfs.takeoff(targetHeight=1.0, duration=2.0)\n        timeHelper.sleep(3.0)\n        for cf in allcfs.crazyflies:\n            pos = np.array(cf.initialPosition) + np.array([0.0, 0.0, 1.0])\n            cf.goTo(pos, 0, 2.0)\n        timeHelper.sleep(2.5)\n\n        allcfs.startTrajectory(0, timescale=TIMESCALE)\n        timeHelper.sleep(max([t.duration for t in trajs]) * TIMESCALE + 2.0)\n\n        allcfs.land(targetHeight=0.06, duration=2.0)\n        timeHelper.sleep(3.0)\n\n    # disable logging\n    allcfs.setParam('usd.logging', 0)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/nice_hover.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\nimport numpy as np\n\n\ndef main():\n    Z = 1.0\n\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    for cf in allcfs.crazyflies:\n        pos = np.array(cf.initialPosition) + np.array([0, 0, Z])\n        cf.goTo(pos, 0, 1.0)\n\n    print('press button to continue...')\n    swarm.input.waitUntilButtonPressed()\n\n    allcfs.land(targetHeight=0.02, duration=1.0+Z)\n    timeHelper.sleep(1.0+Z)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/set_param.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\n\n\ndef main():\n    # In case of key errors, wait for all the crazyflies to be fully connected\n    # before running the script.\n    # Also 'query_all_values_on_connect' should be set to True in the server.yaml file.\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    # disable LED (one by one)\n    for cf in allcfs.crazyflies:\n        cf.setParam('led.bitmask', 128)\n        timeHelper.sleep(1.0)\n        if cf.getParam('led.bitmask') != 128:\n            print('LED is not disabled!')\n\n    timeHelper.sleep(2.0)\n\n    # enable LED (broadcast)\n    allcfs.setParam('led.bitmask', 0)\n    timeHelper.sleep(5.0)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/crazyflie_examples/swap.py",
    "content": "#!/usr/bin/env python\n\nfrom crazyflie_py import Crazyswarm\nimport numpy as np\n\n\ndef main():\n    Id2 = 231\n    Id1 = 5\n    Pos1 = np.array([0.0, -0.2, 0.0])\n    Pos2 = np.array([0.0, 0.2, 0.0])\n    Height1 = 0.4\n    Height2 = 0.5\n    swapTime = 3\n\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    allcfs.takeoff(targetHeight=Height1, duration=3.0)\n    timeHelper.sleep(3.5)\n\n    # go to initial positions\n    allcfs.crazyfliesById[Id1].goTo(Pos1 + np.array([0, 0, Height1]), 0, 3.0)\n    allcfs.crazyfliesById[Id2].goTo(Pos2 + np.array([0, 0, Height2]), 0, 3.0)\n    timeHelper.sleep(3.5)\n\n    # swap 1\n    allcfs.crazyfliesById[Id1].goTo(Pos2 + np.array([0, 0, Height1]), 0, swapTime)\n    allcfs.crazyfliesById[Id2].goTo(Pos1 + np.array([0, 0, Height2]), 0, swapTime)\n    timeHelper.sleep(swapTime + 1.5)\n\n    # swap 2\n    allcfs.crazyfliesById[Id1].goTo(Pos1 + np.array([0, 0, Height1]), 0, swapTime)\n    allcfs.crazyfliesById[Id2].goTo(Pos2 + np.array([0, 0, Height2]), 0, swapTime)\n    timeHelper.sleep(swapTime + 1.5)\n\n    allcfs.land(targetHeight=0.02, duration=3.0)\n    timeHelper.sleep(3.5)\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_examples/data/map.yaml",
    "content": "image: map.pgm\nmode: trinary\nresolution: 0.1\norigin: [-1.99, -1.77, 0]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.25"
  },
  {
    "path": "crazyflie_examples/launch/keyboard_velmux_launch.py",
    "content": "import os\n\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n\n    crazyflie = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource([os.path.join(\n            get_package_share_directory('crazyflie'), 'launch'),\n            '/launch.py']),\n        launch_arguments={\n            'backend': 'cflib',\n            'gui': 'false',\n            'teleop': 'false',\n            'mocap': 'false',\n            }.items())\n\n    return LaunchDescription([\n        crazyflie,\n        Node(\n            package='crazyflie',\n            executable='vel_mux.py',\n            name='vel_mux',\n            output='screen',\n            parameters=[{'hover_height': 0.3},\n                        {'incoming_twist_topic': '/cmd_vel'},\n                        {'robot_prefix': '/cf231'}]\n        ),\n    ])\n"
  },
  {
    "path": "crazyflie_examples/launch/launch.py",
    "content": "import os\n\nfrom ament_index_python.packages import get_package_share_directory\n\n\nfrom launch import LaunchDescription\nfrom launch.actions import DeclareLaunchArgument\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nfrom launch.substitutions import LaunchConfiguration, PythonExpression\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n    script = LaunchConfiguration('script')\n    backend = LaunchConfiguration('backend')\n\n    script_launch_arg = DeclareLaunchArgument(\n        'script'\n    )\n\n    backend_launch_arg = DeclareLaunchArgument(\n        'backend',\n        default_value='cpp'\n    )\n\n    crazyflie = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource([os.path.join(\n            get_package_share_directory('crazyflie'), 'launch'),\n            '/launch.py']),\n        launch_arguments={\n            'backend': backend,\n            }.items()\n    )\n\n    example_node = Node(\n        package='crazyflie_examples',\n        executable=script,\n        name=script,\n        parameters=[{\n            'use_sim_time': PythonExpression([\"'\", backend, \"' == 'sim'\"]),\n        }]\n    )\n\n    return LaunchDescription([\n        script_launch_arg,\n        backend_launch_arg,\n        crazyflie,\n        example_node\n    ])\n"
  },
  {
    "path": "crazyflie_examples/launch/multiranger_mapping_launch.py",
    "content": "import os\n\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n\n    return LaunchDescription(\n        [\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    [\n                        os.path.join(\n                            get_package_share_directory('crazyflie'), 'launch'\n                        ),\n                        '/launch.py',\n                    ]\n                ),\n                launch_arguments={\n                    'backend': 'cflib',\n                    'gui': 'false',\n                    'teleop': 'false',\n                    'mocap': 'false',\n                }.items(),\n            ),\n            Node(\n                package='crazyflie',\n                executable='vel_mux.py',\n                name='vel_mux',\n                output='screen',\n                parameters=[\n                    {'hover_height': 0.3},\n                    {'incoming_twist_topic': '/cmd_vel'},\n                    {'robot_prefix': '/cf231'},\n                ],\n            ),\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    os.path.join(\n                        get_package_share_directory('slam_toolbox'),\n                        'launch/online_async_launch.py',\n                    )\n                ),\n                launch_arguments={\n                    'slam_params_file': os.path.join(\n                        get_package_share_directory('crazyflie_examples'),\n                        'config/slam_params.yaml',\n                    ),\n                    'use_sim_time': 'False',\n                }.items(),\n            ),\n        ]\n    )\n"
  },
  {
    "path": "crazyflie_examples/launch/multiranger_nav2_launch.py",
    "content": "import os\n\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n\n    map_name = 'map'\n\n    return LaunchDescription(\n        [\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    [\n                        os.path.join(\n                            get_package_share_directory('crazyflie'), 'launch'\n                        ),\n                        '/launch.py',\n                    ]\n                ),\n                launch_arguments={\n                    'backend': 'cflib',\n                    'gui': 'false',\n                    'teleop': 'false',\n                    'mocap': 'false',\n                }.items(),\n            ),\n            Node(\n                package='crazyflie',\n                executable='vel_mux.py',\n                name='vel_mux',\n                output='screen',\n                parameters=[\n                    {'hover_height': 0.3},\n                    {'incoming_twist_topic': '/cmd_vel'},\n                    {'robot_prefix': '/cf231'},\n                ],\n            ),\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    os.path.join(\n                        get_package_share_directory('slam_toolbox'),\n                        'launch/online_async_launch.py',\n                    )\n                ),\n                launch_arguments={\n                    'slam_params_file': os.path.join(\n                        get_package_share_directory('crazyflie_examples'),\n                        'config/slam_params.yaml',\n                    ),\n                    'use_sim_time': 'False',\n                }.items(),\n            ),\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    os.path.join(\n                        get_package_share_directory('nav2_bringup'),\n                        'launch/bringup_launch.py',\n                    )\n                ),\n                launch_arguments={\n                    'slam': 'False',\n                    'use_sim_time': 'False',\n                    'map': get_package_share_directory('crazyflie_examples')\n                    + '/data/'\n                    + map_name\n                    + '.yaml',\n                    'params_file': os.path.join(\n                        get_package_share_directory('crazyflie_examples'),\n                        'config/nav2_params.yaml',\n                    ),\n                    'autostart': 'True',\n                    'use_composition': 'True',\n                    'transform_publish_period': '0.02',\n                }.items(),\n            ),\n            IncludeLaunchDescription(\n                PythonLaunchDescriptionSource(\n                    os.path.join(\n                        get_package_share_directory('nav2_bringup'),\n                        'launch/rviz_launch.py',\n                    )\n                ),\n                launch_arguments={\n                    'rviz_config': os.path.join(\n                        get_package_share_directory('nav2_bringup'),\n                        'rviz',\n                        'nav2_default_view.rviz',\n                    )\n                }.items(),\n            ),\n        ]\n    )\n"
  },
  {
    "path": "crazyflie_examples/launch/multiranger_simple_mapper_launch.py",
    "content": "import os\n\nfrom ament_index_python.packages import get_package_share_directory\nfrom launch import LaunchDescription\nfrom launch.actions import IncludeLaunchDescription\nfrom launch.launch_description_sources import PythonLaunchDescriptionSource\nfrom launch_ros.actions import Node\n\n\ndef generate_launch_description():\n\n    crazyflie = IncludeLaunchDescription(\n        PythonLaunchDescriptionSource(\n            [\n                os.path.join(get_package_share_directory('crazyflie'), 'launch'),\n                '/launch.py',\n            ]\n        ),\n        launch_arguments={\n            'backend': 'cflib',\n            'gui': 'false',\n            'teleop': 'false',\n            'mocap': 'false',\n        }.items(),\n    )\n\n    crazyflie_name = '/cf231'\n\n    return LaunchDescription(\n        [\n            crazyflie,\n            Node(\n                package='crazyflie',\n                executable='vel_mux.py',\n                name='vel_mux',\n                output='screen',\n                parameters=[\n                    {'hover_height': 0.3},\n                    {'incoming_twist_topic': '/cmd_vel'},\n                    {'robot_prefix': crazyflie_name},\n                ],\n            ),\n            Node(\n                package='crazyflie',\n                executable='simple_mapper_multiranger.py',\n                name='simple_mapper_multiranger',\n                output='screen',\n                parameters=[{'robot_prefix': crazyflie_name}],\n            ),\n        ]\n    )\n"
  },
  {
    "path": "crazyflie_examples/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>crazyflie_examples</name>\n  <version>1.0.3</version>\n  <description>Examples for the Crazyswarm2 ROS stack</description>\n  <maintainer email=\"hoenig@tu-berlin.de\">Wolfgang Hönig</maintainer>\n  <maintainer email=\"kimberleymcguire@gmail.com\">Kimberly McGuire</maintainer>\n  <license>MIT</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <buildtool_depend>ament_cmake_python</buildtool_depend>\n\n  <depend>rclpy</depend>\n  <depend>crazyflie_py</depend>\n\n  <test_depend>ament_copyright</test_depend>\n  <test_depend>ament_flake8</test_depend>\n  <test_depend>ament_pep257</test_depend>\n  <test_depend>python3-pytest</test_depend>\n  <test_depend>ament_cmake_pytest</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "crazyflie_examples/resource/crazyflie_examples",
    "content": ""
  },
  {
    "path": "crazyflie_examples/setup.cfg",
    "content": "[options.entry_points]\nconsole_scripts =\n    hello_world = crazyflie_examples.hello_world:main\n    nice_hover = crazyflie_examples.nice_hover:main\n    figure8 = crazyflie_examples.figure8:main\n    goto_unicast = crazyflie_examples.goto_unicast:main\n    group_mask = crazyflie_examples.group_mask:main\n    multi_trajectory = crazyflie_examples.multi_trajectory:main\n    cmd_full_state = crazyflie_examples.cmd_full_state:main\n    set_param = crazyflie_examples.set_param:main\n    swap = crazyflie_examples.swap:main\n    infinite_flight = crazyflie_examples.infinite_flight:main\n    arming = crazyflie_examples.arming:main\n"
  },
  {
    "path": "crazyflie_examples/test/test_flake8.py",
    "content": "# Copyright 2017 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_flake8.main import main_with_errors\nimport pytest\n\n\n@pytest.mark.flake8\n@pytest.mark.linter\ndef test_flake8():\n    rc, errors = main_with_errors(argv=[])\n    assert rc == 0, \\\n        'Found %d code style errors / warnings:\\n' % len(errors) + \\\n        '\\n'.join(errors)\n"
  },
  {
    "path": "crazyflie_examples/test/test_pep257.py",
    "content": "# Copyright 2015 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_pep257.main import main\nimport pytest\n\n\n@pytest.mark.linter\n@pytest.mark.pep257\ndef test_pep257():\n    rc = main(argv=['.', 'test'])\n    assert rc == 0, 'Found code style errors / warnings'\n"
  },
  {
    "path": "crazyflie_interfaces/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package crazyflie_interfaces\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.0.3 (2025-07-09)\n------------------\n* add more dependencies to fix the binary build\n* Improve package.xml (separate maintainer tags, update year)\n* Contributors: Kimberly N. McGuire\n\n1.0.2 (2025-07-02)\n------------------\n* Add additional dependencies to address ROSfarm build failures\n* Contributors: Wolfgang Hönig\n\n1.0.1 (2025-06-30)\n------------------\n* Fix build errors and dependencies on ROS Build Farm\n* Contributors: Kimberly N. McGuire, Wolfgang Hönig\n\n1.0.0 (2025-06-21)\n------------------\n* First official release.\n* Contributors: Khaled Wahba, Kimberly McGuire, Wolfgang Hönig, phanfeld\n"
  },
  {
    "path": "crazyflie_interfaces/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(crazyflie_interfaces)\n\n# Default to C++14\nif(NOT CMAKE_CXX_STANDARD)\n  set(CMAKE_CXX_STANDARD 14)\nendif()\nif(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES \"Clang\")\n  add_compile_options(-Wall -Wextra -Wpedantic)\nendif()\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(builtin_interfaces REQUIRED)\nfind_package(geometry_msgs REQUIRED)\nfind_package(std_msgs REQUIRED)\n\nfind_package(rosidl_default_generators REQUIRED)\n\nrosidl_generate_interfaces(${PROJECT_NAME}\n  \"msg/ConnectionStatistics.msg\"\n  \"msg/ConnectionStatisticsArray.msg\"\n  \"msg/FullState.msg\"\n  \"msg/LogDataGeneric.msg\"\n  \"msg/Hover.msg\"\n  \"msg/LogBlock.msg\"\n  \"msg/Position.msg\"\n  \"msg/Status.msg\"\n  \"msg/TrajectoryPolynomialPiece.msg\"\n  \"msg/VelocityWorld.msg\"\n  \"srv/GoTo.srv\"\n  \"srv/Land.srv\"\n  \"srv/NotifySetpointsStop.srv\"\n  \"srv/SetGroupMask.srv\"\n  \"srv/StartTrajectory.srv\"\n  \"srv/Stop.srv\"\n  \"srv/Takeoff.srv\"\n  \"srv/UpdateParams.srv\"\n  \"srv/UploadTrajectory.srv\"\n  \"srv/RemoveLogging.srv\"\n  \"srv/AddLogging.srv\"\n  \"srv/Arm.srv\"\n  DEPENDENCIES builtin_interfaces geometry_msgs std_msgs \n  ADD_LINTER_TESTS\n)\n\n\nament_export_dependencies(rosidl_default_runtime)\n\nament_package()\n"
  },
  {
    "path": "crazyflie_interfaces/msg/ConnectionStatistics.msg",
    "content": "string uri\nuint64 sent_count\nuint64 sent_ping_count\nuint64 receive_count\nuint64 enqueued_count\nuint64 ack_count\n"
  },
  {
    "path": "crazyflie_interfaces/msg/ConnectionStatisticsArray.msg",
    "content": "std_msgs/Header header\nConnectionStatistics[] stats\n"
  },
  {
    "path": "crazyflie_interfaces/msg/FullState.msg",
    "content": "std_msgs/Header header\ngeometry_msgs/Pose pose\ngeometry_msgs/Twist twist\ngeometry_msgs/Vector3 acc\n"
  },
  {
    "path": "crazyflie_interfaces/msg/Hover.msg",
    "content": "std_msgs/Header header\nfloat32 vx\nfloat32 vy\nfloat32 yaw_rate\nfloat32 z_distance\n"
  },
  {
    "path": "crazyflie_interfaces/msg/LogBlock.msg",
    "content": "string topic_name\nint16 frequency\nstring[] variables\n"
  },
  {
    "path": "crazyflie_interfaces/msg/LogDataGeneric.msg",
    "content": "std_msgs/Header header  # Header including the ROS 2 timestamp when the log data was received\nuint32 timestamp        # on-board timestamp from the STM32 (in ms)\nfloat32[] values        # converted values, in the order as specified for the log block\n"
  },
  {
    "path": "crazyflie_interfaces/msg/Position.msg",
    "content": "std_msgs/Header header\nfloat32 x\nfloat32 y\nfloat32 z\nfloat32 yaw\n"
  },
  {
    "path": "crazyflie_interfaces/msg/Status.msg",
    "content": "\n# Constants\nuint16 SUPERVISOR_INFO_CAN_BE_ARMED = 1\nuint16 SUPERVISOR_INFO_IS_ARMED     = 2\nuint16 SUPERVISOR_INFO_AUTO_ARM     = 4\nuint16 SUPERVISOR_INFO_CAN_FLY      = 8\nuint16 SUPERVISOR_INFO_IS_FLYING    = 16\nuint16 SUPERVISOR_INFO_IS_TUMBLED   = 32\nuint16 SUPERVISOR_INFO_IS_LOCKED    = 64\n\nuint8 PM_STATE_BATTERY   = 0\nuint8 PM_STATE_CHARGING  = 1\nuint8 PM_STATE_CHARGED   = 2\nuint8 PM_STATE_LOW_POWER = 3\nuint8 PM_STATE_SHUTDOWN  = 4\n\nstd_msgs/Header header\n\n# general status\nuint16 supervisor_info # Bitfield, see SUPERVISOR_INFO for individual bits\n\n# battery related\nfloat32 battery_voltage  # internal battery voltage [V]\nuint8 pm_state # See PM_STATE_* for potential values\n\n# radio related\nuint8 rssi      # latest radio signal strength indicator [dBm]\nuint32 num_rx_broadcast  # number of received broadcast packets during the last period\nuint32 num_tx_broadcast  # number of broadcast packets sent during the last period\nuint32 num_rx_unicast    # number of received unicast packets during the last period\nuint32 num_tx_unicast    # number of unicast packets sent during the last period\nuint16 latency_unicast   # latency (in ms) for unicast packets\n"
  },
  {
    "path": "crazyflie_interfaces/msg/TrajectoryPolynomialPiece.msg",
    "content": "#\n\nfloat32[] poly_x\nfloat32[] poly_y\nfloat32[] poly_z\nfloat32[] poly_yaw\nbuiltin_interfaces/Duration duration"
  },
  {
    "path": "crazyflie_interfaces/msg/VelocityWorld.msg",
    "content": "std_msgs/Header header\ngeometry_msgs/Vector3 vel\nfloat32 yaw_rate"
  },
  {
    "path": "crazyflie_interfaces/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>crazyflie_interfaces</name>\n  <version>1.0.3</version>\n  <description>Interfaces for Crazyswarm2 package.</description>\n  <maintainer email=\"hoenig@tu-berlin.de\">Wolfgang Hönig</maintainer>\n  <maintainer email=\"kimberleymcguire@gmail.com\">Kimberly N. McGuire</maintainer>\n  <license>MIT</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <buildtool_depend>rosidl_default_generators</buildtool_depend>\n\n  <build_depend>builtin_interfaces</build_depend>\n  <build_depend>rosidl_default_generators</build_depend>\n\n  <depend>geometry_msgs</depend>\n  <depend>std_srvs</depend>\n  <depend>std_msgs</depend>\n\n  <exec_depend>builtin_interfaces</exec_depend>\n  <exec_depend>rosidl_default_runtime</exec_depend>\n\n  <member_of_group>rosidl_interface_packages</member_of_group>\n\n  <!-- For build failures on humble, see https://answers.ros.org/question/416825/ -->\n  <test_depend>ament_cmake_cppcheck</test_depend>\n\n  <test_depend>ament_lint_auto</test_depend>\n  <test_depend>ament_lint_common</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "crazyflie_interfaces/srv/AddLogging.srv",
    "content": "string topic_name\nint32 frequency\nstring[] vars\n---\nbool success\n"
  },
  {
    "path": "crazyflie_interfaces/srv/Arm.srv",
    "content": "bool arm\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/GoTo.srv",
    "content": "uint8 group_mask\nbool relative\ngeometry_msgs/Point goal\nfloat32 yaw # deg\nbuiltin_interfaces/Duration duration\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/Land.srv",
    "content": "uint8 group_mask\nfloat32 height\nbuiltin_interfaces/Duration duration\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/NotifySetpointsStop.srv",
    "content": "uint8 group_mask\nuint32 remain_valid_millisecs\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/RemoveLogging.srv",
    "content": "string topic_name\n---\nbool success\n"
  },
  {
    "path": "crazyflie_interfaces/srv/SetGroupMask.srv",
    "content": "uint8 group_mask\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/StartTrajectory.srv",
    "content": "uint8 group_mask\nuint8 trajectory_id\nfloat32 timescale\nbool reversed\nbool relative\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/Stop.srv",
    "content": "uint8 group_mask\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/Takeoff.srv",
    "content": "uint8 group_mask\nfloat32 height\nbuiltin_interfaces/Duration duration\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/UpdateParams.srv",
    "content": "string[] params\n---\n"
  },
  {
    "path": "crazyflie_interfaces/srv/UploadTrajectory.srv",
    "content": "uint8 trajectory_id\nuint32 piece_offset\nTrajectoryPolynomialPiece[] pieces\n---\n"
  },
  {
    "path": "crazyflie_py/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package crazyflie_py\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.0.3 (2025-07-09)\n------------------\n* Improve package.xml (separate maintainer tags, update year)\n* Contributors: Kimberly N. McGuire\n\n1.0.2 (2025-07-02)\n------------------\n\n1.0.1 (2025-06-30)\n------------------\n\n\n1.0.0 (2025-06-21)\n------------------\n* First official release.\n* Contributors: Julien Thevenoz, Kimberly McGuire, Kimberly N. McGuire, Wolfgang Hönig\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/__init__.py",
    "content": "from .crazyswarm_py import Crazyswarm\n\n__all__ = ['Crazyswarm']\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/crazyflie.py",
    "content": "#!/usr/bin/env python\n\nfrom collections import defaultdict\n\n# import sys\n# import rospy\n# import time\n# import tf_conversions\n# from std_srvs.srv import Empty\n# import std_msgs\n# from crazyswarm.srv import *\n# from crazyswarm.msg import TrajectoryPolynomialPiece, FullState, Position, VelocityWorld\n# from tf import TransformListener\n# from .visualizer import visNull\n\n\nfrom crazyflie_interfaces.msg import FullState, Position, Status, TrajectoryPolynomialPiece\nfrom crazyflie_interfaces.srv import Arm, GoTo, Land, \\\n    NotifySetpointsStop, StartTrajectory, Takeoff, UploadTrajectory\nfrom geometry_msgs.msg import Point, PoseStamped\nimport numpy as np\nfrom rcl_interfaces.msg import Parameter, ParameterType, ParameterValue\nfrom rcl_interfaces.srv import DescribeParameters, GetParameters, ListParameters, SetParameters\n\nimport rclpy\nimport rclpy.node\nimport rowan\nfrom std_srvs.srv import Empty\n\n\ndef arrayToGeometryPoint(a):\n    result = Point()\n    result.x = a[0]\n    result.y = a[1]\n    result.z = a[2]\n    return result\n\n\nclass TimeHelper:\n    \"\"\"\n    Object containing all time-related functionality.\n\n    This class mainly exists to support both real hardware and (potentially\n    faster or slower than realtime) simulation with the same script.\n    When running on real hardware, this class uses ROS time functions.\n    The simulation equivalent does not depend on ROS.\n\n    Attributes:\n        visualizer: No-op object conforming to the Visualizer API used in\n            simulation scripts. Maintains the property that scripts should not\n            know/care if they are running in simulation or not.\n\n    \"\"\"\n\n    def __init__(self, node):\n        self.node = node\n        # self.rosRate = None\n        self.rateHz = None\n        self.nextTime = None\n        # self.visualizer = visNull.VisNull()\n\n    def time(self):\n        \"\"\"Return current time in seconds.\"\"\"\n        return self.node.get_clock().now().nanoseconds / 1e9\n\n    def sleep(self, duration):\n        \"\"\"Sleeps for the provided duration in seconds.\"\"\"\n        start = self.time()\n        end = start + duration\n        while self.time() < end:\n            rclpy.spin_once(self.node, timeout_sec=0)\n\n    def sleepForRate(self, rateHz):\n        \"\"\"Sleep so that, if called in a loop, executes at specified rate.\"\"\"\n        # Note: The following ROS 2 construct cannot easily be used, because in ROS 2\n        #       there is no implicit threading anymore. Thus, the rosRate.sleep() call\n        #       is blocking. Instead, we simulate the rate behavior ourselves.\n        # if self.rosRate is None or self.rateHz != rateHz:\n        #     self.rosRate = self.node.create_rate(rateHz)\n        #     self.rateHz = rateHz\n        # self.rosRate.sleep()\n        if self.nextTime is None or self.rateHz != rateHz:\n            self.rateHz = rateHz\n            self.nextTime = self.time() + 1.0 / rateHz\n        while self.time() < self.nextTime:\n            rclpy.spin_once(self.node, timeout_sec=0)\n        self.nextTime += 1.0 / rateHz\n\n    def isShutdown(self):\n        \"\"\"Return True if the script should abort, e.g. from Ctrl-C.\"\"\"\n        return not rclpy.ok()\n\n\nclass Crazyflie:\n    \"\"\"\n    Object representing a single robot.\n\n    The bulk of the module's functionality is contained in this class.\n    \"\"\"\n\n    def __init__(self, node, cfname, paramTypeDict):\n        \"\"\"\n        Construct Crazyflie.\n\n        Args:\n            node: ROS node reference.\n            cfname (string): Name of the robot names[ace].\n            paramTypeDict: dictionary of the parameter types.\n\n        \"\"\"\n        prefix = '/' + cfname\n        self.prefix = prefix\n        self.node = node\n\n        # self.tf = tf\n\n        self.emergencyService = node.create_client(Empty, prefix + '/emergency')\n        self.emergencyService.wait_for_service()\n        self.takeoffService = node.create_client(Takeoff, prefix + '/takeoff')\n        self.takeoffService.wait_for_service()\n        self.landService = node.create_client(Land, prefix + '/land')\n        self.landService.wait_for_service()\n        # # rospy.wait_for_service(prefix + '/stop')\n        # # self.stopService = rospy.ServiceProxy(prefix + '/stop', Stop)\n        self.goToService = node.create_client(GoTo, prefix + '/go_to')\n        self.goToService.wait_for_service()\n        self.uploadTrajectoryService = node.create_client(\n            UploadTrajectory, prefix + '/upload_trajectory')\n        self.uploadTrajectoryService.wait_for_service()\n        self.startTrajectoryService = node.create_client(\n            StartTrajectory, prefix + '/start_trajectory')\n        self.startTrajectoryService.wait_for_service()\n        self.notifySetpointsStopService = node.create_client(\n            NotifySetpointsStop, prefix + '/notify_setpoints_stop')\n        self.notifySetpointsStopService.wait_for_service()\n        self.armService = node.create_client(\n            Arm, prefix + '/arm')\n        # self.armService.wait_for_service()\n        self.setParamsService = node.create_client(\n            SetParameters, '/crazyflie_server/set_parameters')\n        self.setParamsService.wait_for_service()\n        self.statusSubscriber = node.create_subscription(\n            Status, f'{self.prefix}/status', self.status_topic_callback, 10)\n        self.status = {}\n\n        self.poseStampedSubscriber = node.create_subscription(\n            PoseStamped, f'{self.prefix}/pose', self.poseStamped_topic_callback, 10)\n        self.poseStamped = {}\n        self.pose = {}\n        self.position = [0.0, 0.0, 0.0]\n\n        # Query some settings\n        self.getParamsService = node.create_client(\n            GetParameters, '/crazyflie_server/get_parameters')\n        self.getParamsService.wait_for_service()\n        req = GetParameters.Request()\n        req.names = ['robots.{}.initial_position'.format(cfname), 'robots.{}.uri'.format(cfname)]\n        future = self.getParamsService.call_async(req)\n        while rclpy.ok():\n            rclpy.spin_once(node)\n            if future.done():\n                response = future.result()\n                # extract initial position\n                if response.values[0].type == ParameterType.PARAMETER_INTEGER_ARRAY:\n                    self.initialPosition = np.array(response.values[0].integer_array_value)\n                elif response.values[0].type == ParameterType.PARAMETER_DOUBLE_ARRAY:\n                    self.initialPosition = np.array(response.values[0].double_array_value)\n                else:\n                    assert False\n\n                # extract uri\n                self.uri = response.values[1].string_value\n\n                break\n\n        self.paramTypeDict = paramTypeDict\n\n        self.cmdFullStatePublisher = node.create_publisher(\n            FullState, prefix + '/cmd_full_state', 1)\n        self.cmdFullStateMsg = FullState()\n        self.cmdFullStateMsg.header.frame_id = '/world'\n\n        # self.cmdStopPublisher = rospy.Publisher(\n        #   prefix + '/cmd_stop', std_msgs.msg.Empty, queue_size=1)\n\n        # self.cmdVelPublisher = rospy.Publisher(\n        #   prefix + '/cmd_vel', geometry_msgs.msg.Twist, queue_size=1)\n\n        self.cmdPositionPublisher = node.create_publisher(\n            Position, prefix + '/cmd_position', 1)\n        self.cmdPositionMsg = Position()\n        self.cmdPositionMsg.header.frame_id = '/world'\n\n        # self.cmdVelocityWorldPublisher = rospy.Publisher(\n        #   prefix + '/cmd_velocity_world', VelocityWorld, queue_size=1)\n        # self.cmdVelocityWorldMsg = VelocityWorld()\n        # self.cmdVelocityWorldMsg.header.seq = 0\n        # self.cmdVelocityWorldMsg.header.frame_id = '/world'\n\n    def setGroupMask(self, groupMask):\n        \"\"\"\n        Set the group mask bits for this robot.\n\n        The purpose of groups is to make it possible to trigger an action\n        (for example, executing a previously-uploaded trajectory) on a subset\n        of all robots without needing to send more than one radio packet.\n        This is important to achieve tight, synchronized 'choreography'.\n\n        Up to 8 groups may exist, corresponding to bits in the groupMask byte.\n        When a broadcast command is triggered on the :obj:`CrazyflieServer` object\n        with a groupMask argument, the command only affects those robots whose\n        groupMask has a nonzero bitwise-AND with the command's groupMask.\n        A command with a groupMask of zero applies to all robots regardless of\n        group membership.\n\n        Some individual robot (not broadcast) commands also support groupMask,\n        but it is not especially useful in that case.\n\n        Args:\n        ----\n            groupMask (int): An 8-bit integer representing this robot's\n                membership status in each of the <= 8 possible groups.\n\n        \"\"\"\n        # Note that this requires a recent firmware; older firmware versions\n        #      do not have such a parameter.\n        try:\n            self.setParam('hlCommander.groupmask', groupMask)\n        except KeyError:\n            self.node.get_logger().error('setGroupMask: Your firmware is too old - Please update.')\n\n    # def enableCollisionAvoidance(self, others, ellipsoidRadii):\n    #     \"\"\"Enables onboard collision avoidance.\n\n    #     When enabled, avoids colliding with other Crazyflies by using the\n    #     Buffered Voronoi Cells method [1]. Computation is performed onboard.\n\n    #     Args:\n    #         others (List[Crazyflie]): List of other :obj:`Crazyflie` objects.\n    #             In simulation, collision avoidance is checked only with members\n    #             of this list.  With real hardware, this list is **ignored**, and\n    #             collision avoidance is checked with all other Crazyflies on the\n    #             same radio channel.\n    #         ellipsoidRadii (array-like of float[3]): Radii of collision volume\n    #             ellipsoid in meters.\n    #             The Crazyflie's boundary for collision checking is a tall\n    #             ellipsoid. This accounts for the downwash effect: Due to the\n    #             fast-moving stream of air produced by the rotors, the safe\n    #             distance to pass underneath another rotorcraft is much further\n    #             than the safe distance to pass to the side.\n\n    #     [1] D. Zhou, Wang, Z., Bandyopadhyay, S., and Schwager, M.\n    #         Fast, On-line Collision Avoidance for Dynamic Vehicles using\n    #         Buffered Voronoi Cells.  IEEE Robotics and Automation Letters\n    #         (RA-L), vol. 2, no. 2, pp. 1047 - 1054, 2017.\n    #         https://msl.stanford.edu/fast-line-collision-avoidance-dynamic-vehicles-using-buffered-voronoi-cells\n    #     \"\"\"\n    #     # Set radii before enabling to ensure collision avoidance never\n    #     # observes a wrong radius value.\n    #     self.setParams({\n    #         'colAv/ellipsoidX': float(ellipsoidRadii[0]),\n    #         'colAv/ellipsoidY': float(ellipsoidRadii[1]),\n    #         'colAv/ellipsoidZ': float(ellipsoidRadii[2]),\n    #     })\n    #     self.setParam('colAv/enable', 1)\n\n    # def disableCollisionAvoidance(self):\n    #     \"\"\"Disables onboard collision avoidance.\"\"\"\n    #     self.setParam('colAv/enable', 0)\n\n    def emergency(self):\n        \"\"\"\n        Emergency stop. Cuts power; causes future commands to be ignored.\n\n        This command is useful if the operator determines that the control\n        script is flawed, and that continuing to follow it will cause wrong/\n        self-destructive behavior from the robots. In addition to cutting\n        power to the motors, it ensures that any future commands, both high-\n        level and streaming, will have no effect.\n\n        The only ways to reset the firmware after an emergency stop has occurred\n        are a physical hard reset or an nRF51 Reboot command.\n        \"\"\"\n        req = Empty.Request()\n        self.emergencyService.call_async(req)\n\n    def takeoff(self, targetHeight, duration, groupMask=0):\n        \"\"\"\n        Execute a takeoff - fly straight up, then hover indefinitely.\n\n        Asynchronous command; returns immediately.\n\n        Args:\n        ----\n            targetHeight (float): The z-coordinate at which to hover.\n            duration (float): How long until the height is reached. Seconds.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = Takeoff.Request()\n        req.group_mask = groupMask\n        req.height = targetHeight\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.takeoffService.call_async(req)\n\n    def land(self, targetHeight, duration, groupMask=0):\n        \"\"\"\n        Execute a landing - fly straight down. User must cut power after.\n\n        Asynchronous command; returns immediately.\n\n        Args:\n        ----\n            targetHeight (float): The z-coordinate at which to land. Meters.\n                Usually should be a few centimeters above the initial position\n                to ensure that the controller does not try to penetrate the\n                floor if the mocap coordinate origin is not perfect.\n            duration (float): How long until the height is reached. Seconds.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = Land.Request()\n        req.group_mask = groupMask\n        req.height = targetHeight\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.landService.call_async(req)\n\n    # def stop(self, groupMask = 0):\n    #     \"\"\"Cuts power to the motors when operating in low-level command mode.\n\n    #     Intended for non-emergency scenarios, e.g. landing with the possibility\n    #     of taking off again later. Future low- or high-level commands will\n    #     restart the motors.\n\n    #     Args:\n    #         groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n    #     \"\"\"\n    #     self.stopService(groupMask)\n\n    def goTo(self, goal, yaw, duration, relative=False, groupMask=0):\n        \"\"\"\n        Move smoothly to the goal, then hover indefinitely.\n\n        Asynchronous command; returns immediately.\n\n        Plans a smooth trajectory from the current state to the goal position.\n        Will stop smoothly at the goal with minimal overshoot. If the current\n        state is at hover, the planned trajectory will be a straight line;\n        however, if the current velocity is nonzero, the planned trajectory\n        will be a smooth curve.\n\n        Plans the trajectory by solving for the unique degree-7 polynomial that\n        satisfies the initial conditions of the current position, velocity,\n        and acceleration, and ends at the goal position with zero velocity and\n        acceleration. The jerk (derivative of acceleration) is fixed at zero at\n        both boundary conditions.\n\n        Note: it is the user's responsibility to ensure that the goTo command\n        is feasible. If the duration is too short, the trajectory will require\n        impossible accelerations and velocities. The planner will not correct\n        this, and the failure to achieve the desired states will cause the\n        controller to become unstable.\n\n        Args:\n            goal (iterable of 3 floats): The goal position. Meters.\n            yaw (float): The goal yaw angle (heading). Radians.\n            duration (float): How long until the goal is reached. Seconds.\n            relative (bool): If true, the goal position is interpreted as a\n                relative offset from the current position. Otherwise, the goal\n                position is interpreted as absolute coordintates in the global\n                reference frame.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = GoTo.Request()\n        req.group_mask = groupMask\n        req.relative = relative\n        req.goal = arrayToGeometryPoint(goal)\n        req.yaw = float(yaw)\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.goToService.call_async(req)\n\n    def uploadTrajectory(self, trajectoryId, pieceOffset, trajectory):\n        \"\"\"\n        Upload a piecewise polynomial trajectory for later execution.\n\n        See uav_trajectory.py for more information about piecewise polynomial\n        trajectories.\n\n        Args:\n        ----\n            trajectoryId (int): ID number of this trajectory. Multiple\n                trajectories can be uploaded. TODO: what is the maximum ID?\n            pieceOffset (int): TODO(whoenig): explain this.\n            trajectory (:obj:`pycrazyswarm.uav_trajectory.Trajectory`): Trajectory object.\n\n        \"\"\"\n        pieces = []\n        for poly in trajectory.polynomials:\n            piece = TrajectoryPolynomialPiece()\n            piece.duration = rclpy.duration.Duration(seconds=poly.duration).to_msg()\n            piece.poly_x = poly.px.p.tolist()\n            piece.poly_y = poly.py.p.tolist()\n            piece.poly_z = poly.pz.p.tolist()\n            piece.poly_yaw = poly.pyaw.p.tolist()\n            pieces.append(piece)\n        req = UploadTrajectory.Request()\n        req.trajectory_id = trajectoryId\n        req.piece_offset = pieceOffset\n        req.pieces = pieces\n        future = self.uploadTrajectoryService.call_async(req)\n        while rclpy.ok():\n            rclpy.spin_once(self.node)\n            if future.done():\n                break\n\n    def startTrajectory(self, trajectoryId,\n                        timescale=1.0, reverse=False,\n                        relative=True, groupMask=0):\n        \"\"\"\n        Begin executing a previously uploaded trajectory.\n\n        Asynchronous command; returns immediately.\n\n        Args:\n        ----\n            trajectoryId (int): ID number as given to :meth:`uploadTrajectory()`.\n            timescale (float): Scales the trajectory duration by this factor.\n                For example if timescale == 2.0, the trajectory will take twice\n                as long to execute as the nominal duration.\n            reverse (bool): If true, executes the trajectory backwards in time.\n            relative (bool): If true (default), the position of the trajectory\n                is shifted such that it begins at the current position setpoint.\n                This is usually the desired behavior.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = StartTrajectory.Request()\n        req.group_mask = groupMask\n        req.trajectory_id = trajectoryId\n        req.timescale = timescale\n        req.reversed = reverse\n        req.relative = relative\n        self.startTrajectoryService.call_async(req)\n\n    def notifySetpointsStop(self, remainValidMillisecs=100, groupMask=0):\n        \"\"\"\n        Informs that streaming low-level setpoint packets are about to stop.\n\n        Streaming setpoints are :meth:`cmdVelocityWorld`, :meth:`cmdFullState`,\n        and so on. For safety purposes, they normally preempt onboard high-level\n        commands such as :meth:`goTo`.\n\n        Once preempted, the Crazyflie will not switch back to high-level\n        commands (or other behaviors determined by onboard planning/logic) until\n        a significant amount of time has elapsed where no low-level setpoint\n        was received.\n\n        This command short-circuits that waiting period to a user-chosen time.\n        It should be called after sending the last low-level setpoint, and\n        before sending any high-level command.\n\n        A common use case is to execute the :meth:`land` command after using\n        streaming setpoint modes.\n\n        Args:\n            remainValidMillisecs (int): Number of milliseconds that the last\n                streaming setpoint should be followed before reverting to the\n                onboard-determined behavior. May be longer e.g. if one radio\n                is controlling many robots.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = NotifySetpointsStop.Request()\n        req.remain_valid_millisecs = remainValidMillisecs\n        req.group_mask = groupMask\n        self.notifySetpointsStopService.call_async(req)\n\n    def arm(self, arm=True):\n        \"\"\"\n        Arms the quadrotor.\n\n        For a brushless or Bolt-based drone the motors start spinning and flight\n        is enabled.\n\n        Args:\n            arm (boolean): True if the motors should be armed, False otherwise.\n\n        \"\"\"\n        req = Arm.Request()\n        req.arm = arm\n        self.armService.call_async(req)\n\n    # def position(self):\n    #     \"\"\"Returns the last true position measurement from motion capture.\n\n    #     If at least one position measurement for this robot has been received\n    #     from the motion capture system since startup, this function returns\n    #     immediately with the most recent measurement. However, if **no**\n    #     position measurements have been received, it blocks until the first\n    #     one arrives.\n\n    #     Returns:\n    #         position (np.array[3]): Current position. Meters.\n    #     \"\"\"\n    #     self.tf.waitForTransform(\n    #       '/world', '/cf' + str(self.id), rospy.Time(0), rospy.Duration(10))\n    #     position, quaternion = self.tf.lookupTransform(\n    #       '/world', '/cf' + str(self.id), rospy.Time(0))\n    #     return np.array(position)\n\n    def getParam(self, name):\n        \"\"\"\n        Get the current value of the onboard named parameter.\n\n        Parameters are named values of various primitive C types that control\n        the firmware's behavior. For more information, see\n        https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/userguides/logparam/.\n\n        Parameters are read at system startup over the radio and cached.\n        The ROS launch file can also be used to set parameter values at startup.\n        Subsequent calls to :meth:`setParam()` will update the cached value.\n        However, if the parameter changes for any other reason, the cached value\n        might become stale. This situation is not common.\n\n        Args:\n            name (str): The parameter's name.\n\n        Returns:\n            value (Any): The parameter's value.\n\n        \"\"\"\n        try:\n            param_name = self.prefix[1:] + '.params.' + name\n            req = GetParameters.Request()\n            req.names = [param_name]\n            future = self.getParamsService.call_async(req)\n            rclpy.spin_until_future_complete(self.node, future)\n            param_type = self.paramTypeDict[name]\n            if param_type == ParameterType.PARAMETER_INTEGER:\n                param_value = future.result().values[0].integer_value\n            elif param_type == ParameterType.PARAMETER_DOUBLE:\n                param_value = future.result().values[0].double_value\n            return param_value\n        except KeyError as e:\n            self.node.get_logger().warn(f'(crazyflie.py)getParam : keyError raised {e}')\n            return float('nan')\n        except Exception as e:\n            self.node.get_logger().warn(f'(crazyflie.py)getParam : exception raised {e}')\n            return float('nan')\n\n    def setParam(self, name, value):\n        \"\"\"\n        Change the value of the given parameter.\n\n        See :meth:`getParam()` docs for overview of the parameter system.\n\n        Args:\n            name (str): The parameter's name.\n            value (Any): The parameter's value.\n\n        \"\"\"\n        try:\n            param_name = self.prefix[1:] + '.params.' + name\n            param_type = self.paramTypeDict[name]\n            if param_type == ParameterType.PARAMETER_INTEGER:\n                param_value = ParameterValue(type=param_type, integer_value=int(value))\n            elif param_type == ParameterType.PARAMETER_DOUBLE:\n                param_value = ParameterValue(type=param_type, double_value=float(value))\n            req = SetParameters.Request()\n            req.parameters = [Parameter(name=param_name, value=param_value)]\n            self.setParamsService.call_async(req)\n        except KeyError as e:\n            self.node.get_logger().warn(f'(crazyflie.py)setParam : keyError raised {e}')\n        except Exception as e:\n            self.node.get_logger().warn(f'(crazyflie.py)setParam : exception raised {e}')\n\n    # def setParams(self, params):\n    #     \"\"\"Changes the value of several parameters at once.\n\n    #     See :meth:`getParam()` docs for overview of the parameter system.\n\n    #     Args:\n    #         params (Dict[str, Any]): Dict of parameter names/values.\n    #     \"\"\"\n    #     for name, value in params.items():\n    #         rospy.set_param(self.prefix + '/' + name, value)\n    #     self.updateParamsService(params.keys())\n\n    def cmdFullState(self, pos, vel, acc, yaw, omega):\n        \"\"\"\n        Send a streaming full-state controller setpoint command.\n\n        The full-state setpoint is most useful for aggressive maneuvers where\n        feedforward inputs for acceleration and angular velocity are critical\n        to obtaining good tracking performance. Full-state setpoints can be\n        obtained from any trajectory parameterization that is at least three\n        times differentiable, e.g. piecewise polynomials.\n\n        Sending a streaming setpoint of any type will force a change from\n        high-level to low-level command mode. Currently, there is no mechanism\n        to change back, but it is a high-priority feature to implement.\n        This means it is not possible to use e.g. :meth:`land()` or\n        :meth:`goTo()` after a streaming setpoint has been sent.\n\n        Args:\n            pos (array-like of float[3]): Position. Meters.\n            vel (array-like of float[3]): Velocity. Meters / second.\n            acc (array-like of float[3]): Acceleration. Meters / second^2.\n            yaw (float): Yaw angle. Radians.\n            omega (array-like of float[3]): Angular velocity in body frame.\n                Radians / sec.\n\n        \"\"\"\n        self.cmdFullStateMsg.header.stamp = self.node.get_clock().now().to_msg()\n        self.cmdFullStateMsg.pose.position.x = pos[0]\n        self.cmdFullStateMsg.pose.position.y = pos[1]\n        self.cmdFullStateMsg.pose.position.z = pos[2]\n        self.cmdFullStateMsg.twist.linear.x = vel[0]\n        self.cmdFullStateMsg.twist.linear.y = vel[1]\n        self.cmdFullStateMsg.twist.linear.z = vel[2]\n        self.cmdFullStateMsg.acc.x = acc[0]\n        self.cmdFullStateMsg.acc.y = acc[1]\n        self.cmdFullStateMsg.acc.z = acc[2]\n        q = rowan.from_euler(0, 0, yaw)\n        self.cmdFullStateMsg.pose.orientation.w = q[0]\n        self.cmdFullStateMsg.pose.orientation.x = q[1]\n        self.cmdFullStateMsg.pose.orientation.y = q[2]\n        self.cmdFullStateMsg.pose.orientation.z = q[3]\n        self.cmdFullStateMsg.twist.angular.x = omega[0]\n        self.cmdFullStateMsg.twist.angular.y = omega[1]\n        self.cmdFullStateMsg.twist.angular.z = omega[2]\n        self.cmdFullStatePublisher.publish(self.cmdFullStateMsg)\n\n    # def cmdVelocityWorld(self, vel, yawRate):\n    #     \"\"\"Sends a streaming velocity-world controller setpoint command.\n\n    #     In this mode, the PC specifies desired velocity vector and yaw rate.\n    #     The onboard controller will try to achive this velocity.\n\n    #     NOTE: the Mellinger controller is Crazyswarm's default controller, but\n    #     it has not been tuned (or even tested) for velocity control mode.\n    #     Switch to the PID controller by changing\n    #     `firmwareParams.stabilizer.controller` to `1` in your launch file.\n\n    #     Sending a streaming setpoint of any type will force a change from\n    #     high-level to low-level command mode. Currently, there is no mechanism\n    #     to change back, but it is a high-priority feature to implement.\n    #     This means it is not possible to use e.g. :meth:`land()` or\n    #     :meth:`goTo()` after a streaming setpoint has been sent.\n\n    #     Args:\n    #         vel (array-like of float[3]): Velocity. Meters / second.\n    #         yawRate (float): Yaw angular velocity. Degrees / second.\n    #     \"\"\"\n    #     self.cmdVelocityWorldMsg.header.stamp = rospy.Time.now()\n    #     self.cmdVelocityWorldMsg.header.seq += 1\n    #     self.cmdVelocityWorldMsg.vel.x = vel[0]\n    #     self.cmdVelocityWorldMsg.vel.y = vel[1]\n    #     self.cmdVelocityWorldMsg.vel.z = vel[2]\n    #     self.cmdVelocityWorldMsg.yawRate = yawRate\n    #     self.cmdVelocityWorldPublisher.publish(self.cmdVelocityWorldMsg)\n\n    # def cmdStop(self):\n    #     \"\"\"Interrupts any high-level command to stop and cut motor power.\n\n    #     Intended for non-emergency scenarios, e.g. landing with the possibility\n    #     of taking off again later. Future low- or high-level commands will\n    #     restart the motors. Equivalent of :meth:`stop()` when in high-level mode.\n    #     \"\"\"\n    #     self.cmdStopPublisher.publish(std_msgs.msg.Empty())\n\n    # def cmdVel(self, roll, pitch, yawrate, thrust):\n    #     \"\"\"Sends a streaming command of the 'easy mode' manual control inputs.\n\n    #     The (absolute roll & pitch, yaw rate, thrust) inputs are typically\n    #     used for manual flying by beginners or causal pilots, as opposed to the\n    #     'acrobatic mode' inputs where roll and pitch rates are controlled\n    #     instead of absolute angles. This mode limits the possible maneuvers,\n    #     e.g. it is not possible to do a flip because the controller joystick\n    #     would need to rotate 360 degrees.\n\n    #     For more information on streaming setpoint commands, see the\n    #     :meth:`cmdFullState()` documentation.\n\n    #     !NOTE!: The angles and angular velocities in this command are in\n    #     degrees, whereas they are in radians for cmdFullState.\n\n    #     TODO: should we change the name from cmdVel to something else?\n    #     IMO (japreiss), cmdVel implies controlling linear velocity.\n\n    #     Args:\n    #         roll (float): Roll angle. Degrees. Positive values == roll right.\n    #         pitch (float): Pitch angle. Degrees. Positive values == pitch\n    #             forward/down.\n    #         yawrate (float): Yaw angular velocity. Degrees / second. Positive\n    #             values == turn counterclockwise.\n    #         thrust (float): Thrust magnitude. Non-meaningful units in [0, 2^16),\n    #             where the maximum value corresponds to maximum thrust.\n    #     \"\"\"\n    #     msg = geometry_msgs.msg.Twist()\n    #     msg.linear.x = pitch\n    #     msg.linear.y = roll\n    #     msg.angular.z = yawrate\n    #     msg.linear.z = thrust\n    #     self.cmdVelPublisher.publish(msg)\n\n    def cmdPosition(self, pos, yaw=0.):\n        \"\"\"\n        Send a streaming command of absolute position and yaw setpoint.\n\n        Useful for slow maneuvers where a high-level planner determines the\n        desired position, and the rest is left to the onboard controller.\n\n        For more information on streaming setpoint commands, see the\n        :meth:`cmdFullState()` documentation.\n\n        Args:\n        ----\n            pos (array-like of float[3]): Position. Meters.\n            yaw (float): Yaw angle. Radians.\n\n        \"\"\"\n        self.cmdPositionMsg.header.stamp = self.node.get_clock().now().to_msg()\n        self.cmdPositionMsg.x = pos[0]\n        self.cmdPositionMsg.y = pos[1]\n        self.cmdPositionMsg.z = pos[2]\n        self.cmdPositionMsg.yaw = yaw\n        self.cmdPositionPublisher.publish(self.cmdPositionMsg)\n\n    # def setLEDColor(self, r, g, b):\n    #     \"\"\"Sets the color of the LED ring deck.\n\n    #     While most params (such as PID gains) only need to be set once, it is\n    #     common to change the LED ring color many times during a flight, e.g.\n    #     as some kind of status indicator. This method makes it convenient.\n\n    #     PRECONDITION: The param 'ring/effect' must be set to 7 (solid color)\n    #     for this command to have any effect. The default mode uses the ring\n    #     color to indicate radio connection quality.\n\n    #     This is a blocking command, so it may cause stability problems for\n    #     large swarms and/or high-frequency changes.\n\n    #     Args:\n    #         r (float): Red component of color, in range [0, 1].\n    #         g (float): Green component of color, in range [0, 1].\n    #         b (float): Blue component of color, in range [0, 1].\n    #     \"\"\"\n    #     self.setParam('ring/solidRed', int(r * 255))\n    #     self.setParam('ring/solidGreen', int(g * 255))\n    #     self.setParam('ring/solidBlue', int(b * 255))\n\n    def status_topic_callback(self, msg):\n        \"\"\"\n        Call back for topic /cfXXX/status.\n\n        Update the status attribute every time a crazyflie_interfaces/msg/Status\n        message is published on the topic /cfXXX/status\n        \"\"\"\n        self.status = {'id': msg.header.frame_id,\n                       'timestamp_sec': msg.header.stamp.sec,\n                       'timestamp_nsec': msg.header.stamp.nanosec,\n                       'supervisor': msg.supervisor_info,\n                       'battery': msg.battery_voltage,\n                       'pm_state': msg.pm_state,\n                       'rssi': msg.rssi,\n                       'num_rx_broadcast': msg.num_rx_broadcast,\n                       'num_tx_broadcast': msg.num_tx_broadcast,\n                       'num_rx_unicast': msg.num_rx_unicast,\n                       'num_tx_unicast': msg.num_tx_unicast}\n\n    def get_status(self):\n        \"\"\"\n        Return the status attribute.\n\n        Status is a dictionary containing:\n        frame id, timestamp, supervisor info, battery voltage, pm state, rssi, nb of received or\n        transmitted broadcast or unicast messages. see crazyflie_interfaces/msg/Status for details\n        \"\"\"\n        # self.node.get_logger().info(f'Crazyflie.get_status() was called {self.status}')\n        return self.status\n\n    def poseStamped_topic_callback(self, msg):\n        \"\"\"\n        Call back for topic /cfXXX/pose.\n\n        Update the pose attribute every time a pose\n        message is published on the topic /cfXXX/pose\n        \"\"\"\n        self.poseStamped = {'id': msg.header.frame_id,\n                            'timestamp_sec': msg.header.stamp.sec,\n                            'timestamp_nsec': msg.header.stamp.nanosec,\n                            'pose': msg.pose}\n\n        poseMsg = self.poseStamped['pose']\n\n        self.pose = {'position': poseMsg.position,\n                     'orientation': poseMsg.orientation}\n\n        positionMsg = self.pose['position']\n\n        self.position = [float(positionMsg.x), float(positionMsg.y), float(positionMsg.z)]\n\n    def get_pose(self):\n        return self.pose\n\n    def get_position(self):\n        return self.position\n\n\nclass CrazyflieServer(rclpy.node.Node):\n    \"\"\"\n    Object for broadcasting commands to all robots at once.\n\n    Also is the container for the individual :obj:`Crazyflie` objects.\n\n    Attributes:\n        crazyfiles (List[Crazyflie]): List of one Crazyflie object per robot,\n            as determined by the crazyflies.yaml config file.\n        crazyfliesById (Dict[int, Crazyflie]): Index to the same Crazyflie\n            objects by their ID number (last byte of radio address).\n\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"Initialize the server. Waits for all ROS services before returning.\"\"\"\n        super().__init__('CrazyflieAPI')\n\n        # wait for server to be fully started\n        self.emergencyService = self.create_client(Empty, 'all/emergency')\n        self.emergencyService.wait_for_service()\n\n        self.takeoffService = self.create_client(Takeoff, 'all/takeoff')\n        self.takeoffService.wait_for_service()\n        self.landService = self.create_client(Land, 'all/land')\n        self.landService.wait_for_service()\n        self.goToService = self.create_client(GoTo, 'all/go_to')\n        self.goToService.wait_for_service()\n        self.startTrajectoryService = self.create_client(StartTrajectory, 'all/start_trajectory')\n        self.startTrajectoryService.wait_for_service()\n        self.armService = self.create_client(Arm, 'all/arm')\n        # self.armService.wait_for_service()\n        self.setParamsService = self.create_client(\n            SetParameters, '/crazyflie_server/set_parameters')\n        self.setParamsService.wait_for_service()\n\n        self.cmdFullStatePublisher = self.create_publisher(\n            FullState, 'all/cmd_full_state', 1)\n        self.cmdFullStateMsg = FullState()\n        self.cmdFullStateMsg.header.frame_id = '/world'\n\n        cfnames = []\n        for srv_name, srv_types in self.get_service_names_and_types():\n            if 'crazyflie_interfaces/srv/StartTrajectory' in srv_types:\n                # remove '/' and '/start_trajectory'\n                cfname = srv_name[1:-17]\n                if cfname != 'all':\n                    cfnames.append(cfname)\n\n        # Query all parameters\n        listParamsService = self.create_client(ListParameters, '/crazyflie_server/list_parameters')\n        listParamsService.wait_for_service()\n        req = ListParameters.Request()\n        req.depth = ListParameters.Request.DEPTH_RECURSIVE\n        req.prefixes = []\n        future = listParamsService.call_async(req)\n        params = []\n        while rclpy.ok():\n            rclpy.spin_once(self)\n            if future.done():\n                # Filter the parameters that belong to this Crazyflie\n                response = future.result()\n                for p in response.result.names:\n                    if '.params.' in p:\n                        params.append(p)\n                break\n\n        # Find the types for the parameters and store them\n        describeParametersService = self.create_client(\n            DescribeParameters, '/crazyflie_server/describe_parameters')\n        describeParametersService.wait_for_service()\n        req = DescribeParameters.Request()\n        req.names = params\n        future = describeParametersService.call_async(req)\n        allParamTypeDicts = defaultdict(dict)\n        while rclpy.ok():\n            rclpy.spin_once(self)\n            if future.done():\n                # Filter the parameters that belong to this Crazyflie\n                response = future.result()\n                for p, d in zip(params, response.descriptors):\n                    idx = p.index('.params.')\n                    cf_name = p[0:idx]\n                    param_name = p[idx+8:]\n                    t = d.type\n                    if cf_name in allParamTypeDicts:\n                        allParamTypeDicts[cf_name][param_name] = t\n                    else:\n                        allParamTypeDicts[cf_name] = {param_name: t}\n                break\n        self.paramTypeDict = allParamTypeDicts['all']\n\n        self.crazyflies = []\n        self.crazyfliesById = {}\n        self.crazyfliesByName = {}\n        for cfname in cfnames:\n            cf = Crazyflie(self, cfname, allParamTypeDicts[cfname])\n            self.crazyflies.append(cf)\n            self.crazyfliesByName[cfname] = cf\n            # For legacy crazyswarm1 code, also provide crazyfliesById\n            cfid = int(cf.uri[-2:], 16)\n            self.crazyfliesById[cfid] = cf\n\n    def emergency(self):\n        \"\"\"\n        Emergency stop. Cuts power; causes future commands to be ignored.\n\n        This command is useful if the operator determines that the control\n        script is flawed, and that continuing to follow it will cause wrong/\n        self-destructive behavior from the robots. In addition to cutting\n        power to the motors, it ensures that any future commands, both high-\n        level and streaming, will have no effect.\n\n        The only ways to reset the firmware after an emergency stop has occurred\n        are a physical hard reset or an nRF51 Reboot command.\n        \"\"\"\n        req = Empty.Request()\n        self.emergencyService.call_async(req)\n\n    def takeoff(self, targetHeight, duration, groupMask=0):\n        \"\"\"\n        Broadcasted takeoff - fly straight up, then hover indefinitely.\n\n        Broadcast version of :meth:`Crazyflie.takeoff()`. All robots that match the\n        groupMask take off at exactly the same time. Use for synchronized\n        movement. Asynchronous command; returns immediately.\n\n        Args:\n        ----\n            targetHeight (float): The z-coordinate at which to hover.\n            duration (float): How long until the height is reached. Seconds.\n            groupMask (int): Group mask bits. See :meth:`setGroupMask()` doc.\n\n        \"\"\"\n        req = Takeoff.Request()\n        req.group_mask = groupMask\n        req.height = targetHeight\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.takeoffService.call_async(req)\n\n    def land(self, targetHeight, duration, groupMask=0):\n        \"\"\"\n        Broadcasted landing - fly straight down. User must cut power after.\n\n        Broadcast version of :meth:`Crazyflie.land()`. All robots that match the\n        groupMask land at exactly the same time. Use for synchronized\n        movement. Asynchronous command; returns immediately.\n\n        Args:\n        ----\n            targetHeight (float): The z-coordinate at which to land. Meters.\n                Usually should be a few centimeters above the initial position\n                to ensure that the controller does not try to penetrate the\n                floor if the mocap coordinate origin is not perfect.\n            duration (float): How long until the height is reached. Seconds.\n            groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc.\n\n        \"\"\"\n        req = Land.Request()\n        req.group_mask = groupMask\n        req.height = targetHeight\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.landService.call_async(req)\n\n    def goTo(self, goal, yaw, duration, groupMask=0):\n        \"\"\"\n        Broadcasted goTo - Move smoothly to goal, then hover indefinitely.\n\n        Broadcast version of :meth:`Crazyflie.goTo()`. All robots that match the\n        groupMask start moving at exactly the same time. Use for synchronized\n        movement. Asynchronous command; returns immediately.\n\n        While the individual goTo() supports both relative and absolute\n        coordinates, the broadcasted goTo only makes sense with relative\n        coordinates (since absolute broadcasted goTo() would cause a collision).\n        Therefore, there is no `relative` kwarg.\n\n        See docstring of :meth:`Crazyflie.goTo()` for additional details.\n\n        Args:\n            goal (iterable of 3 floats): The goal offset. Meters.\n            yaw (float): The goal yaw angle (heading). Radians.\n            duration (float): How long until the goal is reached. Seconds.\n            groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc.\n\n        \"\"\"\n        req = GoTo.Request()\n        req.group_mask = groupMask\n        req.relative = True\n        req.goal = arrayToGeometryPoint(goal)\n        req.yaw = yaw\n        req.duration = rclpy.duration.Duration(seconds=duration).to_msg()\n        self.goToService.call_async(req)\n\n    def startTrajectory(self, trajectoryId,\n                        timescale=1.0, reverse=False,\n                        relative=True, groupMask=0):\n        \"\"\"\n        Broadcasted - begins executing a previously uploaded trajectory.\n\n        Broadcast version of :meth:`Crazyflie.startTrajectory()`.\n        Asynchronous command; returns immediately.\n\n        Args:\n            trajectoryId (int): ID number as given to :meth:`Crazyflie.uploadTrajectory()`.\n            timescale (float): Scales the trajectory duration by this factor.\n                For example if timescale == 2.0, the trajectory will take twice\n                as long to execute as the nominal duration.\n            reverse (bool): If true, executes the trajectory backwards in time.\n            relative (bool): If true (default), the position of the trajectory\n                is shifted such that it begins at the current position setpoint.\n            groupMask (int): Group mask bits. See :meth:`Crazyflie.setGroupMask()` doc.\n\n        \"\"\"\n        req = StartTrajectory.Request()\n        req.group_mask = groupMask\n        req.trajectory_id = trajectoryId\n        req.timescale = timescale\n        req.reversed = reverse\n        req.relative = relative\n        self.startTrajectoryService.call_async(req)\n\n    def arm(self, arm=True):\n        \"\"\"\n        Broadcasted arming.\n\n        For a brushless or Bolt-based drone the motors start spinning and flight\n        is enabled.\n\n        Args:\n            arm (boolean): True if the motors should be armed, False otherwise.\n\n        \"\"\"\n        req = Arm.Request()\n        req.arm = arm\n        self.armService.call_async(req)\n\n    def setParam(self, name, value):\n        \"\"\"Set parameter via broadcasts. See Crazyflie.setParam for details.\"\"\"\n        try:\n            param_name = 'all.params.' + name\n            param_type = self.paramTypeDict[name]\n            if param_type == ParameterType.PARAMETER_INTEGER:\n                param_value = ParameterValue(type=param_type, integer_value=int(value))\n            elif param_type == ParameterType.PARAMETER_DOUBLE:\n                param_value = ParameterValue(type=param_type, double_value=float(value))\n            req = SetParameters.Request()\n            req.parameters = [Parameter(name=param_name, value=param_value)]\n            self.setParamsService.call_async(req)\n        except KeyError as e:\n            self.get_logger().warn(f'(crazyflie.py)setParam : keyError raised {e}')\n        except Exception as e:\n            self.get_logger().warn(f'(crazyflie.py)setParam : exception raised {e}')\n\n    def cmdFullState(self, pos, vel, acc, yaw, omega):\n        \"\"\"\n        Send a streaming full-state controller setpoint command.\n\n        The full-state setpoint is most useful for aggressive maneuvers where\n        feedforward inputs for acceleration and angular velocity are critical\n        to obtaining good tracking performance. Full-state setpoints can be\n        obtained from any trajectory parameterization that is at least three\n        times differentiable, e.g. piecewise polynomials.\n\n        Sending a streaming setpoint of any type will force a change from\n        high-level to low-level command mode. Currently, there is no mechanism\n        to change back, but it is a high-priority feature to implement.\n        This means it is not possible to use e.g. :meth:`land()` or\n        :meth:`goTo()` after a streaming setpoint has been sent.\n\n        Args:\n            pos (array-like of float[3]): Position. Meters.\n            vel (array-like of float[3]): Velocity. Meters / second.\n            acc (array-like of float[3]): Acceleration. Meters / second^2.\n            yaw (float): Yaw angle. Radians.\n            omega (array-like of float[3]): Angular velocity in body frame.\n                Radians / sec.\n\n        \"\"\"\n        self.cmdFullStateMsg.header.stamp = self.get_clock().now().to_msg()\n        self.cmdFullStateMsg.pose.position.x = pos[0]\n        self.cmdFullStateMsg.pose.position.y = pos[1]\n        self.cmdFullStateMsg.pose.position.z = pos[2]\n        self.cmdFullStateMsg.twist.linear.x = vel[0]\n        self.cmdFullStateMsg.twist.linear.y = vel[1]\n        self.cmdFullStateMsg.twist.linear.z = vel[2]\n        self.cmdFullStateMsg.acc.x = acc[0]\n        self.cmdFullStateMsg.acc.y = acc[1]\n        self.cmdFullStateMsg.acc.z = acc[2]\n        q = rowan.from_euler(0, 0, yaw)\n        self.cmdFullStateMsg.pose.orientation.w = q[0]\n        self.cmdFullStateMsg.pose.orientation.x = q[1]\n        self.cmdFullStateMsg.pose.orientation.y = q[2]\n        self.cmdFullStateMsg.pose.orientation.z = q[3]\n        self.cmdFullStateMsg.twist.angular.x = omega[0]\n        self.cmdFullStateMsg.twist.angular.y = omega[1]\n        self.cmdFullStateMsg.twist.angular.z = omega[2]\n        self.cmdFullStatePublisher.publish(self.cmdFullStateMsg)\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/crazyswarm_py.py",
    "content": "import rclpy\n\nfrom . import genericJoystick\nfrom .crazyflie import CrazyflieServer, TimeHelper\n\n\nclass Crazyswarm:\n\n    def __init__(self):\n        rclpy.init()\n\n        self.allcfs = CrazyflieServer()\n        self.timeHelper = TimeHelper(self.allcfs)\n\n        self.input = genericJoystick.Joystick(self.timeHelper)\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/genericJoystick.py",
    "content": "import copy\n# import pyglet\n\nfrom . import keyboard\n\n# class JoyStickHandler:\n#     def __init__(self):\n#         self.buttonWasPressed = False\n\n#     def on_joybutton_press(joystick, button):\n#         if button == 5:\n#             self.buttonWasPressed = True\n\n#     def on_joybutton_release(joystick, button):\n#         pass\n\n#     def on_joyaxis_motion(joystick, axis, value):\n#         pass\n\n#     def on_joyhat_motion(joystick, hat_x, hat_y):\n#         pass\n\n\nclass Joystick:\n\n    def __init__(self, timeHelper):\n        # joysticks = pyglet.input.get_joysticks()\n        # joystick = joysticks[0]\n        # joystick.open()\n        # self.buttonWasPressed = False\n        # joystick.push_handlers(self)\n        self.timeHelper = timeHelper\n        self.joyID = None\n\n        try:\n            from . import linuxjsdev\n            self.js = linuxjsdev.Joystick()\n            devices = self.js.devices()\n            if len(devices) == 0:\n                print('Warning: No joystick found!')\n            else:\n                ids = [dev['id'] for dev in devices]\n                # For backwards compatibility, always choose device 0 if available.\n                self.joyID = 0 if 0 in ids else devices[0]['id']\n                self.js.open(self.joyID)\n        except ImportError:\n            print('Warning: Joystick only supported on Linux.')\n\n    # def on_joybutton_press(joystick, button):\n        # print(button)\n        # if button == 5:\n            # self.buttonWasPressed = True\n\n    # def wasButtonPressed(self):\n    #     return self.buttonWasPressed\n\n    # def clearButtonPressed(self):\n    #     self.buttonWasPressed = False\n\n    def checkIfButtonIsPressed(self):\n        if self.joyID is not None:\n            state = self.js.read(self.joyID)\n            return state[1][5] == 1\n        else:\n            return False\n\n    def waitUntilButtonPressed(self):\n        if self.joyID is not None:\n            while not self.checkIfButtonIsPressed():\n                self.timeHelper.sleep(0.01)\n            while self.checkIfButtonIsPressed():\n                self.timeHelper.sleep(0.01)\n        else:\n            with keyboard.KeyPoller() as keyPoller:\n                # Wait until a key is pressed.\n                while keyPoller.poll() is None:\n                    self.timeHelper.sleep(0.01)\n                # Wait until the key is released.\n                while keyPoller.poll() is not None:\n                    self.timeHelper.sleep(0.01)\n\n    def checkIfAnyButtonIsPressed(self):\n        if self.joyID is not None:\n            state = self.js.read(self.joyID)\n            if state[1][5] == 1 or state[1][4] == 1 or state[1][3] == 1:\n                return state[1]\n            else:\n                return None\n        else:\n            return None\n\n    def waitUntilAnyButtonPressed(self):\n        if self.joyID is not None:\n            buttons = self.checkIfAnyButtonIsPressed()\n            while buttons is None:\n                self.timeHelper.sleep(0.01)\n                buttons = copy.copy(self.checkIfAnyButtonIsPressed())\n            while self.checkIfAnyButtonIsPressed() is not None:\n                self.timeHelper.sleep(0.01)\n            return buttons\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/joystick.py",
    "content": "import time\n\nimport rospy\nfrom sensor_msgs.msg import Joy\n\n\nclass Joystick:\n\n    def __init__(self):\n        self.lastButtonState = 0\n        self.buttonWasPressed = False\n        rospy.Subscriber('/joy', Joy, self.joyChanged)\n\n    def joyChanged(self, data):\n        if (not self.buttonWasPressed and\n                data.buttons[5] == 1 and\n                self.lastButtonState == 0):\n            self.buttonWasPressed = True\n        self.lastButtonState = data.buttons[5]\n\n    def waitUntilButtonPressed(self):\n        while not rospy.is_shutdown() and not self.buttonWasPressed:\n            time.sleep(0.01)\n        self.buttonWasPressed = False\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/keyboard.py",
    "content": "import select\nimport sys\nimport termios\n\n\nclass KeyPoller():\n\n    def __enter__(self):\n        # Save the terminal settings\n        self.fd = sys.stdin.fileno()\n        self.new_term = termios.tcgetattr(self.fd)\n        self.old_term = termios.tcgetattr(self.fd)\n\n        # New terminal setting unbuffered\n        self.new_term[3] = (self.new_term[3] & ~termios.ICANON & ~termios.ECHO)\n        termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.new_term)\n\n        return self\n\n    def __exit__(self, type, value, traceback):  # noqa A002\n        termios.tcsetattr(self.fd, termios.TCSAFLUSH, self.old_term)\n\n    def poll(self):\n        dr, dw, de = select.select([sys.stdin], [], [], 0)\n        if not dr == []:\n            return sys.stdin.read(1)\n        return None\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/linuxjsdev.py",
    "content": "# -*- coding: utf-8 -*-\n#     ||\n#  +------+      / __ )(_) /_______________ _____  ___\n#  | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \\\n#  +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/\n#   ||  ||    /_____/_/\\__/\\___/_/   \\__,_/ /___/\\___/\n#\n#  Copyright (C) 2011-2013 Bitcraze AB\n#\n#  Crazyflie Nano Quadcopter Client\n#\n#  This program is free software; you can redistribute it and/or\n#  modify it under the terms of the GNU General Public License\n#  as published by the Free Software Foundation; either version 2\n#  of the License, or (at your option) any later version.\n#\n#  This program is distributed in the hope that it will be useful,\n#  but WITHOUT ANY WARRANTY; without even the implied warranty of\n#  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n#  GNU General Public License for more details.\n#\n#  You should have received a copy of the GNU General Public License\n#  along with this program; if not, write to the Free Software Foundation,\n#  Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.\n\"\"\"\nLinux joystick driver using the Linux input_joystick subsystem.\n\nRequires sysfs to be mounted on /sys and /dev/input/js* to be readable.\n\nThis module is very linux specific but should work on any CPU platform\n\"\"\"\nimport ctypes\nimport glob\nimport logging\nimport os\nimport struct\nimport sys\n\nif not sys.platform.startswith('linux'):\n    raise ImportError('Only supported on Linux')\n\ntry:\n    import fcntl\nexcept ImportError as e:\n    raise Exception('fcntl library probably not installed ({})'.format(e))\n\n__author__ = 'Bitcraze AB'\n__all__ = ['Joystick']\n\nlogger = logging.getLogger(__name__)\n\nJS_EVENT_FMT = '@IhBB'\nJE_TIME = 0\nJE_VALUE = 1\nJE_TYPE = 2\nJE_NUMBER = 3\n\nJS_EVENT_BUTTON = 0x001\nJS_EVENT_AXIS = 0x002\nJS_EVENT_INIT = 0x080\n\n# ioctls\nJSIOCGAXES = 0x80016a11\nJSIOCGBUTTONS = 0x80016a12\n\nMODULE_MAIN = 'Joystick'\nMODULE_NAME = 'linuxjsdev'\n\n\nclass JEvent(object):\n    \"\"\"Joystick event class. Encapsulate single joystick event.\"\"\"\n\n    def __init__(self, evt_type, number, value):\n        self.type = evt_type\n        self.number = number\n        self.value = value\n\n    def __repr__(self):\n        return 'JEvent(type={}, number={}, value={})'.format(\n            self.type, self.number, self.value)\n\n\n# Constants\nTYPE_BUTTON = 1\nTYPE_AXIS = 2\n\n\nclass _JS():\n\n    def __init__(self, num, name):\n        self.num = num\n        self.name = name\n        self._f_name = '/dev/input/js{}'.format(num)\n        self._f = None\n\n        self.opened = False\n        self.buttons = []\n        self.axes = []\n        self._prev_pressed = {}\n\n    def open(self):  # noqa: A003\n        if self._f:\n            raise Exception('{} at {} is already '\n                            'opened'.format(self.name, self._f_name))\n\n        self._f = open('/dev/input/js{}'.format(self.num), 'rb')\n        fcntl.fcntl(self._f.fileno(), fcntl.F_SETFL, os.O_NONBLOCK)\n\n        # Get number of axis and button\n        val = ctypes.c_int()\n        if fcntl.ioctl(self._f.fileno(), JSIOCGAXES, val) != 0:\n            self._f.close()\n            self._f = None\n            raise Exception('Failed to read number of axes')\n\n        self.axes = [0 for i in range(val.value)]\n        if fcntl.ioctl(self._f.fileno(), JSIOCGBUTTONS, val) != 0:\n            self._f.close()\n            self._f = None\n            raise Exception('Failed to read number of axes')\n\n        self.buttons = [0 for i in range(val.value)]\n        self.__initvalues()\n\n    def close(self):\n        \"\"\"Open the joystick device.\"\"\"\n        if not self._f:\n            return\n\n        logger.info('Closed {} ({})'.format(self.name, self.num))\n\n        self._f.close()\n        self._f = None\n\n    def __initvalues(self):\n        \"\"\"Read the buttons and axes initial values from the js device.\"\"\"\n        for _ in range(len(self.axes) + len(self.buttons)):\n            data = self._f.read(struct.calcsize(JS_EVENT_FMT))\n            jsdata = struct.unpack(JS_EVENT_FMT, data)\n            self.__updatestate(jsdata)\n\n    def __updatestate(self, jsdata):\n        \"\"\"Update the internal absolute state of buttons and axes.\"\"\"\n        if jsdata[JE_TYPE] & JS_EVENT_AXIS != 0:\n            self.axes[jsdata[JE_NUMBER]] = jsdata[JE_VALUE] / 32768.0\n        elif jsdata[JE_TYPE] & JS_EVENT_BUTTON != 0:\n            self.buttons[jsdata[JE_NUMBER]] = jsdata[JE_VALUE]\n\n    def __decode_event(self, jsdata):\n        \"\"\"Decode a jsdev event into a dict.\"\"\"\n        # TODO: Add timestamp?\n        if jsdata[JE_TYPE] & JS_EVENT_AXIS != 0:\n            return JEvent(evt_type=TYPE_AXIS,\n                          number=jsdata[JE_NUMBER],\n                          value=jsdata[JE_VALUE] / 32768.0)\n        if jsdata[JE_TYPE] & JS_EVENT_BUTTON != 0:\n            return JEvent(evt_type=TYPE_BUTTON,\n                          number=jsdata[JE_NUMBER],\n                          value=jsdata[JE_VALUE] / 32768.0)\n\n    def _read_all_events(self):\n        \"\"\"Consume all the events queued up in the JS device.\"\"\"\n        try:\n            while True:\n                data = self._f.read(struct.calcsize(JS_EVENT_FMT))\n                jsdata = struct.unpack(JS_EVENT_FMT, data)\n                self.__updatestate(jsdata)\n        except IOError as e:\n            if e.errno != 11:\n                logger.info(str(e))\n                self._f.close()\n                self._f = None\n                raise IOError('Device has been disconnected')\n        except TypeError:\n            pass\n        except ValueError:\n            # This will happen if I/O operations are done on a closed device,\n            # which is the case when you first close and then open the device\n            # while switching device. But, in order for SDL2 to work on Linux\n            # (for debugging) the device needs to be closed before it's opened.\n            # This is the workaround to make both cases work.\n            pass\n\n    def read(self):\n        \"\"\"Return a list of all joystick event since the last call.\"\"\"\n        if not self._f:\n            raise Exception('Joystick device not opened')\n\n        self._read_all_events()\n\n        return [self.axes, self.buttons]\n\n\nclass Joystick():\n    \"\"\"Linux jsdev implementation of the Joystick class.\"\"\"\n\n    def __init__(self):\n        self.name = MODULE_NAME\n        self._js = {}\n        self._devices = []\n\n    def devices(self):\n        \"\"\"\n        Return a list containing an {'id': id, 'name': name} dict for each detected device.\n\n        Result is cached once one or more devices are found.\n        \"\"\"\n        if len(self._devices) == 0:\n            syspaths = glob.glob('/sys/class/input/js*')\n\n            for path in syspaths:\n                device_id = int(os.path.basename(path)[2:])\n                with open(path + '/device/name') as namefile:\n                    name = namefile.read().strip()\n                self._js[device_id] = _JS(device_id, name)\n                self._devices.append({'id': device_id, 'name': name})\n\n        return self._devices\n\n    def open(self, device_id):  # noqa: A003\n        \"\"\"Open the joystick device. The device_id is given by available_devices.\"\"\"\n        self._js[device_id].open()\n\n    def close(self, device_id):\n        \"\"\"Open the joystick device.\"\"\"\n        self._js[device_id].close()\n\n    def read(self, device_id):\n        \"\"\"Return a list of all joystick event since the last call.\"\"\"\n        return self._js[device_id].read()\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/uav_trajectory.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\n\n\ndef normalize(v):\n    norm = np.linalg.norm(v)\n    assert norm > 0\n    return v / norm\n\n\nclass Polynomial:\n\n    def __init__(self, p):\n        self.p = p\n\n    # evaluate a polynomial using horner's rule\n    def eval(self, t):  # noqa: A003\n        assert t >= 0\n        x = 0.0\n        for i in range(0, len(self.p)):\n            x = x * t + self.p[len(self.p) - 1 - i]\n        return x\n\n    # compute and return derivative\n    def derivative(self):\n        return Polynomial([(i+1) * self.p[i+1] for i in range(0, len(self.p) - 1)])\n\n\nclass TrajectoryOutput:\n\n    def __init__(self):\n        self.pos = None    # position [m]\n        self.vel = None    # velocity [m/s]\n        self.acc = None    # acceleration [m/s^2]\n        self.omega = None  # angular velocity [rad/s]\n        self.yaw = None    # yaw angle [rad]\n\n\n# 4d single polynomial piece for x-y-z-yaw, includes duration.\nclass Polynomial4D:\n\n    def __init__(self, duration, px, py, pz, pyaw):\n        self.duration = duration\n        self.px = Polynomial(px)\n        self.py = Polynomial(py)\n        self.pz = Polynomial(pz)\n        self.pyaw = Polynomial(pyaw)\n\n    # compute and return derivative\n    def derivative(self):\n        return Polynomial4D(\n            self.duration,\n            self.px.derivative().p,\n            self.py.derivative().p,\n            self.pz.derivative().p,\n            self.pyaw.derivative().p)\n\n    def eval(self, t):  # noqa: A003\n        result = TrajectoryOutput()\n        # flat variables\n        result.pos = np.array([self.px.eval(t), self.py.eval(t), self.pz.eval(t)])\n        result.yaw = self.pyaw.eval(t)\n\n        # 1st derivative\n        derivative = self.derivative()\n        result.vel = np.array([derivative.px.eval(t),\n                               derivative.py.eval(t),\n                               derivative.pz.eval(t)])\n        dyaw = derivative.pyaw.eval(t)\n\n        # 2nd derivative\n        derivative2 = derivative.derivative()\n        result.acc = np.array([derivative2.px.eval(t),\n                               derivative2.py.eval(t),\n                               derivative2.pz.eval(t)])\n\n        # 3rd derivative\n        derivative3 = derivative2.derivative()\n        jerk = np.array([derivative3.px.eval(t),\n                         derivative3.py.eval(t),\n                         derivative3.pz.eval(t)])\n\n        thrust = result.acc + np.array([0, 0, 9.81])  # add gravity\n\n        z_body = normalize(thrust)\n        x_world = np.array([np.cos(result.yaw), np.sin(result.yaw), 0])\n        y_body = normalize(np.cross(z_body, x_world))\n        x_body = np.cross(y_body, z_body)\n\n        jerk_orth_zbody = jerk - (np.dot(jerk, z_body) * z_body)\n        h_w = jerk_orth_zbody / np.linalg.norm(thrust)\n\n        result.omega = np.array([-np.dot(h_w, y_body), np.dot(h_w, x_body), z_body[2] * dyaw])\n        return result\n\n\nclass Trajectory:\n\n    def __init__(self):\n        self.polynomials = None\n        self.duration = None\n\n    def n_pieces(self):\n        return len(self.polynomials)\n\n    def loadcsv(self, filename):\n        data = np.loadtxt(filename, delimiter=',', skiprows=1, usecols=range(33))\n        self.polynomials = [Polynomial4D(row[0], row[1:9],\n                                         row[9:17], row[17:25], row[25:33]) for row in data]\n        self.duration = np.sum(data[:, 0])\n\n    def eval(self, t):  # noqa: A003\n        assert t >= 0\n        assert t <= self.duration\n\n        current_t = 0.0\n        for p in self.polynomials:\n            if t <= current_t + p.duration:\n                return p.eval(t - current_t)\n            current_t = current_t + p.duration\n"
  },
  {
    "path": "crazyflie_py/crazyflie_py/util.py",
    "content": "\"\"\"Useful functions for both pycrazyswarm internals and user scripts.\"\"\"\n\nimport numpy as np\nimport scipy as sp\nimport scipy.spatial\n\n\ndef check_ellipsoid_collisions(positions, radii):\n    \"\"\"\n    Check for collisions between a set of ellipsoids at given positions.\n\n    Args:\n        positions (array float[n, 3]): The ellipsoid centers.\n        radii (array float[3]): The radii of the axis-aligned ellipsoids.\n\n    Returns:\n        colliding (array bool[n]): True at index i if the i'th ellipsoid\n            intersects any of the other ellipsoids.\n\n    \"\"\"\n    scaled = positions / radii[None, :]\n    dists = sp.spatial.distance.pdist(scaled)\n    dists = sp.spatial.distance.squareform(dists)\n    # Do not consider 0 distance to self as a collision!\n    n, _ = positions.shape\n    dists[range(n), range(n)] = np.inf\n    colliding = np.any(dists < 1.97, axis=1)\n    return colliding\n\n\ndef poisson_disk_sample(n, dim, mindist):\n    \"\"\"\n    Generate random points with guaranteed minimum pairwise distance.\n\n    Uses extremely naive and slow \"dart throwing\" algorithm.\n    TODO(jpreiss): find/implement a library with a fast algorithm.\n\n    Args:\n        n (int): Number of points.\n        dim (int): Dimensionality of points.\n        mindist (float): Minimum Euclidean distance between any two points.\n\n    Returns:\n        pts (array float[n, dim]): The sampled points.\n\n    \"\"\"\n    # Select hypercube volume such that n points will not pack it too tightly.\n    # Note: Will be too sparse for dim >> 3, but reasonable for dim == 2 or 3.\n    measure_ratio = 1.25\n    std = (measure_ratio * n) ** (1.0 / dim) * mindist\n\n    def sample():\n        return std * np.random.uniform(-0.5, 0.5, size=dim)\n\n    # Sample the points using dart-throwing.\n    pts = sample()[None, :]\n    while len(pts) < n:\n        pt = sample()\n        dists = np.linalg.norm(pts - pt, axis=1)\n        if np.all(dists >= mindist):\n            pts = np.concatenate([pts, pt[None, :]], axis=0)\n    return pts\n"
  },
  {
    "path": "crazyflie_py/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>crazyflie_py</name>\n  <version>1.0.3</version>\n  <description>Simple Python Interface for Crayzswarm2</description>\n  <maintainer email=\"hoenig@tu-berlin.de\">Wolfgang Hönig</maintainer>\n  <maintainer email=\"kimberleymcguire@gmail.com\">Kimberly N. McGuire</maintainer>\n  <license>MIT</license>\n\n  <depend>rclpy</depend>\n  <depend>crazyflie_interfaces</depend>\n\n  <test_depend>ament_copyright</test_depend>\n  <test_depend>ament_flake8</test_depend>\n  <test_depend>ament_pep257</test_depend>\n  <test_depend>python3-pytest</test_depend>\n\n  <export>\n    <build_type>ament_python</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "crazyflie_py/resource/crazyflie_py",
    "content": ""
  },
  {
    "path": "crazyflie_py/setup.cfg",
    "content": "[develop]\nscript_dir=$base/lib/crazyflie_py\n[install]\ninstall_scripts=$base/lib/crazyflie_py\n"
  },
  {
    "path": "crazyflie_py/setup.py",
    "content": "from setuptools import setup\n\npackage_name = 'crazyflie_py'\n\nsetup(\n    name=package_name,\n    version='1.0.3',\n    packages=[package_name],\n    data_files=[\n        ('share/ament_index/resource_index/packages',\n            ['resource/' + package_name]),\n        ('share/' + package_name, ['package.xml']),\n    ],\n    install_requires=['setuptools'],\n    zip_safe=True,\n    maintainer='Wolfgang Hönig, Kimberly N. McGuire',\n    maintainer_email='hoenig@tu-berlin.de, kimberleymcguire@gmail.com',\n    description='Simple Python interface for Crazyswarm2',\n    license='MIT',\n    tests_require=['pytest'],\n    entry_points={\n        'console_scripts': [\n        ],\n    },\n)\n"
  },
  {
    "path": "crazyflie_py/test/test_flake8.py",
    "content": "# Copyright 2017 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_flake8.main import main_with_errors\nimport pytest\n\n\n@pytest.mark.flake8\n@pytest.mark.linter\ndef test_flake8():\n    rc, errors = main_with_errors(argv=[])\n    assert rc == 0, \\\n        'Found %d code style errors / warnings:\\n' % len(errors) + \\\n        '\\n'.join(errors)\n"
  },
  {
    "path": "crazyflie_py/test/test_pep257.py",
    "content": "# Copyright 2015 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_pep257.main import main\nimport pytest\n\n\n@pytest.mark.linter\n@pytest.mark.pep257\ndef test_pep257():\n    rc = main(argv=['.', 'test', '--add-ignore', 'D406', 'D407', 'D417'])\n    assert rc == 0, 'Found code style errors / warnings'\n"
  },
  {
    "path": "crazyflie_sim/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package crazyflie_sim\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n1.0.3 (2025-07-09)\n------------------\n* Improve package.xml (separate maintainer tags, update year)\n* Contributors: Kimberly N. McGuire\n\n1.0.2 (2025-07-02)\n------------------\n\n1.0.1 (2025-06-30)\n------------------\n\n\n1.0.0 (2025-06-21)\n------------------\n* First official release.\n* Contributors: HP99, Khaled Wahba, Kimberly N. McGuire, Pablo, Wolfgang Hönig, julienthevenoz, matthewoots, phanfeld\n"
  },
  {
    "path": "crazyflie_sim/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 3.8)\nproject(crazyflie_sim)\n\n# find dependencies\nfind_package(ament_cmake REQUIRED)\nfind_package(ament_cmake_python REQUIRED)\n\n# Install Python modules\nament_python_install_package(${PROJECT_NAME} SCRIPTS_DESTINATION lib/${PROJECT_NAME})\n\n# # Install launch and config files.\n# install(DIRECTORY\n#   config\n#   data\n#   launch\n#   DESTINATION share/${PROJECT_NAME}/\n# )\n\nif(BUILD_TESTING)\n  find_package(ament_cmake_pytest REQUIRED)\n  set(_pytest_tests\n    test/test_flake8.py\n    test/test_pep257.py\n  )\n  foreach(_test_path ${_pytest_tests})\n    get_filename_component(_test_name ${_test_path} NAME_WE)\n    ament_add_pytest_test(${_test_name} ${_test_path}\n      APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}\n      TIMEOUT 60\n      WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}\n    )\n  endforeach()\nendif()\n\nament_package()\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/__init__.py",
    "content": ""
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/data/dynobench/crazyflie2.yaml",
    "content": "# distance_weights: [1. , .5, .2, .2 ]\ndistance_weights: [1., .5, .1, .05]\nmax_vel: 4\nmax_angular_vel: 8\nmax_acc: 25 # used for bounds on time\nmax_angular_acc: 20 # used for bounds on time\nmotor_control: true # True = controls are forces in the motors (False is NOT implemented)\nm: 0.034\nmax_f: 1.3\narm_length: 0.046\nt2t: 0.006 # thrust-to-torque ratio\nJ_v: [16.571710e-6, 16.655602e-6, 29.261652e-6] # inertia matrix\ndt: .01\nsize: [.25]\ndynamics: quad3d\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/data/pinocchio/crazyflie2.urdf",
    "content": "<?xml version=\"1.0\"?>\n<robot name=\"crazflie\">\n    \n    <link name=\"world\"></link>\n    \n    <joint name=\"freefly\" type=\"floating\">\n        <parent link=\"world\"/>\n        <child link=\"base\"/>\n        <axis xyz=\"1 1 1\"/>\n        <limit effort=\"1000.0\" lower=\"-100.0\" upper=\"100.0\" velocity=\"100.0\"/>\n    </joint>\n\n    <link name=\"base\">\n        <inertial>\n            <mass value=\"0.034\"/>\n            <origin xyz=\"0 0 0\"/>\n            <inertia ixx=\"16.571710e-6\" iyy=\"16.655602e-6\" izz=\"29.261652e-6\" ixy=\"0.0\" ixz=\"0.0\" iyx=\"0.0\" iyz=\"0.0\" izx=\"0.0\" izy=\"0.0\"/>\n        </inertial>\n\n        <collision>\n            <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>\n            <geometry>\n                <sphere radius=\"0.1\"/>\n            </geometry>\n        </collision>      \n    </link>\n</robot>"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/dynobench.py",
    "content": "from pathlib import Path\n\nimport numpy as np\nfrom rclpy.node import Node\nfrom rclpy.time import Time\nimport robot_python\nfrom rosgraph_msgs.msg import Clock\n\n# import sys\n# sys.path.append(\"/home/whoenig/projects/dynobench/build\")\n\nfrom ..sim_data_types import Action, State\n\n\nclass Backend:\n    \"\"\"Backend that uses newton-euler rigid-body dynamics implemented in numpy.\"\"\"\n\n    def __init__(self, node: Node, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.clock_publisher = node.create_publisher(Clock, 'clock', 10)\n        self.t = 0\n        self.dt = 0.0005\n\n        self.uavs = []\n        for state in states:\n            uav = Quadrotor(state)\n            self.uavs.append(uav)\n\n    def time(self) -> float:\n        return self.t\n\n    def step(self, states_desired: list[State], actions: list[Action]) -> list[State]:\n        # advance the time\n        self.t += self.dt\n\n        next_states = []\n\n        for uav, action in zip(self.uavs, actions):\n            uav.step(action, self.dt)\n            next_states.append(uav.state)\n\n        # print(states_desired, actions, next_states)\n        # publish the current clock\n        clock_message = Clock()\n        clock_message.clock = Time(seconds=self.time()).to_msg()\n        self.clock_publisher.publish(clock_message)\n\n        return next_states\n\n    def shutdown(self):\n        pass\n\n\n# convert RPM -> Force\ndef rpm_to_force(rpm):\n    # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id\n    p = [2.55077341e-08, -4.92422570e-05, -1.51910248e-01]\n    force_in_grams = np.polyval(p, rpm)\n    force_in_newton = force_in_grams * 9.81 / 1000.0\n    return np.maximum(force_in_newton, 0)\n\n\ndef sim_state2dynobench_state(state):\n    result = np.empty(13)\n    result[0:3] = state.pos\n    result[3:6] = state.quat[1:]\n    result[6] = state.quat[0]\n    result[7:10] = state.vel\n    result[10:13] = state.omega\n    return result\n\n\ndef dynobench_state2sim_state(state):\n    result = State()\n    result.pos = state[0:3]\n    result.quat = np.concatenate((state[6:7], state[3:6]))\n    result.vel = state[7:10]\n    result.omega = state[10:13]\n    return result\n\n\nclass Quadrotor:\n    \"\"\"Basic rigid body quadrotor model (no drag) using numpy and rowan.\"\"\"\n\n    def __init__(self, state):\n        self.uav = robot_python.robot_factory(\n            str((Path(__file__).parent / 'data/dynobench/crazyflie2.yaml').resolve()), [], [])\n        self.state = state\n\n    def step(self, action, dt):\n\n        # m: 0.034\n        # max_f: 1.3\n        force_in_newton = rpm_to_force(action.rpm)\n        normalized_force = force_in_newton / (1.3 * (0.034 / 4) * 9.81)\n\n        xnext = np.zeros(13)\n        self.uav.step(xnext, sim_state2dynobench_state(self.state), normalized_force, dt)\n        self.state = dynobench_state2sim_state(xnext)\n\n        # if we fall below the ground, set velocities to 0\n        if self.state.pos[2] < 0:\n            self.state.pos[2] = 0\n            self.state.vel = [0, 0, 0]\n            self.state.omega = [0, 0, 0]\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/neuralswarm.py",
    "content": "\"\"\"\nThis implementes interaction force prediction using NeuralSwarm(2).\n\nSee https://github.com/aerorobotics/neural-swarm\n\nLogic copied from https://github.com/aerorobotics/neural-swarm/blob/master/planning/robots.py\n\"\"\"\n\nfrom pathlib import Path\n\nimport numpy as np\nfrom rclpy.node import Node\nfrom rclpy.time import Time\nfrom rosgraph_msgs.msg import Clock\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nfrom .np import Quadrotor\nfrom ..sim_data_types import Action, State\n\n\n# H is the dimension of the hidden state\nclass phi_Net(nn.Module):\n\n    def __init__(self, inputdim=6, hiddendim=40):\n        super(phi_Net, self).__init__()\n        self.fc1 = nn.Linear(inputdim, 25)\n        self.fc2 = nn.Linear(25, 40)\n        self.fc3 = nn.Linear(40, 40)\n        self.fc4 = nn.Linear(40, hiddendim)\n\n    def forward(self, x):\n        x = F.relu(self.fc1(x))\n        x = F.relu(self.fc2(x))\n        x = F.relu(self.fc3(x))\n        x = self.fc4(x)\n        return x\n\n\nclass rho_Net(nn.Module):\n\n    def __init__(self, hiddendim=40):\n        super(rho_Net, self).__init__()\n        self.fc1 = nn.Linear(hiddendim, 40)\n        self.fc2 = nn.Linear(40, 40)\n        self.fc3 = nn.Linear(40, 40)\n        self.fc4 = nn.Linear(40, 1)\n\n    def forward(self, x):\n        x = F.relu(self.fc1(x))\n        x = F.relu(self.fc2(x))\n        x = F.relu(self.fc3(x))\n        x = self.fc4(x)\n        return x\n\n\nclass NeuralSwarm:\n\n    def __init__(self, model_folder):\n        self.H = 20\n        self.rho_L_net = rho_Net(hiddendim=self.H)\n        self.phi_L_net = phi_Net(inputdim=6, hiddendim=self.H)  # x,y,z,vx,vy,vz\n        self.rho_L_net.load_state_dict(torch.load('{}/rho_L.pth'.format(model_folder)))\n        self.phi_L_net.load_state_dict(torch.load('{}/phi_L.pth'.format(model_folder)))\n        self.rho_S_net = rho_Net(hiddendim=self.H)\n        self.phi_S_net = phi_Net(inputdim=6, hiddendim=self.H)  # x,y,z,vx,vy,vz\n        self.rho_S_net.load_state_dict(torch.load('{}/rho_S.pth'.format(model_folder)))\n        self.phi_S_net.load_state_dict(torch.load('{}/phi_S.pth'.format(model_folder)))\n        self.phi_G_net = phi_Net(inputdim=4, hiddendim=self.H)  # z,vx,vy,vz\n        self.phi_G_net.load_state_dict(torch.load('{}/phi_G.pth'.format(model_folder)))\n\n    def compute_Fa(self, data_self, data_neighbors):\n        rho_input = torch.zeros(self.H)\n        cftype, x = data_self\n        for cftype_neighbor, x_neighbor in data_neighbors:\n            x_12 = torch.zeros(6)\n            x_12 = (x_neighbor - x).float()\n            if abs(x_12[0]) < 0.2 and abs(x_12[1]) < 0.2 and abs(x_12[3]) < 1.5:\n                if cftype_neighbor == 'small' or cftype_neighbor == 'small_powerful_motors':\n                    rho_input += self.phi_S_net(x_12)\n                elif cftype_neighbor == 'large':\n                    rho_input += self.phi_L_net(x_12)\n                else:\n                    raise Exception('Unknown cftype!')\n\n        # interaction with the ground\n        x_12 = torch.zeros(4)\n        x_12[0] = 0 - x[2]\n        x_12[1:4] = -x[3:6]\n        rho_input += self.phi_G_net(x_12)\n\n        if cftype == 'small' or cftype == 'small_powerful_motors':\n            faz = self.rho_S_net(rho_input)\n        elif cftype == 'large':\n            faz = self.rho_L_net(rho_input)\n        else:\n            raise Exception('Unknown cftype!')\n\n        return np.array([0, 0, faz[0].item()])\n\n\nclass Backend:\n    \"\"\"Backend that is based on the one defined in np.py.\"\"\"\n\n    def __init__(self, node: Node, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.clock_publisher = node.create_publisher(Clock, 'clock', 10)\n        self.t = 0\n        self.dt = 0.0005\n\n        self.uavs = []\n        for state in states:\n            uav = Quadrotor(state)\n            self.uavs.append(uav)\n        self.neuralswarm = NeuralSwarm(Path(__file__).parent / 'data/neuralswarm2')\n\n    def time(self) -> float:\n        return self.t\n\n    def step(self, states_desired: list[State], actions: list[Action]) -> list[State]:\n        # advance the time\n        self.t += self.dt\n\n        fa_data = []\n        for uav in self.uavs:\n            fa_data.append(('small', torch.hstack(\n                (torch.tensor(uav.state.pos), torch.tensor(uav.state.vel)))))\n\n        next_states = []\n        for k, (uav, action) in enumerate(zip(self.uavs, actions)):\n            # estimate F_a\n            # print(k, fa_data[k], fa_data[0:k] + fa_data[k+1:])\n            f_a = self.neuralswarm.compute_Fa(fa_data[k], fa_data[0:k] + fa_data[k+1:])\n            # convert grams to Newtons\n            f_a = f_a / 1000 * 9.81\n            # print(f_a)\n            uav.step(action, self.dt, f_a)\n            next_states.append(uav.state)\n\n        # print(states_desired, actions, next_states)\n        # publish the current clock\n        clock_message = Clock()\n        clock_message.clock = Time(seconds=self.time()).to_msg()\n        self.clock_publisher.publish(clock_message)\n\n        return next_states\n\n    def shutdown(self):\n        pass\n\n\nif __name__ == '__main__':\n\n    # test case, see Fig 5g in NeuralSwarm2 paper\n    ns = NeuralSwarm(Path(__file__).parent / 'data/neuralswarm2')\n\n    # x, y, z, vx, vy, vz\n    states = torch.tensor([\n        [0, 0, 0.6, 0, 0, 0],\n        [0, -0.1, 0.5, 0, 0, 0],\n        [0, 0.1, 0.5, 0, 0, 0],\n        [0, 0, 0.3, 0, 0, 0],\n    ])\n\n    print(ns.compute_Fa(('small', states[3]),\n                        [('small', states[0]),\n                        ('small', states[1]),\n                        ('small', states[2])]))\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/none.py",
    "content": "from __future__ import annotations\n\nfrom rclpy.node import Node\nfrom rclpy.time import Time\nfrom rosgraph_msgs.msg import Clock\n\nfrom ..sim_data_types import Action, State\n\n\nclass Backend:\n    \"\"\"Tracks the desired state perfectly (no physics simulation).\"\"\"\n\n    def __init__(self, node: Node, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.clock_publisher = node.create_publisher(Clock, 'clock', 10)\n        self.t = 0\n        self.dt = 0.1\n\n    def time(self) -> float:\n        return self.t\n\n    def step(self, states_desired: list[State], actions: list[Action]) -> list[State]:\n        # advance the time\n        self.t += self.dt\n\n        # publish the current clock\n        clock_message = Clock()\n        clock_message.clock = Time(seconds=self.time()).to_msg()\n        self.clock_publisher.publish(clock_message)\n\n        # pretend we were able to follow desired states perfectly\n        return states_desired\n\n    def shutdown(self):\n        pass\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/np.py",
    "content": "from __future__ import annotations\n\nimport numpy as np\nfrom rclpy.node import Node\nfrom rclpy.time import Time\nfrom rosgraph_msgs.msg import Clock\nimport rowan\n\nfrom ..sim_data_types import Action, State\n\n\nclass Backend:\n    \"\"\"Backend that uses newton-euler rigid-body dynamics implemented in numpy.\"\"\"\n\n    def __init__(self, node: Node, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.clock_publisher = node.create_publisher(Clock, 'clock', 10)\n        self.t = 0\n        self.dt = 0.0005\n\n        self.uavs = []\n        for state in states:\n            uav = Quadrotor(state)\n            self.uavs.append(uav)\n\n    def time(self) -> float:\n        return self.t\n\n    def step(self, states_desired: list[State], actions: list[Action]) -> list[State]:\n        # advance the time\n        self.t += self.dt\n\n        next_states = []\n\n        for uav, action in zip(self.uavs, actions):\n            uav.step(action, self.dt)\n            next_states.append(uav.state)\n\n        # print(states_desired, actions, next_states)\n        # publish the current clock\n        clock_message = Clock()\n        clock_message.clock = Time(seconds=self.time()).to_msg()\n        self.clock_publisher.publish(clock_message)\n\n        return next_states\n\n    def shutdown(self):\n        pass\n\n\nclass Quadrotor:\n    \"\"\"Basic rigid body quadrotor model (no drag) using numpy and rowan.\"\"\"\n\n    def __init__(self, state):\n        # parameters (Crazyflie 2.0 quadrotor)\n        self.mass = 0.034  # kg\n        # self.J = np.array([\n        # \t[16.56,0.83,0.71],\n        # \t[0.83,16.66,1.8],\n        # \t[0.72,1.8,29.26]\n        # \t]) * 1e-6  # kg m^2\n        self.J = np.array([16.571710e-6, 16.655602e-6, 29.261652e-6])\n\n        # Note: we assume here that our control is forces\n        arm_length = 0.046  # m\n        arm = 0.707106781 * arm_length\n        t2t = 0.006  # thrust-to-torque ratio\n        self.B0 = np.array([\n            [1, 1, 1, 1],\n            [-arm, -arm, arm, arm],\n            [-arm, arm, arm, -arm],\n            [-t2t, t2t, -t2t, t2t]\n            ])\n        self.g = 9.81  # not signed\n\n        if self.J.shape == (3, 3):\n            self.inv_J = np.linalg.pinv(self.J)  # full matrix -> pseudo inverse\n        else:\n            self.inv_J = 1 / self.J  # diagonal matrix -> division\n\n        self.state = state\n\n    def step(self, action, dt, f_a=np.zeros(3)):\n\n        # convert RPM -> Force\n        def rpm_to_force(rpm):\n            # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id\n            p = [2.55077341e-08, -4.92422570e-05, -1.51910248e-01]\n            force_in_grams = np.polyval(p, rpm)\n            force_in_newton = force_in_grams * 9.81 / 1000.0\n            return np.maximum(force_in_newton, 0)\n\n        force = rpm_to_force(action.rpm)\n\n        # compute next state\n        eta = np.dot(self.B0, force)\n        f_u = np.array([0, 0, eta[0]])\n        tau_u = np.array([eta[1], eta[2], eta[3]])\n\n        # dynamics\n        # dot{p} = v\n        pos_next = self.state.pos + self.state.vel * dt\n        # mv = mg + R f_u + f_a\n        vel_next = self.state.vel + (\n            np.array([0, 0, -self.g]) +\n            (rowan.rotate(self.state.quat, f_u) + f_a) / self.mass) * dt\n\n        # dot{R} = R S(w)\n        # to integrate the dynamics, see\n        # https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/, and\n        # https://arxiv.org/pdf/1604.08139.pdf\n        # Sec 4.5, https://arxiv.org/pdf/1711.02508.pdf\n        omega_global = rowan.rotate(self.state.quat, self.state.omega)\n        q_next = rowan.normalize(\n            rowan.calculus.integrate(\n                self.state.quat, omega_global, dt))\n\n        # mJ = Jw x w + tau_u\n        omega_next = self.state.omega + (\n            self.inv_J * (np.cross(self.J * self.state.omega, self.state.omega) + tau_u)) * dt\n\n        self.state.pos = pos_next\n        self.state.vel = vel_next\n        self.state.quat = q_next\n        self.state.omega = omega_next\n\n        # if we fall below the ground, set velocities to 0\n        if self.state.pos[2] < 0:\n            self.state.pos[2] = 0\n            self.state.vel = [0, 0, 0]\n            self.state.omega = [0, 0, 0]\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/backend/pinocchio.py",
    "content": "from pathlib import Path\n\nimport numpy as np\nimport pinocchio as pin\nfrom rclpy.node import Node\nfrom rclpy.time import Time\nfrom rosgraph_msgs.msg import Clock\n\nfrom ..sim_data_types import Action, State\n\n\nclass Backend:\n    \"\"\"Backend that uses pinocchio to simulate the rigid-body dynamics.\"\"\"\n\n    def __init__(self, node: Node, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.clock_publisher = node.create_publisher(Clock, 'clock', 10)\n        self.t = 0\n        self.dt = 0.0005\n\n        self.uavs = []\n        for state in states:\n            uav = Quadrotor(state)\n            self.uavs.append(uav)\n\n    def time(self) -> float:\n        return self.t\n\n    def step(self, states_desired: list[State], actions: list[Action]) -> list[State]:\n        # advance the time\n        self.t += self.dt\n\n        next_states = []\n\n        for uav, action in zip(self.uavs, actions):\n            uav.step(action, self.dt)\n            next_states.append(uav.state)\n\n        # print(states_desired, actions, next_states)\n        # publish the current clock\n        clock_message = Clock()\n        clock_message.clock = Time(seconds=self.time()).to_msg()\n        self.clock_publisher.publish(clock_message)\n\n        return next_states\n\n    def shutdown(self):\n        pass\n\n\n# convert RPM -> Force\ndef rpm_to_force(rpm):\n    # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id\n    p = [2.55077341e-08, -4.92422570e-05, -1.51910248e-01]\n    force_in_grams = np.polyval(p, rpm)\n    force_in_newton = force_in_grams * 9.81 / 1000.0\n    return np.maximum(force_in_newton, 0)\n\n\ndef pinocchio_state2sim_state(q, v):\n    result = State()\n    result.pos = q[0:3]\n    result.quat = np.concatenate((q[6:7], q[3:6]))\n    result.vel = v[0:3]\n    result.omega = v[3:6]\n    return result\n\n\ndef sim_state2pinocchio_state(state):\n    result = np.empty(13)\n    result[0:3] = state.pos\n    result[3:6] = state.quat[1:]\n    result[6] = state.quat[0]\n    result[7:10] = state.vel\n    result[10:13] = state.omega\n    q = result[0:7]  # geometric states: x, y, z, qx, qy, qz, qw\n    v = result[7:]  # velocities: vx, vy, vz, wx, wy, wz\n    return q, v\n\n\nclass Quadrotor:\n    \"\"\"Basic rigid body quadrotor model (no drag) using numpy and rowan.\"\"\"\n\n    def __init__(self, state):\n        arm_length = 0.046  # m\n        arm = 0.707106781 * arm_length\n        t2t = 0.006  # thrust-to-torque ratio\n        self.B0 = np.array([\n            [1, 1, 1, 1],\n            [-arm, -arm, arm, arm],\n            [-arm, arm, arm, -arm],\n            [-t2t, t2t, -t2t, t2t]\n            ])\n        self.uav, self.collision_model, self.visual_model = pin.buildModelsFromUrdf(\n            str((Path(__file__).parent / 'data/pinocchio/crazyflie2.urdf')))\n        self.uavPinocchioData = self.uav.createData()\n        self.state = state\n\n    def step(self, action, dt):\n\n        # m: 0.034\n        # max_f: 1.3\n        force_in_newton = rpm_to_force(action.rpm)\n        eta = np.dot(self.B0, force_in_newton)\n        force_generalized = np.array([0., 0., eta[0], eta[1], eta[2], eta[3]])\n\n        q, v = sim_state2pinocchio_state(self.state)\n        a = pin.aba(self.uav, self.uavPinocchioData, q, v, force_generalized)\n        v_next = v + a*dt\n        q_next = pin.integrate(self.uav, q, v*dt)\n        self.state = pinocchio_state2sim_state(q_next, v_next)\n\n        # if we fall below the ground, set velocities to 0\n        if self.state.pos[2] < 0:\n            self.state.pos[2] = 0\n            self.state.vel = [0, 0, 0]\n            self.state.omega = [0, 0, 0]\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/crazyflie_server.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nA crazyflie server for simulation.\n\n    2022 - Wolfgang Hönig (TU Berlin)\n    2025 - Updated by Kimberly N. McGuire (Independent)\n\"\"\"\n\nfrom functools import partial\nimport importlib\n\nfrom crazyflie_interfaces.msg import FullState, Hover\nfrom crazyflie_interfaces.srv import GoTo, Land, Takeoff\nfrom crazyflie_interfaces.srv import NotifySetpointsStop, StartTrajectory, UploadTrajectory\nfrom geometry_msgs.msg import Twist\nimport rclpy\nfrom rclpy.node import Node\nimport rowan\nfrom std_msgs.msg import String\nfrom std_srvs.srv import Empty\n\n\n# import BackendRviz from .backend_rviz\n# from .backend import *\n# from .backend.none import BackendNone\nfrom .crazyflie_sil import CrazyflieSIL, TrajectoryPolynomialPiece\nfrom .sim_data_types import State\n\n\nclass CrazyflieServer(Node):\n\n    def __init__(self):\n        super().__init__(\n            'crazyflie_server',\n            allow_undeclared_parameters=True,\n            automatically_declare_parameters_from_overrides=True,\n        )\n\n        # Turn ROS parameters into a dictionary\n        self._ros_parameters = self._param_to_dict(self._parameters)\n        self.cfs = {}\n\n        world_tf_name = 'world'\n        robot_yaml_version = 0\n\n        try:\n            robot_yaml_version = self._ros_parameters['fileversion']\n        except KeyError:\n            self.get_logger().info('No fileversion found in crazyflies.yaml, assuming version 0')\n\n        robot_data = self._ros_parameters['robots']\n\n        # Parse robots\n        names = []\n        initial_states = []\n        reference_frames = []\n        for cfname in robot_data:\n            if robot_data[cfname]['enabled']:\n                type_cf = robot_data[cfname]['type']\n                # do not include virtual objects\n                connection = self._ros_parameters['robot_types'][type_cf].get(\n                    'connection', 'crazyflie')\n                if connection == 'crazyflie':\n                    names.append(cfname)\n                    pos = robot_data[cfname]['initial_position']\n                    initial_states.append(State(pos))\n                    # Get the current reference frame for the robot\n                    reference_frame = world_tf_name\n                    if robot_yaml_version >= 3:\n                        try:\n                            reference_frame = self._ros_parameters['all']['reference_frame']\n                        except KeyError:\n                            pass\n                        try:\n                            reference_frame = self._ros_parameters['robot_types'][\n                                robot_data[cfname]['type']]['reference_frame']\n                        except KeyError:\n                            pass\n                        try:\n                            reference_frame = self._ros_parameters['robots'][\n                                cfname]['reference_frame']\n                        except KeyError:\n                            pass\n                    reference_frames.append(reference_frame)\n\n        # initialize backend by dynamically loading the module\n        backend_name = self._ros_parameters['sim']['backend']\n        module = importlib.import_module(\n            '.backend.' + backend_name, package='crazyflie_sim'\n        )\n        class_ = getattr(module, 'Backend')\n        self.backend = class_(self, names, initial_states)\n\n        # initialize visualizations by dynamically loading the modules\n        self.visualizations = []\n        for vis_key in self._ros_parameters['sim']['visualizations']:\n            if self._ros_parameters['sim']['visualizations'][vis_key]['enabled']:\n                module = importlib.import_module(\n                    '.visualization.' + str(vis_key), package='crazyflie_sim'\n                )\n                class_ = getattr(module, 'Visualization')\n                if vis_key == 'rviz':\n                    # special case for rviz, which needs the reference frames\n                    vis = class_(\n                        self,\n                        self._ros_parameters['sim']['visualizations'][vis_key],\n                        names,\n                        initial_states,\n                        reference_frames\n                    )\n                else:\n                    vis = class_(\n                        self,\n                        self._ros_parameters['sim']['visualizations'][vis_key],\n                        names,\n                        initial_states\n                    )\n                self.visualizations.append(vis)\n\n        controller_name = backend_name = self._ros_parameters['sim']['controller']\n\n        # create robot SIL objects\n        for name, initial_state in zip(names, initial_states):\n            self.cfs[name] = CrazyflieSIL(\n                name,\n                initial_state.pos,\n                controller_name,\n                self.backend.time)\n\n        for name, _ in self.cfs.items():\n            pub = self.create_publisher(\n                    String,\n                    name + '/robot_description',\n                    rclpy.qos.QoSProfile(\n                        depth=1,\n                        durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL))\n\n            msg = String()\n            msg.data = self._ros_parameters['robot_description'].replace('$NAME', name)\n            pub.publish(msg)\n\n            self.create_service(\n                Empty,\n                name + '/emergency',\n                partial(self._emergency_callback, name=name)\n            )\n            self.create_service(\n                Takeoff,\n                name + '/takeoff',\n                partial(self._takeoff_callback, name=name)\n            )\n            self.create_service(\n                Land,\n                name + '/land',\n                partial(self._land_callback, name=name)\n            )\n            self.create_service(\n                GoTo,\n                name + '/go_to',\n                partial(self._go_to_callback, name=name)\n            )\n            self.create_service(\n                StartTrajectory,\n                name + '/start_trajectory',\n                partial(self._start_trajectory_callback, name=name)\n            )\n            self.create_service(\n                UploadTrajectory,\n                name + '/upload_trajectory',\n                partial(self._upload_trajectory_callback, name=name)\n            )\n            self.create_service(\n                NotifySetpointsStop,\n                name + '/notify_setpoints_stop',\n                partial(self._notify_setpoints_stop_callback, name=name)\n            )\n            self.create_subscription(\n                Twist,\n                name + '/cmd_vel_legacy',\n                partial(self._cmd_vel_legacy_changed, name=name),\n                10\n            )\n            self.create_subscription(\n                Hover,\n                name + '/cmd_hover',\n                partial(self._cmd_hover_changed, name=name),\n                10\n            )\n            self.create_subscription(\n                FullState,\n                name + '/cmd_full_state',\n                partial(self._cmd_full_state_changed, name=name),\n                10\n            )\n\n        # Create services for the entire swarm and each individual crazyflie\n        self.create_service(Takeoff, 'all/takeoff', self._takeoff_callback)\n        self.create_service(Land, 'all/land', self._land_callback)\n        self.create_service(GoTo, 'all/go_to', self._go_to_callback)\n        self.create_service(StartTrajectory,\n                            'all/start_trajectory',\n                            self._start_trajectory_callback)\n\n        # This is the last service to announce.\n        # Can be used to check if the server is fully available.\n        self.create_service(Empty, 'all/emergency', self._emergency_callback)\n\n        # step as fast as possible\n        max_dt = 0.0 if 'max_dt' not in self._ros_parameters['sim'] \\\n            else self._ros_parameters['sim']['max_dt']\n        self.timer = self.create_timer(max_dt, self._timer_callback)\n        self.is_shutdown = False\n\n    def on_shutdown_callback(self):\n        if not self.is_shutdown:\n            self.backend.shutdown()\n            for visualization in self.visualizations:\n                visualization.shutdown()\n\n            self.is_shutdown = True\n\n    def _timer_callback(self):\n        # update setpoint\n        states_desired = [cf.getSetpoint() for _, cf in self.cfs.items()]\n\n        # execute the control loop\n        actions = [cf.executeController() for _, cf in self.cfs.items()]\n\n        # execute the physics simulator\n        states_next = self.backend.step(states_desired, actions)\n\n        # update the resulting state\n        for state, (_, cf) in zip(states_next, self.cfs.items()):\n            cf.setState(state)\n\n        for vis in self.visualizations:\n            vis.step(self.backend.time(), states_next, states_desired, actions)\n\n    def _param_to_dict(self, param_ros):\n        \"\"\"Turn ROS 2 parameters from the node into a dict.\"\"\"\n        tree = {}\n        for item in param_ros:\n            t = tree\n            for part in item.split('.'):\n                if part == item.split('.')[-1]:\n                    t = t.setdefault(part, param_ros[item].value)\n                else:\n                    t = t.setdefault(part, {})\n        return tree\n\n    def _emergency_callback(self, request, response, name='all'):\n        self.get_logger().info(f'[{name}] emergency not yet implemented')\n\n        return response\n\n    def _takeoff_callback(self, request, response, name='all'):\n        \"\"\"Service callback to takeoff the crazyflie.\"\"\"\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n        self.get_logger().info(\n            f'[{name}] takeoff(height={request.height} m,'\n            + f'duration={duration} s,'\n            + f'group_mask={request.group_mask})'\n        )\n        cfs = self.cfs if name == 'all' else {name: self.cfs[name]}\n        for _, cf in cfs.items():\n            cf.takeoff(request.height, duration, request.group_mask)\n\n        return response\n\n    def _land_callback(self, request, response, name='all'):\n        \"\"\"Service callback to land the crazyflie.\"\"\"\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n        self.get_logger().info(\n            f'[{name}] land(height={request.height} m,'\n            + f'duration={duration} s,'\n            + f'group_mask={request.group_mask})'\n        )\n        cfs = self.cfs if name == 'all' else {name: self.cfs[name]}\n        for _, cf in cfs.items():\n            cf.land(request.height, duration, request.group_mask)\n\n        return response\n\n    def _go_to_callback(self, request, response, name='all'):\n        \"\"\"Service callback to have the crazyflie go to a position.\"\"\"\n        duration = float(request.duration.sec) + \\\n            float(request.duration.nanosec / 1e9)\n\n        self.get_logger().info(\n            \"\"\"[%s] go_to(position=%f,%f,%f m,\n             yaw=%f rad,\n             duration=%f s,\n             relative=%d,\n             group_mask=%d)\"\"\"\n            % (\n                name,\n                request.goal.x,\n                request.goal.y,\n                request.goal.z,\n                request.yaw,\n                duration,\n                request.relative,\n                request.group_mask,\n            )\n        )\n        cfs = self.cfs if name == 'all' else {name: self.cfs[name]}\n        for _, cf in cfs.items():\n            cf.goTo([request.goal.x, request.goal.y, request.goal.z],\n                    request.yaw, duration, request.relative, request.group_mask)\n\n        return response\n\n    def _notify_setpoints_stop_callback(self, request, response, name='all'):\n        self.get_logger().info(f'[{name}] Notify setpoint stop not yet implemented')\n        return response\n\n    def _upload_trajectory_callback(self, request, response, name='all'):\n        self.get_logger().info('[%s] Upload trajectory(id=%d)' % (name, request.trajectory_id))\n\n        cfs = self.cfs if name == 'all' else {name: self.cfs[name]}\n        for _, cf in cfs.items():\n            pieces = []\n            for piece in request.pieces:\n                poly_x = piece.poly_x\n                poly_y = piece.poly_y\n                poly_z = piece.poly_z\n                poly_yaw = piece.poly_yaw\n                duration = float(piece.duration.sec) + \\\n                    float(piece.duration.nanosec / 1e9)\n                pieces.append(TrajectoryPolynomialPiece(\n                    poly_x,\n                    poly_y,\n                    poly_z,\n                    poly_yaw,\n                    duration))\n            cf.uploadTrajectory(request.trajectory_id, request.piece_offset, pieces)\n\n        return response\n\n    def _start_trajectory_callback(self, request, response, name='all'):\n        self.get_logger().info(\n            '[%s] start_trajectory(id=%d, timescale=%f, reverse=%d, relative=%d, group_mask=%d)'\n            % (\n                name,\n                request.trajectory_id,\n                request.timescale,\n                request.reversed,\n                request.relative,\n                request.group_mask,\n            )\n        )\n        cfs = self.cfs if name == 'all' else {name: self.cfs[name]}\n        for _, cf in cfs.items():\n            cf.startTrajectory(\n                request.trajectory_id,\n                request.timescale,\n                request.reversed,\n                request.relative,\n                request.group_mask)\n\n        return response\n\n    def _cmd_vel_legacy_changed(self, msg, name=''):\n        \"\"\"\n        Topic update callback.\n\n        Controls the attitude and thrust of the crazyflie with teleop.\n        \"\"\"\n        self.get_logger().info('cmd_vel_legacy not yet implemented')\n\n    def _cmd_hover_changed(self, msg, name=''):\n        \"\"\"\n        Topic update callback for hover command.\n\n        Used from the velocity multiplexer (vel_mux).\n        \"\"\"\n        self.get_logger().info('cmd_hover not yet implemented')\n\n    def _cmd_full_state_changed(self, msg, name):\n        q = [msg.pose.orientation.w,\n             msg.pose.orientation.x,\n             msg.pose.orientation.y,\n             msg.pose.orientation.z]\n        rpy = rowan.to_euler(q, convention='xyz')\n\n        self.cfs[name].cmdFullState(\n            [msg.pose.position.x, msg.pose.position.y, msg.pose.position.z],\n            [msg.twist.linear.x, msg.twist.linear.y, msg.twist.linear.z],\n            [msg.acc.x, msg.acc.y, msg.acc.z],\n            rpy[2],\n            [msg.twist.angular.x, msg.twist.angular.y, msg.twist.angular.z])\n\n\ndef main(args=None):\n\n    rclpy.init(args=args)\n    crazyflie_server = CrazyflieServer()\n    rclpy.get_default_context().on_shutdown(crazyflie_server.on_shutdown_callback)\n\n    try:\n        rclpy.spin(crazyflie_server)\n    except KeyboardInterrupt:\n        crazyflie_server.on_shutdown_callback()\n    finally:\n        rclpy.try_shutdown()\n        crazyflie_server.destroy_node()\n\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/crazyflie_sil.py",
    "content": "#!/usr/bin/env python3\n\n\"\"\"\nCrazyflie Software-In-The-Loop Wrapper that uses the firmware Python bindings.\n\n    2022 - Wolfgang Hönig (TU Berlin)\n\"\"\"\nfrom __future__ import annotations\n\nimport cffirmware as firm\nimport numpy as np\nimport rowan\n\nfrom . import sim_data_types\n\n\nclass TrajectoryPolynomialPiece:\n\n    def __init__(self, poly_x, poly_y, poly_z, poly_yaw, duration):\n        self.poly_x = poly_x\n        self.poly_y = poly_y\n        self.poly_z = poly_z\n        self.poly_yaw = poly_yaw\n        self.duration = duration\n\n\ndef copy_svec(v):\n    return firm.mkvec(v.x, v.y, v.z)\n\n\nclass CrazyflieSIL:\n\n    # Flight modes.\n    MODE_IDLE = 0\n    MODE_HIGH_POLY = 1\n    MODE_LOW_FULLSTATE = 2\n    MODE_LOW_POSITION = 3\n    MODE_LOW_VELOCITY = 4\n\n    def __init__(self, name, initialPosition, controller_name, time_func):\n        # Core.\n        self.name = name\n        self.groupMask = 0\n        self.initialPosition = np.array(initialPosition)\n        self.time_func = time_func\n\n        # Commander.\n        self.mode = CrazyflieSIL.MODE_IDLE\n        self.planner = firm.planner()\n        firm.plan_init(self.planner)\n        self.trajectories = {}\n\n        # previous state for HL commander\n        self.cmdHl_pos = firm.mkvec(*initialPosition)\n        self.cmdHl_vel = firm.vzero()\n        self.cmdHl_yaw = 0\n\n        # current setpoint\n        self.setpoint = firm.setpoint_t()\n\n        # latest sensor values.\n        self.state = firm.state_t()\n        self.state.position.x = self.initialPosition[0]\n        self.state.position.y = self.initialPosition[1]\n        self.state.position.z = self.initialPosition[2]\n        self.state.velocity.x = 0\n        self.state.velocity.y = 0\n        self.state.velocity.z = 0\n        self.state.attitude.roll = 0\n        self.state.attitude.pitch = -0  # WARNING: this is in the legacy coordinate system\n        self.state.attitude.yaw = 0\n\n        self.sensors = firm.sensorData_t()\n        self.sensors.gyro.x = 0\n        self.sensors.gyro.y = 0\n        self.sensors.gyro.z = 0\n\n        # current controller output\n        self.control = firm.control_t()\n        self.motors_thrust_uncapped = firm.motors_thrust_uncapped_t()\n        self.motors_thrust_pwm = firm.motors_thrust_pwm_t()\n\n        self.controller_name = controller_name\n\n        # set up controller\n        if controller_name == 'none':\n            self.controller = None\n        elif controller_name == 'pid':\n            firm.controllerPidInit()\n            self.controller = firm.controllerPid\n        elif controller_name == 'mellinger':\n            self.mellinger_control = firm.controllerMellinger_t()\n            firm.controllerMellingerInit(self.mellinger_control)\n            self.controller = firm.controllerMellinger\n        elif controller_name == 'brescianini':\n            firm.controllerBrescianiniInit()\n            self.controller = firm.controllerBrescianini\n        else:\n            raise ValueError('Unknown controller {}'.format(controller_name))\n\n    def setGroupMask(self, groupMask):\n        self.groupMask = groupMask\n\n    def takeoff(self, targetHeight, duration, groupMask=0):\n        if self._isGroup(groupMask):\n            self.mode = CrazyflieSIL.MODE_HIGH_POLY\n            targetYaw = 0.0\n            firm.plan_takeoff(\n                self.planner,\n                self.cmdHl_pos,\n                self.cmdHl_yaw,\n                targetHeight, targetYaw, duration, self.time_func())\n\n    def land(self, targetHeight, duration, groupMask=0):\n        if self._isGroup(groupMask):\n            self.mode = CrazyflieSIL.MODE_HIGH_POLY\n            targetYaw = 0.0\n            firm.plan_land(\n                self.planner,\n                self.cmdHl_pos,\n                self.cmdHl_yaw,\n                targetHeight, targetYaw, duration, self.time_func())\n\n    # def stop(self, groupMask = 0):\n    #     if self._isGroup(groupMask):\n    #         self.mode = CrazyflieSIL.MODE_IDLE\n    #         firm.plan_stop(self.planner)\n\n    def goTo(self, goal, yaw, duration, relative=False, groupMask=0):\n        if self._isGroup(groupMask):\n            if self.mode != CrazyflieSIL.MODE_HIGH_POLY:\n                # We need to update to the latest firmware that has go_to_from.\n                raise ValueError('goTo from low-level modes not yet supported.')\n            self.mode = CrazyflieSIL.MODE_HIGH_POLY\n            try:\n                firm.plan_go_to(\n                    self.planner,\n                    relative,\n                    False,\n                    firm.mkvec(*goal),\n                    yaw, duration, self.time_func())\n            except TypeError:\n                message = ('Warning: Your Crazyflie firmware is outdated. '\n                           ' Please update to the latest version.')\n                print(message)\n                firm.plan_go_to(\n                    self.planner,\n                    relative,\n                    firm.mkvec(*goal),\n                    yaw, duration, self.time_func())\n\n    def uploadTrajectory(self,\n                         trajectoryId: int,\n                         pieceOffset: int,\n                         pieces: list[TrajectoryPolynomialPiece]):\n        traj = firm.piecewise_traj()\n        traj.t_begin = 0\n        traj.timescale = 1.0\n        traj.shift = firm.mkvec(0, 0, 0)\n        traj.n_pieces = len(pieces)\n        traj.pieces = firm.poly4d_malloc(traj.n_pieces)\n        for i, piece in enumerate(pieces):\n            fwpiece = firm.piecewise_get(traj, i)\n            fwpiece.duration = piece.duration\n            for coef in range(0, 8):\n                firm.poly4d_set(fwpiece, 0, coef, piece.poly_x[coef])\n                firm.poly4d_set(fwpiece, 1, coef, piece.poly_y[coef])\n                firm.poly4d_set(fwpiece, 2, coef, piece.poly_z[coef])\n                firm.poly4d_set(fwpiece, 3, coef, piece.poly_yaw[coef])\n        self.trajectories[trajectoryId] = traj\n\n    def startTrajectory(self,\n                        trajectoryId: int,\n                        timescale: float = 1.0,\n                        reverse: bool = False,\n                        relative: bool = True,\n                        groupMask: int = 0):\n        if self._isGroup(groupMask):\n            self.mode = CrazyflieSIL.MODE_HIGH_POLY\n            traj = self.trajectories[trajectoryId]\n            traj.t_begin = self.time_func()\n            traj.timescale = timescale\n            startfrom = self.cmdHl_pos\n            firm.plan_start_trajectory(self.planner, traj, reverse, relative, startfrom)\n\n    # def notifySetpointsStop(self, remainValidMillisecs=100):\n    #     # No-op - the real Crazyflie prioritizes streaming setpoints over\n    #     # high-level commands. This tells it to stop doing that. We don't\n    #     # simulate this behavior.\n    #     pass\n\n    def cmdFullState(self, pos, vel, acc, yaw, omega):\n        self.mode = CrazyflieSIL.MODE_LOW_FULLSTATE\n        self.setpoint.position.x = pos[0]\n        self.setpoint.position.y = pos[1]\n        self.setpoint.position.z = pos[2]\n        self.setpoint.velocity.x = vel[0]\n        self.setpoint.velocity.y = vel[1]\n        self.setpoint.velocity.z = vel[2]\n        self.setpoint.attitude.yaw = np.degrees(yaw)\n        self.setpoint.attitudeRate.roll = np.degrees(omega[0])\n        self.setpoint.attitudeRate.pitch = np.degrees(omega[1])\n        self.setpoint.attitudeRate.yaw = np.degrees(omega[2])\n        self.setpoint.mode.x = firm.modeAbs\n        self.setpoint.mode.y = firm.modeAbs\n        self.setpoint.mode.z = firm.modeAbs\n        self.setpoint.mode.roll = firm.modeDisable\n        self.setpoint.mode.pitch = firm.modeDisable\n        self.setpoint.mode.yaw = firm.modeAbs\n        self.setpoint.mode.quat = firm.modeDisable\n        self.setpoint.acceleration.x = acc[0]\n        self.setpoint.acceleration.y = acc[1]\n        self.setpoint.acceleration.z = acc[2]\n\n        self.cmdHl_pos = copy_svec(self.setpoint.position)\n        self.cmdHl_vel = copy_svec(self.setpoint.velocity)\n        self.cmdHl_yaw = yaw\n\n    # def cmdPosition(self, pos, yaw = 0):\n    #     self.mode = CrazyflieSIL.MODE_LOW_POSITION\n    #     self.setState.pos = firm.mkvec(*pos)\n    #     self.setState.yaw = yaw\n    #     # TODO: should we set vel, acc, omega to zero, or rely on modes to not read them?\n\n    # def cmdVelocityWorld(self, vel, yawRate):\n    #     self.mode = CrazyflieSIL.MODE_LOW_VELOCITY\n    #     self.setState.vel = firm.mkvec(*vel)\n    #     self.setState.omega = firm.mkvec(0.0, 0.0, yawRate)\n    #     # TODO: should we set pos, acc, yaw to zero, or rely on modes to not read them?\n\n    # def cmdStop(self):\n    #     # TODO: set mode to MODE_IDLE?\n    #     pass\n\n    def getSetpoint(self):\n        if self.mode == CrazyflieSIL.MODE_HIGH_POLY:\n            # See logic in crtp_commander_high_level.c\n            ev = firm.plan_current_goal(self.planner, self.time_func())\n            if firm.is_traj_eval_valid(ev):\n                self.setpoint.position.x = ev.pos.x\n                self.setpoint.position.y = ev.pos.y\n                self.setpoint.position.z = ev.pos.z\n                self.setpoint.velocity.x = ev.vel.x\n                self.setpoint.velocity.y = ev.vel.y\n                self.setpoint.velocity.z = ev.vel.z\n                self.setpoint.attitude.yaw = np.degrees(ev.yaw)\n                self.setpoint.attitudeRate.roll = np.degrees(ev.omega.x)\n                self.setpoint.attitudeRate.pitch = np.degrees(ev.omega.y)\n                self.setpoint.attitudeRate.yaw = np.degrees(ev.omega.z)\n                self.setpoint.mode.x = firm.modeAbs\n                self.setpoint.mode.y = firm.modeAbs\n                self.setpoint.mode.z = firm.modeAbs\n                self.setpoint.mode.roll = firm.modeDisable\n                self.setpoint.mode.pitch = firm.modeDisable\n                self.setpoint.mode.yaw = firm.modeAbs\n                self.setpoint.mode.quat = firm.modeDisable\n                self.setpoint.acceleration.x = ev.acc.x\n                self.setpoint.acceleration.y = ev.acc.y\n                self.setpoint.acceleration.z = ev.acc.z\n\n                self.cmdHl_pos = copy_svec(ev.pos)\n                self.cmdHl_vel = copy_svec(ev.vel)\n                self.cmdHl_yaw = ev.yaw\n\n        return self._fwsetpoint_to_sim_data_types_state(self.setpoint)\n\n        # # else:\n        #     # return self._fwstate_to_sim_data_types_state(self.setState)\n        # setState = firm.traj_eval(self.setState)\n        # if not firm.is_traj_eval_valid(setState):\n        #     return self._fwstate_to_sim_data_types_state(self.state)\n\n        # if self.mode == CrazyflieSIL.MODE_IDLE:\n        #     return self._fwstate_to_sim_data_types_state(self.state)\n\n        # self.state = setState\n        # return self._fwstate_to_sim_data_types_state(setState)\n\n    def setState(self, state: sim_data_types.State):\n        self.state.position.x = state.pos[0]\n        self.state.position.y = state.pos[1]\n        self.state.position.z = state.pos[2]\n\n        self.state.velocity.x = state.vel[0]\n        self.state.velocity.y = state.vel[1]\n        self.state.velocity.z = state.vel[2]\n\n        rpy = np.degrees(rowan.to_euler(state.quat, convention='xyz'))\n        # Note, legacy coordinate system, so invert pitch\n        self.state.attitude.roll = rpy[0]\n        self.state.attitude.pitch = -rpy[1]\n        self.state.attitude.yaw = rpy[2]\n\n        self.state.attitudeQuaternion.w = state.quat[0]\n        self.state.attitudeQuaternion.x = state.quat[1]\n        self.state.attitudeQuaternion.y = state.quat[2]\n        self.state.attitudeQuaternion.z = state.quat[3]\n\n        # omega is part of sensors, not of the state\n        self.sensors.gyro.x = np.degrees(state.omega[0])\n        self.sensors.gyro.y = np.degrees(state.omega[1])\n        self.sensors.gyro.z = np.degrees(state.omega[2])\n\n        # TODO: state technically also has acceleration, but sim_data_types does not\n\n    def executeController(self):\n        if self.controller is None:\n            return None\n\n        if self.mode == CrazyflieSIL.MODE_IDLE:\n            return sim_data_types.Action([0, 0, 0, 0])\n\n        time_in_seconds = self.time_func()\n        # ticks is essentially the time in milliseconds as an integer\n        tick = int(time_in_seconds * 1000)\n        if self.controller_name != 'mellinger':\n            self.controller(self.control, self.setpoint, self.sensors, self.state, tick)\n        else:\n            self.controller(\n                self.mellinger_control,\n                self.control,\n                self.setpoint,\n                self.sensors,\n                self.state,\n                tick)\n        return self._fwcontrol_to_sim_data_types_action()\n\n    # 'private' methods\n    def _isGroup(self, groupMask):\n        return groupMask == 0 or (self.groupMask & groupMask) > 0\n\n    def _fwcontrol_to_sim_data_types_action(self):\n\n        firm.powerDistribution(self.control, self.motors_thrust_uncapped)\n        firm.powerDistributionCap(self.motors_thrust_uncapped, self.motors_thrust_pwm)\n\n        # self.motors_thrust_pwm.motors.m{1,4} contain the PWM\n        # convert PWM -> RPM\n        def pwm_to_rpm(pwm):\n            # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id\n            if pwm < 10000:\n                return 0\n            p = [3.26535711e-01, 3.37495115e+03]\n            return np.polyval(p, pwm)\n\n        def pwm_to_force(pwm):\n            # polyfit using data and scripts from https://github.com/IMRCLab/crazyflie-system-id\n            p = [1.71479058e-09,  8.80284482e-05, -2.21152097e-01]\n            force_in_grams = np.polyval(p, pwm)\n            force_in_newton = force_in_grams * 9.81 / 1000.0\n            return np.maximum(force_in_newton, 0)\n\n        return sim_data_types.Action(\n            [pwm_to_rpm(self.motors_thrust_pwm.motors.m1),\n             pwm_to_rpm(self.motors_thrust_pwm.motors.m2),\n             pwm_to_rpm(self.motors_thrust_pwm.motors.m3),\n             pwm_to_rpm(self.motors_thrust_pwm.motors.m4)])\n\n    @staticmethod\n    def _fwsetpoint_to_sim_data_types_state(fwsetpoint):\n        pos = np.array([fwsetpoint.position.x, fwsetpoint.position.y, fwsetpoint.position.z])\n        vel = np.array([fwsetpoint.velocity.x, fwsetpoint.velocity.y, fwsetpoint.velocity.z])\n        acc = np.array([\n            fwsetpoint.acceleration.x,\n            fwsetpoint.acceleration.y,\n            fwsetpoint.acceleration.z])\n        omega = np.radians(np.array([\n            fwsetpoint.attitudeRate.roll,\n            fwsetpoint.attitudeRate.pitch,\n            fwsetpoint.attitudeRate.yaw]))\n\n        if fwsetpoint.mode.quat == firm.modeDisable:\n            # compute rotation based on differential flatness\n            thrust = acc + np.array([0, 0, 9.81])\n            z_body = thrust / np.linalg.norm(thrust)\n            yaw = np.radians(fwsetpoint.attitude.yaw)\n            x_world = np.array([np.cos(yaw), np.sin(yaw), 0])\n            y_body = np.cross(z_body, x_world)\n            # Mathematically not needed. This addresses numerical issues to ensure R is orthogonal\n            y_body /= np.linalg.norm(y_body)\n            x_body = np.cross(y_body, z_body)\n            # Mathematically not needed. This addresses numerical issues to ensure R is orthogonal\n            x_body /= np.linalg.norm(x_body)\n            R = np.column_stack([x_body, y_body, z_body])\n            quat = rowan.from_matrix(R)\n        else:\n            quat = fwsetpoint.attitudeQuaternion\n\n        return sim_data_types.State(pos, vel, quat, omega)\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/sim_data_types.py",
    "content": "import numpy as np\n\n\nclass State:\n    \"\"\"Class that stores the state of a UAV as used in the simulator interface.\"\"\"\n\n    def __init__(self, pos=np.zeros(3), vel=np.zeros(3),\n                 quat=np.array([1, 0, 0, 0]), omega=np.zeros(3)):\n        # internally use one numpy array\n        self._state = np.empty(13)\n        self.pos = pos\n        self.vel = vel\n        self.quat = quat\n        self.omega = omega\n\n    @property\n    def pos(self):\n        \"\"\"Position [m; world frame].\"\"\"\n        return self._state[0:3]\n\n    @pos.setter\n    def pos(self, value):\n        self._state[0:3] = value\n\n    @property\n    def vel(self):\n        \"\"\"Velocity [m/s; world frame].\"\"\"\n        return self._state[3:6]\n\n    @vel.setter\n    def vel(self, value):\n        self._state[3:6] = value\n\n    @property\n    def quat(self):\n        \"\"\"Quaternion [qw, qx, qy, qz; body -> world].\"\"\"\n        return self._state[6:10]\n\n    @quat.setter\n    def quat(self, value):\n        self._state[6:10] = value\n\n    @property\n    def omega(self):\n        \"\"\"Angular velocity [rad/s; body frame].\"\"\"\n        return self._state[10:13]\n\n    @omega.setter\n    def omega(self, value):\n        self._state[10:13] = value\n\n    def __repr__(self) -> str:\n        return 'State pos={}, vel={}, quat={}, omega={}'.format(\n            self.pos, self.vel, self.quat, self.omega)\n\n\nclass Action:\n    \"\"\"Class that stores the action of a UAV as used in the simulator interface.\"\"\"\n\n    def __init__(self, rpm):\n        # internally use one numpy array\n        self._action = np.empty(4)\n        self.rpm = rpm\n\n    @property\n    def rpm(self):\n        \"\"\"Rotation per second [rpm].\"\"\"\n        return self._action\n\n    @rpm.setter\n    def rpm(self, value):\n        self._action = value\n\n    def __repr__(self) -> str:\n        return 'Action rpm={}'.format(self.rpm)\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/README.md",
    "content": "# Visualizations\n\n## Blender\n\n### Dependencies\n\n- `bpy`\n- `rowan`\n- `numpy` \n- `yaml` \n\n### Output\n- Takes pictures from robots' perspectives\n- Saves pictures in working directory in `simulation_results/<date-and-time>` with the following folder structure\n\n    ```\n    simulation_results\n    └── <date-and-time>\n        ├── cf1\n        │   ├── calibration.yaml\n        │   ├── cf0.csv\n        │   ├── cf0_00000.jpg\n        │   ├── cf0_00001.jpg\n        │   └── ...\n        ├── ...\n        └── cfn\n            ├── calibration.yaml\n            ├── cfn.csv\n            ├── cfn_00000.jpg\n            ├── cfn_00001.jpg\n            └── ...\n    ```\n    where `<name>.csv` contains the states in world coordinates of the camera or crazyflie, `calibration.yaml` contains the calibration information of the cameras and \n    `<name>_<frame>.jpg` is the `<frame>`th image taken from `<names>`'s perspective. If a robot is configured to not carry a camera, only `<name>.csv` will be recorded. \n- In order to use it, you need to add `blender` to the list of visualizations in `crazyflie/config/server.yaml` and run \n\n    ```sh\n    ros2 launch crazyflie launch.py backend:=sim\n    ```\n\n### Configuration\n- Crazyflies to appear in scene are defined in `crazyflie/config/crazyflies.yaml` \n- In `crazyflie/config/server.yaml` you **must** set the following parameters, unless stated otherwise:\n    * `enabled: boolean`, enables or disables blender visualization in simulator\n    * `fps: float`, frames per second rate of all cameras  \n    * `auto_yaw: boolean`, enables or disables auto-yaw (optional, defaults to `false` if not set)\n        - `radps: float`, radians per second\n    * for every robot in `cf_cameras`:\n        - `calibration`\n            * `tvec: list[float]` translation vector of camera wrt. robot\n            * `rvec: list[float]` rotation vector of camera wrt. robot (for camera +Z is front and +Y is up)  \n\n            > **Note**\n            > 1. The camera matrix $\\mathbf K$ is set internally to be close to a real crazyflie's as possible.\n            > It is given (in row-major order) by $$\\mathbf  K = \\left[ [170, 0, 160], [0, 170, 160], [0, 0, 1] \\right].$$\n            > 2. The distortion coefficient is set to $\\left(0, 0, 0, 0, 0\\right)^\\top $\n\n- Example configuration\n\n    ```yaml\n    blender:\n      enabled: true\n      fps: 1           # frames per second\n      cycle_bg: false  # if true, pictures will cycle through different environemt background images (useful for synthetic image generation). Otherwise a single environment background image will be used\n      cf_cameras:      # names of crazyflies with cameras on them if enabled in `crazyflies.yaml`\n        cf231:\n          calibration:\n            tvec: [0,0,0]\n            rvec: [1.2092,-1.2092,1.2092]   # 0 deg tilt\n        cf5:\n          calibration:\n            tvec: [0,0,0]\n            rvec: [ 0.61394313, -0.61394313,  1.48218982]   # 45 deg tilt\n        cf6:\n          calibration:\n            tvec: [0,0,0]\n            rvec: [0.0,0.0,1.5707963267948966]    # 90 deg tilt\n    ```\n\n- For efficiently generating synthetic images, we recommend setting the backend `none` in `crazyflie/config/server.yaml` \n\n### Acknowledgments \n\n- All background images are in the public domain (CC0 license) and were sourced from [polyhaven.com](https://polyhaven.com/) \n- The crazyflie model used is under an MIT license and was modified and sourced from [https://github.com/bitcraze/crazyflie-simulation](https://github.com/bitcraze/crazyflie-simulation)\n\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/blender.py",
    "content": "import datetime\nimport os\nfrom pathlib import Path\n\nimport bpy\nimport numpy as np\nfrom rclpy.node import Node\nimport rowan as rw\nimport yaml\n\nfrom ..sim_data_types import Action, State\n\n\n# rotation vectors are axis-angle format in 'compact form', where\n# theta = norm(rvec) and axis = rvec / theta\n# they can be converted to a matrix using cv2. Rodrigues, see\n# https://docs.opencv.org/4.7.0/d9/d0c/group__calib3d.html#ga61585db663d9da06b68e70cfbf6a1eac\ndef opencv2quat(rvec):\n    angle = np.linalg.norm(rvec)\n    if angle == 0:\n        q = np.array([1, 0, 0, 0])\n    else:\n        axis = rvec.flatten() / angle\n        q = rw.from_axis_angle(axis, angle)\n    return q\n\n\nclass Visualization:\n\n    def __init__(self, node: Node, params: dict, names: list[str], states: list[State]):\n        self.node = node\n\n        # blender\n        # load environment\n        world = bpy.context.scene.world\n        world.use_nodes = True\n        self.env = world.node_tree.nodes.new('ShaderNodeTexEnvironment')\n        if params['cycle_bg']:\n            bg_paths = []\n            p = Path(__file__).resolve().parent / 'data/env'\n            print(p)\n            for subdir, dirs, files in os.walk(p):\n                bg_paths.extend([os.path.join(subdir, file) for file in files])\n            self.cycle_bg = True\n            self.bg_idx = 0\n            self.bg_imgs = [bpy.data.images.load(bgp) for bgp in bg_paths]\n            print(self.bg_imgs)\n            print(bg_paths)\n            self.env.image = self.bg_imgs[self.bg_idx]\n        else:\n            self.cycle_bg = False\n            self.env.image = bpy.data.images.load(\n                Path(__file__).resolve().parent / 'data/env/env.jpg')\n        node_tree = world.node_tree\n        node_tree.links.new(\n            self.env.outputs['Color'],\n            node_tree.nodes['Background'].inputs['Color'])\n\n        # import crazyflie object\n        bpy.ops.import_scene.obj(\n            filepath=f'{Path(__file__).resolve().parent}/data/model/cf.obj',\n            axis_forward='Y', axis_up='Z')\n        self.cf_default = bpy.data.objects['cf']\n        # save scene\n        self.scene = bpy.context.scene\n        self.scene.render.resolution_x = 320\n        self.scene.render.resolution_y = 320\n        self.scene.render.pixel_aspect_x = 1.0\n        self.scene.render.pixel_aspect_y = 1.0\n        self.scene.render.image_settings.file_format = 'JPEG'\n        self.scene.unit_settings.length_unit = 'METERS'\n        self.scene.unit_settings.system = 'METRIC'\n        self.scene.unit_settings.scale_length = 1.0\n        # self.scene.render.threads = 2  # max CPU cores to use to render\n\n        # remove default objects\n        bpy.data.objects.remove(bpy.data.objects['Cube'])\n        bpy.data.objects.remove(bpy.data.objects['Light'])\n        # create lamp\n        lamp_data = bpy.data.lights.new(name='Lamp', type='SUN')\n        lamp_data.energy = 1.5\n        lamp_data.angle = 0.19198621809482574  # 11 deg\n        self.lamp = bpy.data.objects.new(name='Lamp', object_data=lamp_data)\n        bpy.context.collection.objects.link(self.lamp)\n        bpy.context.view_layer.objects.active = self.lamp\n        # camera\n        self.camera = bpy.data.objects['Camera']\n        self.camera.data.lens = 0.7376461029052734\n        self.camera.data.lens_unit = 'FOV'\n        self.camera.data.sensor_fit = 'AUTO'\n        self.camera.data.sensor_width = 1.4\n        self.camera.data.sensor_height = 18\n        self.camera.data.angle = 1.518436431884765  # 87 deg\n        self.camera.data.clip_start = 1.1e-6\n        # link camera to scene\n\n        self.cf_default.hide_render = False\n        # set rotation mode to quaternion\n        self.cf_default.rotation_mode = 'QUATERNION'\n        self.camera.rotation_mode = 'QUATERNION'\n        self.lamp.rotation_mode = 'QUATERNION'\n\n        base = 'simulation_results'\n        self.path = base + '/' + datetime.datetime.now().strftime('%Y-%m-%d_%H%M%S') + '/'\n        os.makedirs(self.path, exist_ok=True)\n\n        self.ts = []\n        self.frame = 0\n        self.fps = params['fps']  # frames per second\n\n        self.names = names\n        self.n = len(names)\n        self.state_filenames = []\n        self.cam_state_filenames = []\n\n        # dictionary with (name, idx) pairs to later find corresponding cf\n        self.names_idx_map = {}\n        # init list\n        self.cf_list = [self.cf_default]\n        self.cf_cameras = params['cf_cameras'] if 'cf_cameras' in params else {}\n        # matrix where rows are the constant transformation between camera and its cf\n        # it should only be accessed if corresponding cf carries a camera\n        self.Q_virt_cf_cam = np.zeros((self.n, 4))\n\n        for idx, (name, state) in enumerate(zip(names, states)):\n            self.names_idx_map[name] = idx\n            if idx > 0:\n                # cf copies\n                cf_copy = self.cf_default.copy()\n                bpy.context.collection.objects.link(cf_copy)\n                self.cf_list.append(cf_copy)\n            # set rotations\n            self.cf_list[idx].rotation_quaternion = np.array(state.quat)\n            # set positions\n            self.cf_list[idx].location = np.array(state.pos)\n\n        self.tvecs = np.zeros((self.n, 3))\n        for name in names:\n            os.mkdir(self.path + '/' + name + '/')  # create dir for every cf for saving images\n            csf = f'{self.path}/{name}/{name}.csv'\n            calibration_sf = f'{self.path}/{name}/calibration.yaml'\n            # initialize <robot_name>/<robot_name>.csv\n            self.state_filenames.append(csf)\n            # self.cam_state_filenames.append(cam_sf)\n            with open(csf, 'w') as file:\n                file.write('image_name,timestamp,x,y,z,qw,qx,qy,qz\\n')\n            if name in self.cf_cameras:\n                calibration = self.cf_cameras[name]['calibration']\n                calibration['dist_coeff'] = np.zeros(5).tolist()\n                calibration['camera_matrix'] = np.array([\n                    [170.0, 0, 160.0],\n                    [0, 170.0, 160.0],\n                    [0, 0, 1]]).tolist()\n                with open(calibration_sf, 'w') as file:\n                    yaml.dump(calibration, file)\n                rvec = np.array([1.2092, -1.2092, 1.2092])\n                if 'rvec' in calibration:\n                    rvec = np.array(calibration['rvec'])\n                tvec = np.array(calibration['tvec']) if 'tvec' in calibration else np.zeros(3)\n                self.tvecs[self.names_idx_map[name]] = tvec\n                q_real_camera_to_robot = rw.inverse(opencv2quat(rvec))\n                q_virtual_camera_to_real_camera = rw.from_euler(np.pi, 0, 0, 'xyz')\n                self.Q_virt_cf_cam[self.names_idx_map[name]] = rw.multiply(\n                    q_real_camera_to_robot,\n                    q_virtual_camera_to_real_camera)\n\n    def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]):\n        self.ts.append(t)\n        # render and record `self.fps` frames per second\n        if t - self.frame / self.fps >= 1 / self.fps:\n            self.frame += 1\n            # quaternion matrix\n            Q = np.zeros((self.n, 4))\n            # position matrix\n            P = np.zeros((self.n, 3))\n\n            # first put everything in place and record cfs's states\n            for name, state in zip(self.names, states):\n                idx = self.names_idx_map[name]\n                Q[idx] = np.array(state.quat)\n                P[idx] = np.array(state.pos)\n\n                # set rotations\n                self.cf_list[idx].rotation_quaternion = Q[idx]\n                # set positions\n                self.cf_list[idx].location = P[idx]\n                # record states\n                # image capturing scene from cf's pov or None\n                image_name = None\n                if name in self.cf_cameras:\n                    image_name = f'{self.names[idx]}_{self.frame:05}.jpg'\n                # record cf's state in world frame\n                with open(self.state_filenames[idx], 'a') as file:\n                    file.write(f'{image_name},{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\\n')  # noqa E501\n\n            # cycle background image if enabled\n            if self.cycle_bg:\n                self.bg_idx = (self.bg_idx + 1) % len(self.bg_imgs)\n                self.env.image = self.bg_imgs[self.bg_idx]\n\n            # render images from cfs' perspectives\n            for name, state in zip(self.names, states):\n                idx = self.names_idx_map[name]\n                if name not in self.cf_cameras:\n                    continue\n                # rotation\n                self.camera.rotation_quaternion = rw.multiply(Q[idx], self.Q_virt_cf_cam[idx])\n                self.lamp.rotation_quaternion = self.camera.rotation_quaternion\n                # positions\n                p_cam = P[idx] + rw.to_matrix(Q[idx]) @ self.tvecs[idx]\n                self.camera.location = p_cam\n                self.lamp.location = p_cam\n                # hide corresponding cf for rendering\n                self.cf_list[idx].hide_render = True\n                # Render image\n                image_name = f'{name}_{self.frame:05}.jpg'  # image capturing scene from cf's pov\n                self.scene.render.filepath = f'{self.path}/{name}/{image_name}'\n                bpy.ops.render.render(write_still=True)\n                # show again after rendering\n                self.cf_list[idx].hide_render = False\n\n    def shutdown(self):\n        for idx in range(1, self.n):\n            bpy.data.objects.remove(self.cf_list[idx])\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/data/README.md",
    "content": "# Acknowledgments \n\n- All background images are in the public domain (CC0 license) and were sourced from [polyhaven.com](https://polyhaven.com/) \n- The crazyflie model used is under an MIT license and was modified and sourced from [https://github.com/bitcraze/crazyflie-simulation](https://github.com/bitcraze/crazyflie-simulation)\n\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/data/model/cf.mtl",
    "content": "# Blender 3.4.1 MTL File: 'None'\n# www.blender.org\n\nnewmtl Material.001\nNs 250.000000\nKa 0.652850 0.652850 0.652850\nKd 0.342856 0.342856 0.342856\nKs 0.500000 0.500000 0.500000\nKe 0.000000 0.000000 0.000000\nNi 1.450000\nd 1.000000\nillum 3\n\nnewmtl Material.002\nNs 360.000000\nKa 1.000000 1.000000 1.000000\nKd 0.800000 0.800000 0.800000\nKs 0.500000 0.500000 0.500000\nKe 0.000000 0.000000 0.000000\nNi 1.000000\nd 1.000000\nillum 2\n\nnewmtl metal\nNs 250.000000\nKa 0.800000 0.800000 0.800000\nKd 0.116953 0.116953 0.116953\nKs 0.500000 0.500000 0.500000\nKe 0.000000 0.000000 0.000000\nNi 1.450000\nd 1.000000\nillum 3\n\nnewmtl pcb\nNs 0.000000\nKa 1.000000 1.000000 1.000000\nKd 0.009524 0.009524 0.009524\nKs 0.500000 0.500000 0.500000\nKe 0.000000 0.000000 0.000000\nNi 1.450000\nd 1.000000\nillum 2\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/data/model/cf.obj",
    "content": "# Blender 3.4.1\n# www.blender.org\nmtllib cf.mtl\ng cf_Mesh\nv 0.031894 0.032030 0.007876\nv 0.031894 0.032030 0.011571\nv 0.031441 0.032740 0.011453\nv 0.031441 0.032740 0.007876\nv 0.031294 0.033570 0.011116\nv 0.031294 0.033570 0.007876\nv 0.031476 0.034393 0.010611\nv 0.031476 0.034393 0.007876\nv 0.031960 0.035084 0.010017\nv 0.031960 0.035084 0.007876\nv 0.032670 0.035537 0.009422\nv 0.032670 0.035537 0.007876\nv 0.033500 0.035684 0.008918\nv 0.033500 0.035684 0.007876\nv 0.034323 0.035502 0.008581\nv 0.034323 0.035502 0.007876\nv 0.035014 0.035018 0.008462\nv 0.035014 0.035018 0.007876\nv 0.035467 0.034308 0.007876\nv 0.035014 0.035018 0.012196\nv 0.035467 0.034308 0.012196\nv 0.035614 0.033478 0.012196\nv 0.035614 0.033478 0.007876\nv 0.035432 0.032655 0.012196\nv 0.035432 0.032655 0.007876\nv 0.034948 0.031964 0.012196\nv 0.034948 0.031964 0.007876\nv 0.034238 0.031511 0.012196\nv 0.034238 0.031511 0.007876\nv 0.033408 0.031364 0.012196\nv 0.033408 0.031364 0.007876\nv 0.031294 0.033570 0.012196\nv 0.031441 0.032740 0.012196\nv 0.031894 0.032030 0.012196\nv 0.032585 0.031546 0.012196\nv 0.034323 0.035502 0.012196\nv 0.033500 0.035684 0.012196\nv 0.032670 0.035537 0.012196\nv 0.031960 0.035084 0.012196\nv 0.031476 0.034393 0.012196\nv 0.032585 0.031546 0.007876\nv 0.032585 0.031546 0.008581\nv 0.031894 0.032030 0.008462\nv 0.042430 0.017392 0.008993\nv 0.046328 0.013940 0.009543\nv 0.035432 0.032655 0.010611\nv 0.034948 0.031964 0.010017\nv 0.050607 0.014876 0.011222\nv 0.051372 0.015998 0.011404\nv 0.035614 0.033478 0.011116\nv 0.051882 0.017675 0.011318\nv 0.035467 0.034308 0.011453\nv 0.051536 0.020602 0.011266\nv 0.034238 0.031511 0.009422\nv 0.049298 0.013689 0.010663\nv 0.035014 0.035018 0.011571\nv 0.047570 0.025376 0.011245\nv 0.033408 0.031364 0.008918\nv 0.048266 0.013091 0.010186\nv 0.034323 0.035502 0.008581\nv 0.035014 0.035018 0.008462\nv 0.024478 0.049656 0.008993\nv 0.020580 0.053108 0.009543\nv 0.031476 0.034393 0.010611\nv 0.031960 0.035084 0.010017\nv 0.016301 0.052172 0.011222\nv 0.015536 0.051050 0.011404\nv 0.031294 0.033570 0.011116\nv 0.015026 0.049373 0.011318\nv 0.031441 0.032740 0.011453\nv 0.015372 0.046446 0.011266\nv 0.032670 0.035537 0.009422\nv 0.017610 0.053359 0.010663\nv 0.019338 0.041672 0.011245\nv 0.033500 0.035684 0.008918\nv 0.018642 0.053957 0.010186\nv 0.032753 0.031650 0.008078\nv 0.046545 0.014084 0.009070\nv 0.042582 0.017483 0.008483\nv 0.032047 0.032121 0.007953\nv 0.035543 0.032740 0.010090\nv 0.051498 0.016093 0.010888\nv 0.050775 0.014995 0.010723\nv 0.035115 0.032083 0.009517\nv 0.035669 0.033530 0.010581\nv 0.051955 0.017735 0.010786\nv 0.035471 0.034322 0.010913\nv 0.051575 0.020645 0.010729\nv 0.049489 0.013818 0.010175\nv 0.034431 0.031641 0.008935\nv 0.035008 0.035023 0.011031\nv 0.047564 0.025381 0.010705\nv 0.033623 0.031508 0.008444\nv 0.048472 0.013228 0.009706\nv 0.034155 0.035398 0.008078\nv 0.020363 0.052964 0.009070\nv 0.024326 0.049565 0.008483\nv 0.034861 0.034927 0.007953\nv 0.031365 0.034308 0.010090\nv 0.015410 0.050955 0.010888\nv 0.016133 0.052053 0.010723\nv 0.031793 0.034965 0.009517\nv 0.031239 0.033518 0.010581\nv 0.014953 0.049313 0.010786\nv 0.031437 0.032726 0.010913\nv 0.015333 0.046403 0.010729\nv 0.017419 0.053230 0.010175\nv 0.032477 0.035407 0.008935\nv 0.031900 0.032025 0.011031\nv 0.019344 0.041667 0.010705\nv 0.033285 0.035540 0.008444\nv 0.018436 0.053820 0.009706\nv 0.034155 0.035398 0.008078\nv 0.034861 0.034927 0.007953\nv 0.018436 0.053820 0.009706\nv -0.031946 0.032030 0.007876\nv -0.031946 0.032030 0.011571\nv -0.031493 0.032740 0.011453\nv -0.031493 0.032740 0.007876\nv -0.031346 0.033570 0.011116\nv -0.031346 0.033570 0.007876\nv -0.031528 0.034393 0.010611\nv -0.031528 0.034393 0.007876\nv -0.032012 0.035084 0.010017\nv -0.032012 0.035084 0.007876\nv -0.032722 0.035537 0.009422\nv -0.032722 0.035537 0.007876\nv -0.033552 0.035684 0.008918\nv -0.033552 0.035684 0.007876\nv -0.034375 0.035502 0.008581\nv -0.034375 0.035502 0.007876\nv -0.035066 0.035018 0.008462\nv -0.035066 0.035018 0.007876\nv -0.035519 0.034308 0.007876\nv -0.035066 0.035018 0.012196\nv -0.035519 0.034308 0.012196\nv -0.035666 0.033478 0.012196\nv -0.035666 0.033478 0.007876\nv -0.035484 0.032655 0.012196\nv -0.035484 0.032655 0.007876\nv -0.035000 0.031964 0.012196\nv -0.035000 0.031964 0.007876\nv -0.034290 0.031511 0.012196\nv -0.034290 0.031511 0.007876\nv -0.033460 0.031364 0.012196\nv -0.033460 0.031364 0.007876\nv -0.031346 0.033570 0.012196\nv -0.031493 0.032740 0.012196\nv -0.031946 0.032030 0.012196\nv -0.032637 0.031546 0.012196\nv -0.034375 0.035502 0.012196\nv -0.033552 0.035684 0.012196\nv -0.032722 0.035537 0.012196\nv -0.032012 0.035084 0.012196\nv -0.031528 0.034393 0.012196\nv -0.032637 0.031546 0.007876\nv -0.032637 0.031546 0.008581\nv -0.031946 0.032030 0.008462\nv -0.042482 0.017392 0.008993\nv -0.046380 0.013940 0.009543\nv -0.035484 0.032655 0.010611\nv -0.035000 0.031964 0.010017\nv -0.050659 0.014876 0.011222\nv -0.051424 0.015998 0.011404\nv -0.035666 0.033478 0.011116\nv -0.051934 0.017675 0.011318\nv -0.035519 0.034308 0.011453\nv -0.051588 0.020602 0.011266\nv -0.034290 0.031511 0.009422\nv -0.049350 0.013689 0.010663\nv -0.035066 0.035018 0.011571\nv -0.047622 0.025376 0.011245\nv -0.033460 0.031364 0.008918\nv -0.048318 0.013091 0.010186\nv -0.034375 0.035502 0.008581\nv -0.035066 0.035018 0.008462\nv -0.024530 0.049656 0.008993\nv -0.020632 0.053108 0.009543\nv -0.031528 0.034393 0.010611\nv -0.032012 0.035084 0.010017\nv -0.016353 0.052172 0.011222\nv -0.015588 0.051050 0.011404\nv -0.031346 0.033570 0.011116\nv -0.015078 0.049373 0.011318\nv -0.031493 0.032740 0.011453\nv -0.015424 0.046446 0.011266\nv -0.032722 0.035537 0.009422\nv -0.017662 0.053359 0.010663\nv -0.019390 0.041672 0.011245\nv -0.033552 0.035684 0.008918\nv -0.018694 0.053957 0.010186\nv -0.032805 0.031650 0.008078\nv -0.046597 0.014084 0.009070\nv -0.042635 0.017483 0.008483\nv -0.032099 0.032121 0.007953\nv -0.035595 0.032740 0.010090\nv -0.051550 0.016093 0.010888\nv -0.050827 0.014995 0.010723\nv -0.035167 0.032083 0.009517\nv -0.035721 0.033530 0.010581\nv -0.052007 0.017735 0.010786\nv -0.035523 0.034322 0.010913\nv -0.051627 0.020645 0.010729\nv -0.049541 0.013818 0.010175\nv -0.034483 0.031641 0.008935\nv -0.035060 0.035023 0.011031\nv -0.047616 0.025381 0.010705\nv -0.033675 0.031508 0.008444\nv -0.048524 0.013228 0.009706\nv -0.034207 0.035398 0.008078\nv -0.020415 0.052964 0.009070\nv -0.024378 0.049565 0.008483\nv -0.034913 0.034927 0.007953\nv -0.031417 0.034308 0.010090\nv -0.015462 0.050955 0.010888\nv -0.016185 0.052053 0.010723\nv -0.031845 0.034965 0.009517\nv -0.031291 0.033518 0.010581\nv -0.015005 0.049313 0.010786\nv -0.031489 0.032726 0.010913\nv -0.015385 0.046403 0.010729\nv -0.017471 0.053230 0.010175\nv -0.032529 0.035407 0.008935\nv -0.031952 0.032025 0.011031\nv -0.019396 0.041667 0.010705\nv -0.033337 0.035540 0.008444\nv -0.018488 0.053820 0.009706\nv -0.034207 0.035398 0.008078\nv -0.034913 0.034927 0.007953\nv -0.018488 0.053820 0.009706\nv 0.031894 -0.031942 0.007876\nv 0.031894 -0.031942 0.011571\nv 0.031441 -0.032652 0.011453\nv 0.031441 -0.032652 0.007876\nv 0.031294 -0.033482 0.011116\nv 0.031294 -0.033482 0.007876\nv 0.031476 -0.034305 0.010611\nv 0.031476 -0.034305 0.007876\nv 0.031960 -0.034996 0.010017\nv 0.031960 -0.034996 0.007876\nv 0.032670 -0.035449 0.009422\nv 0.032670 -0.035449 0.007876\nv 0.033500 -0.035596 0.008918\nv 0.033500 -0.035596 0.007876\nv 0.034323 -0.035414 0.008581\nv 0.034323 -0.035414 0.007876\nv 0.035014 -0.034930 0.008462\nv 0.035014 -0.034930 0.007876\nv 0.035467 -0.034220 0.007876\nv 0.035014 -0.034930 0.012196\nv 0.035467 -0.034220 0.012196\nv 0.035614 -0.033390 0.012196\nv 0.035614 -0.033390 0.007876\nv 0.035432 -0.032567 0.012196\nv 0.035432 -0.032567 0.007876\nv 0.034948 -0.031876 0.012196\nv 0.034948 -0.031876 0.007876\nv 0.034238 -0.031423 0.012196\nv 0.034238 -0.031423 0.007876\nv 0.033408 -0.031276 0.012196\nv 0.033408 -0.031276 0.007876\nv 0.031294 -0.033482 0.012196\nv 0.031441 -0.032652 0.012196\nv 0.031894 -0.031942 0.012196\nv 0.032585 -0.031458 0.012196\nv 0.034323 -0.035414 0.012196\nv 0.033500 -0.035596 0.012196\nv 0.032670 -0.035449 0.012196\nv 0.031960 -0.034996 0.012196\nv 0.031476 -0.034305 0.012196\nv 0.032585 -0.031458 0.007876\nv 0.032585 -0.031458 0.008581\nv 0.031894 -0.031942 0.008462\nv 0.042430 -0.017304 0.008993\nv 0.046328 -0.013852 0.009543\nv 0.035432 -0.032567 0.010611\nv 0.034948 -0.031876 0.010017\nv 0.050607 -0.014788 0.011222\nv 0.051372 -0.015910 0.011404\nv 0.035614 -0.033390 0.011116\nv 0.051882 -0.017587 0.011318\nv 0.035467 -0.034220 0.011453\nv 0.051536 -0.020514 0.011266\nv 0.034238 -0.031423 0.009422\nv 0.049298 -0.013601 0.010663\nv 0.035014 -0.034930 0.011571\nv 0.047570 -0.025288 0.011245\nv 0.033408 -0.031276 0.008918\nv 0.048266 -0.013003 0.010186\nv 0.034323 -0.035414 0.008581\nv 0.035014 -0.034930 0.008462\nv 0.024478 -0.049568 0.008993\nv 0.020580 -0.053020 0.009543\nv 0.031476 -0.034305 0.010611\nv 0.031960 -0.034996 0.010017\nv 0.016301 -0.052084 0.011222\nv 0.015536 -0.050962 0.011404\nv 0.031294 -0.033482 0.011116\nv 0.015026 -0.049285 0.011318\nv 0.031441 -0.032652 0.011453\nv 0.015372 -0.046358 0.011266\nv 0.032670 -0.035449 0.009422\nv 0.017610 -0.053271 0.010663\nv 0.019338 -0.041584 0.011245\nv 0.033500 -0.035596 0.008918\nv 0.018642 -0.053869 0.010186\nv 0.032753 -0.031562 0.008078\nv 0.046545 -0.013996 0.009070\nv 0.042583 -0.017395 0.008483\nv 0.032047 -0.032033 0.007953\nv 0.035543 -0.032652 0.010090\nv 0.051498 -0.016005 0.010888\nv 0.050775 -0.014907 0.010723\nv 0.035115 -0.031995 0.009517\nv 0.035669 -0.033442 0.010581\nv 0.051955 -0.017647 0.010786\nv 0.035471 -0.034234 0.010913\nv 0.051575 -0.020557 0.010729\nv 0.049489 -0.013730 0.010175\nv 0.034431 -0.031553 0.008935\nv 0.035008 -0.034935 0.011031\nv 0.047564 -0.025293 0.010705\nv 0.033623 -0.031420 0.008444\nv 0.048472 -0.013140 0.009706\nv 0.034155 -0.035310 0.008078\nv 0.020363 -0.052876 0.009070\nv 0.024326 -0.049477 0.008483\nv 0.034861 -0.034839 0.007953\nv 0.031365 -0.034220 0.010090\nv 0.015410 -0.050867 0.010888\nv 0.016133 -0.051965 0.010723\nv 0.031793 -0.034877 0.009517\nv 0.031239 -0.033430 0.010581\nv 0.014953 -0.049225 0.010786\nv 0.031437 -0.032638 0.010913\nv 0.015333 -0.046315 0.010729\nv 0.017419 -0.053142 0.010175\nv 0.032477 -0.035319 0.008935\nv 0.031900 -0.031937 0.011031\nv 0.019344 -0.041579 0.010705\nv 0.033285 -0.035452 0.008444\nv 0.018436 -0.053732 0.009706\nv 0.034155 -0.035310 0.008078\nv 0.034861 -0.034839 0.007953\nv 0.018436 -0.053732 0.009706\nv -0.031946 -0.031942 0.007876\nv -0.031946 -0.031942 0.011571\nv -0.031493 -0.032652 0.011453\nv -0.031493 -0.032652 0.007876\nv -0.031346 -0.033482 0.011116\nv -0.031346 -0.033482 0.007876\nv -0.031528 -0.034305 0.010611\nv -0.031528 -0.034305 0.007876\nv -0.032012 -0.034996 0.010017\nv -0.032012 -0.034996 0.007876\nv -0.032722 -0.035449 0.009422\nv -0.032722 -0.035449 0.007876\nv -0.033552 -0.035596 0.008918\nv -0.033552 -0.035596 0.007876\nv -0.034375 -0.035414 0.008581\nv -0.034375 -0.035414 0.007876\nv -0.035066 -0.034930 0.008462\nv -0.035066 -0.034930 0.007876\nv -0.035519 -0.034220 0.007876\nv -0.035066 -0.034930 0.012196\nv -0.035519 -0.034220 0.012196\nv -0.035666 -0.033390 0.012196\nv -0.035666 -0.033390 0.007876\nv -0.035484 -0.032567 0.012196\nv -0.035484 -0.032567 0.007876\nv -0.035000 -0.031876 0.012196\nv -0.035000 -0.031876 0.007876\nv -0.034290 -0.031423 0.012196\nv -0.034290 -0.031423 0.007876\nv -0.033460 -0.031276 0.012196\nv -0.033460 -0.031276 0.007876\nv -0.031346 -0.033482 0.012196\nv -0.031493 -0.032652 0.012196\nv -0.031946 -0.031942 0.012196\nv -0.032637 -0.031458 0.012196\nv -0.034375 -0.035414 0.012196\nv -0.033552 -0.035596 0.012196\nv -0.032722 -0.035449 0.012196\nv -0.032012 -0.034996 0.012196\nv -0.031528 -0.034305 0.012196\nv -0.032637 -0.031458 0.007876\nv -0.032637 -0.031458 0.008581\nv -0.031946 -0.031942 0.008462\nv -0.042482 -0.017304 0.008993\nv -0.046380 -0.013852 0.009543\nv -0.035484 -0.032567 0.010611\nv -0.035000 -0.031876 0.010017\nv -0.050659 -0.014788 0.011222\nv -0.051424 -0.015910 0.011404\nv -0.035666 -0.033390 0.011116\nv -0.051934 -0.017587 0.011318\nv -0.035519 -0.034220 0.011453\nv -0.051588 -0.020514 0.011266\nv -0.034290 -0.031423 0.009422\nv -0.049350 -0.013601 0.010663\nv -0.035066 -0.034930 0.011571\nv -0.047622 -0.025288 0.011245\nv -0.033460 -0.031276 0.008918\nv -0.048318 -0.013003 0.010186\nv -0.034375 -0.035414 0.008581\nv -0.035066 -0.034930 0.008462\nv -0.024530 -0.049568 0.008993\nv -0.020632 -0.053020 0.009543\nv -0.031528 -0.034305 0.010611\nv -0.032012 -0.034996 0.010017\nv -0.016353 -0.052084 0.011222\nv -0.015588 -0.050962 0.011404\nv -0.031346 -0.033482 0.011116\nv -0.015078 -0.049285 0.011318\nv -0.031493 -0.032652 0.011453\nv -0.015424 -0.046358 0.011266\nv -0.032722 -0.035449 0.009422\nv -0.017662 -0.053271 0.010663\nv -0.019390 -0.041584 0.011245\nv -0.033552 -0.035596 0.008918\nv -0.018694 -0.053869 0.010186\nv -0.032805 -0.031562 0.008078\nv -0.046597 -0.013996 0.009070\nv -0.042634 -0.017395 0.008483\nv -0.032099 -0.032033 0.007953\nv -0.035595 -0.032652 0.010090\nv -0.051550 -0.016005 0.010888\nv -0.050827 -0.014907 0.010723\nv -0.035167 -0.031995 0.009517\nv -0.035721 -0.033442 0.010581\nv -0.052007 -0.017647 0.010786\nv -0.035523 -0.034234 0.010913\nv -0.051627 -0.020557 0.010729\nv -0.049541 -0.013730 0.010175\nv -0.034483 -0.031553 0.008935\nv -0.035060 -0.034936 0.011031\nv -0.047616 -0.025293 0.010705\nv -0.033675 -0.031420 0.008444\nv -0.048524 -0.013140 0.009706\nv -0.034207 -0.035310 0.008078\nv -0.020415 -0.052876 0.009070\nv -0.024378 -0.049477 0.008483\nv -0.034913 -0.034839 0.007953\nv -0.031417 -0.034220 0.010090\nv -0.015462 -0.050867 0.010888\nv -0.016185 -0.051965 0.010723\nv -0.031845 -0.034877 0.009517\nv -0.031291 -0.033430 0.010581\nv -0.015005 -0.049225 0.010786\nv -0.031489 -0.032638 0.010913\nv -0.015385 -0.046315 0.010729\nv -0.017471 -0.053142 0.010175\nv -0.032529 -0.035319 0.008935\nv -0.031952 -0.031937 0.011031\nv -0.019396 -0.041579 0.010705\nv -0.033337 -0.035452 0.008444\nv -0.018488 -0.053732 0.009706\nv -0.034207 -0.035310 0.008078\nv -0.034913 -0.034839 0.007953\nv -0.018488 -0.053732 0.009706\nv 0.041233 0.033180 -0.000984\nv 0.040449 0.033187 -0.000200\nv 0.037689 0.033209 -0.000200\nv 0.037689 0.033209 -0.011000\nv 0.041233 0.033180 -0.011000\nv 0.041237 0.033742 -0.000984\nv 0.041237 0.033742 -0.011000\nv 0.037693 0.033771 -0.011000\nv 0.037693 0.033771 -0.000200\nv 0.040453 0.033749 -0.000200\nv 0.039263 0.033196 -0.018602\nv 0.041233 0.033180 -0.016632\nv 0.037689 0.033209 -0.018602\nv 0.039267 0.033758 -0.018602\nv 0.037693 0.033771 -0.018602\nv 0.041237 0.033742 -0.016632\nv 0.033862 0.041300 -0.000984\nv 0.033849 0.040516 -0.000200\nv 0.033804 0.037756 -0.000200\nv 0.033804 0.037756 -0.011000\nv 0.033862 0.041300 -0.011000\nv 0.033300 0.041309 -0.000984\nv 0.033300 0.041309 -0.011000\nv 0.033242 0.037765 -0.011000\nv 0.033242 0.037765 -0.000200\nv 0.033288 0.040525 -0.000200\nv 0.033830 0.039330 -0.018602\nv 0.033862 0.041300 -0.016632\nv 0.033804 0.037756 -0.018602\nv 0.033268 0.039339 -0.018602\nv 0.033242 0.037765 -0.018602\nv 0.033300 0.041309 -0.016632\nv 0.017427 0.014245 -0.001400\nv 0.017310 0.014362 -0.001125\nv 0.016877 0.014794 -0.001125\nv 0.016877 0.014794 -0.001496\nv 0.017328 0.014343 -0.001496\nv 0.013892 0.017780 -0.004835\nv 0.013892 0.017780 -0.001514\nv 0.016467 0.020355 -0.001514\nv 0.016467 0.020355 -0.004835\nv 0.020285 0.016537 -0.004835\nv 0.020285 0.016537 -0.001514\nv 0.017710 0.013962 -0.001514\nv 0.017710 0.013962 -0.004835\nv 0.019453 0.017369 -0.001125\nv 0.017299 0.019523 -0.001125\nv 0.014724 0.016947 -0.001125\nv 0.029754 0.027670 -0.001125\nv 0.027600 0.029824 -0.001125\nv 0.025025 0.027248 -0.001125\nv 0.027178 0.025095 -0.001125\nv 0.024603 0.022520 -0.001125\nv 0.022450 0.024673 -0.001125\nv 0.019875 0.022098 -0.001125\nv 0.022028 0.019945 -0.001125\nv 0.032946 0.029629 -0.001427\nv 0.033162 0.029413 -0.001514\nv 0.033162 0.029413 -0.004835\nv 0.032946 0.029629 -0.004835\nv 0.028011 0.024263 -0.004835\nv 0.028011 0.024263 -0.001514\nv 0.025436 0.021687 -0.001514\nv 0.025436 0.021687 -0.004835\nv 0.022860 0.019112 -0.001514\nv 0.022860 0.019112 -0.004835\nv 0.026768 0.030656 -0.004835\nv 0.026768 0.030656 -0.001514\nv 0.029343 0.033232 -0.001514\nv 0.029343 0.033232 -0.004835\nv 0.030586 0.026838 -0.004835\nv 0.030586 0.026838 -0.001514\nv 0.024193 0.028081 -0.004835\nv 0.024193 0.028081 -0.001514\nv 0.021617 0.025506 -0.004835\nv 0.021617 0.025506 -0.001514\nv 0.019042 0.022930 -0.004835\nv 0.019042 0.022930 -0.001514\nv 0.030186 0.027238 -0.001125\nv 0.027611 0.024663 -0.001125\nv 0.025035 0.022088 -0.001125\nv 0.022460 0.019513 -0.001125\nv 0.019885 0.016937 -0.001125\nv 0.014292 0.017380 -0.001125\nv 0.014175 0.017497 -0.001400\nv 0.014273 0.017398 -0.001496\nv 0.014724 0.016947 -0.001496\nv 0.019443 0.022530 -0.001125\nv 0.016867 0.019955 -0.001125\nv 0.022018 0.025105 -0.001125\nv 0.024593 0.027681 -0.001125\nv 0.027168 0.030256 -0.001125\nv 0.029614 0.032739 -0.001496\nv 0.027150 0.030274 -0.001496\nv 0.027150 0.030274 -0.004835\nv 0.029614 0.032739 -0.004835\nv 0.019903 0.016919 -0.004835\nv 0.017328 0.014343 -0.004835\nv 0.019903 0.016919 -0.001496\nv 0.017299 0.019523 -0.001496\nv 0.016849 0.019973 -0.001496\nv 0.019453 0.017369 -0.001496\nv 0.029754 0.027670 -0.001496\nv 0.027178 0.025095 -0.001496\nv 0.025025 0.027248 -0.001496\nv 0.027600 0.029824 -0.001496\nv 0.024603 0.022520 -0.001496\nv 0.022028 0.019945 -0.001496\nv 0.019875 0.022098 -0.001496\nv 0.022450 0.024673 -0.001496\nv 0.032669 0.029684 -0.001496\nv 0.030204 0.027220 -0.001496\nv 0.031919 0.029836 -0.001496\nv 0.031925 0.029832 -0.001496\nv 0.027629 0.024644 -0.001496\nv 0.025054 0.022069 -0.001496\nv 0.022479 0.019494 -0.001496\nv 0.029766 0.031989 -0.001496\nv 0.029762 0.031995 -0.001496\nv 0.024574 0.027699 -0.001496\nv 0.021999 0.025124 -0.001496\nv 0.019424 0.022549 -0.001496\nv 0.030204 0.027220 -0.004835\nv 0.032669 0.029684 -0.004835\nv 0.027629 0.024644 -0.004835\nv 0.025054 0.022069 -0.004835\nv 0.022479 0.019494 -0.004835\nv 0.014273 0.017398 -0.004835\nv 0.016849 0.019973 -0.004835\nv 0.019424 0.022549 -0.004835\nv 0.021999 0.025124 -0.004835\nv 0.024574 0.027699 -0.004835\nv 0.031925 0.029832 -0.001125\nv 0.031919 0.029836 -0.001125\nv 0.032638 0.029690 -0.001125\nv 0.029762 0.031995 -0.001125\nv 0.029620 0.032708 -0.001125\nv 0.029766 0.031989 -0.001125\nv 0.029559 0.033016 -0.004835\nv 0.029559 0.033016 -0.001427\nv 0.029559 0.033016 -0.001304\nv 0.032946 0.029629 -0.001304\nv 0.029231 0.034436 -0.011000\nv 0.029231 0.034436 -0.000200\nv 0.029902 0.035982 -0.000200\nv 0.029902 0.035982 -0.011000\nv 0.031113 0.037155 -0.000200\nv 0.031113 0.037155 -0.011000\nv 0.032681 0.037774 -0.000200\nv 0.032681 0.037774 -0.011000\nv 0.034366 0.037747 -0.000200\nv 0.034366 0.037747 -0.011000\nv 0.035912 0.037076 -0.000200\nv 0.035912 0.037076 -0.011000\nv 0.037085 0.035865 -0.000200\nv 0.037085 0.035865 -0.011000\nv 0.037704 0.034297 -0.000200\nv 0.037704 0.034297 -0.011000\nv 0.037677 0.032612 -0.000200\nv 0.037677 0.032612 -0.011000\nv 0.037006 0.031066 -0.000200\nv 0.037006 0.031066 -0.011000\nv 0.035795 0.029893 -0.000200\nv 0.035795 0.029893 -0.011000\nv 0.034227 0.029274 -0.000200\nv 0.034227 0.029274 -0.011000\nv 0.032542 0.029301 -0.000200\nv 0.032542 0.029301 -0.011000\nv 0.030996 0.029972 -0.000200\nv 0.030996 0.029972 -0.011000\nv 0.029823 0.031183 -0.000200\nv 0.029823 0.031183 -0.011000\nv 0.029204 0.032751 -0.000200\nv 0.029204 0.032751 -0.011000\nv 0.029697 0.034335 -0.000200\nv 0.030293 0.035711 -0.000200\nv 0.031371 0.036754 -0.000200\nv 0.032766 0.037306 -0.000200\nv 0.034265 0.037281 -0.000200\nv 0.035641 0.036685 -0.000200\nv 0.036684 0.035607 -0.000200\nv 0.037236 0.034212 -0.000200\nv 0.037211 0.032713 -0.000200\nv 0.036615 0.031337 -0.000200\nv 0.035537 0.030294 -0.000200\nv 0.034142 0.029742 -0.000200\nv 0.032643 0.029767 -0.000200\nv 0.031267 0.030363 -0.000200\nv 0.030224 0.031441 -0.000200\nv 0.029672 0.032836 -0.000200\nv 0.030224 0.031441 -0.009326\nv 0.029672 0.032836 -0.009326\nv 0.031163 0.035815 -0.009326\nv 0.031732 0.036195 -0.009326\nv 0.031371 0.036754 -0.009326\nv 0.030293 0.035711 -0.009326\nv 0.029697 0.034335 -0.009326\nv 0.031267 0.030363 -0.009326\nv 0.032643 0.029767 -0.009326\nv 0.034142 0.029742 -0.009326\nv 0.035537 0.030294 -0.009326\nv 0.035176 0.030853 -0.009326\nv 0.034694 0.030531 -0.009326\nv 0.033454 0.030284 -0.009326\nv 0.030461 0.034764 -0.009326\nv 0.032214 0.030531 -0.009326\nv 0.030214 0.033524 -0.009326\nv 0.030461 0.032284 -0.009326\nv 0.031163 0.031233 -0.009326\nv 0.035745 0.031233 -0.009326\nv 0.036615 0.031337 -0.009326\nv 0.037211 0.032713 -0.009326\nv 0.037236 0.034212 -0.009326\nv 0.036684 0.035607 -0.009326\nv 0.035641 0.036685 -0.009326\nv 0.034265 0.037281 -0.009326\nv 0.032766 0.037306 -0.009326\nv 0.032214 0.036517 -0.009326\nv 0.033454 0.036764 -0.009326\nv 0.036447 0.032284 -0.009326\nv 0.034694 0.036517 -0.009326\nv 0.036694 0.033524 -0.009326\nv 0.036447 0.034764 -0.009326\nv 0.035745 0.035815 -0.009326\nv 0.030327 0.032955 -0.011000\nv 0.036581 0.034093 -0.011000\nv 0.036447 0.034764 -0.011000\nv 0.030214 0.033524 -0.011000\nv 0.030461 0.034764 -0.011000\nv 0.035745 0.035815 -0.011000\nv 0.034694 0.036517 -0.011000\nv 0.031163 0.035815 -0.011000\nv 0.033454 0.036764 -0.011000\nv 0.032214 0.036517 -0.011000\nv 0.036694 0.033524 -0.011000\nv 0.030461 0.032284 -0.011000\nv 0.031163 0.031233 -0.011000\nv 0.036447 0.032284 -0.011000\nv 0.032214 0.030531 -0.011000\nv 0.035745 0.031233 -0.011000\nv 0.034694 0.030531 -0.011000\nv 0.033454 0.030284 -0.011000\nv -0.041285 0.033180 -0.000984\nv -0.040501 0.033187 -0.000200\nv -0.037741 0.033209 -0.000200\nv -0.037741 0.033209 -0.011000\nv -0.041285 0.033180 -0.011000\nv -0.041289 0.033742 -0.000984\nv -0.041289 0.033742 -0.011000\nv -0.037745 0.033771 -0.011000\nv -0.037745 0.033771 -0.000200\nv -0.040505 0.033749 -0.000200\nv -0.039315 0.033196 -0.018602\nv -0.041285 0.033180 -0.016632\nv -0.037741 0.033209 -0.018602\nv -0.039319 0.033758 -0.018602\nv -0.037745 0.033771 -0.018602\nv -0.041289 0.033742 -0.016632\nv -0.033914 0.041300 -0.000984\nv -0.033901 0.040516 -0.000200\nv -0.033856 0.037756 -0.000200\nv -0.033856 0.037756 -0.011000\nv -0.033914 0.041300 -0.011000\nv -0.033352 0.041309 -0.000984\nv -0.033352 0.041309 -0.011000\nv -0.033294 0.037765 -0.011000\nv -0.033294 0.037765 -0.000200\nv -0.033340 0.040525 -0.000200\nv -0.033882 0.039330 -0.018602\nv -0.033914 0.041300 -0.016632\nv -0.033856 0.037756 -0.018602\nv -0.033320 0.039339 -0.018602\nv -0.033294 0.037765 -0.018602\nv -0.033352 0.041309 -0.016632\nv -0.017479 0.014245 -0.001400\nv -0.017362 0.014362 -0.001125\nv -0.016929 0.014794 -0.001125\nv -0.016929 0.014794 -0.001496\nv -0.017380 0.014343 -0.001496\nv -0.013944 0.017780 -0.004835\nv -0.013944 0.017780 -0.001514\nv -0.016519 0.020355 -0.001514\nv -0.016519 0.020355 -0.004835\nv -0.020337 0.016537 -0.004835\nv -0.020337 0.016537 -0.001514\nv -0.017762 0.013962 -0.001514\nv -0.017762 0.013962 -0.004835\nv -0.019505 0.017369 -0.001125\nv -0.017351 0.019523 -0.001125\nv -0.014776 0.016947 -0.001125\nv -0.029806 0.027670 -0.001125\nv -0.027652 0.029824 -0.001125\nv -0.025077 0.027248 -0.001125\nv -0.027230 0.025095 -0.001125\nv -0.024655 0.022520 -0.001125\nv -0.022502 0.024673 -0.001125\nv -0.019927 0.022098 -0.001125\nv -0.022080 0.019945 -0.001125\nv -0.032998 0.029629 -0.001427\nv -0.033214 0.029413 -0.001514\nv -0.033214 0.029413 -0.004835\nv -0.032998 0.029629 -0.004835\nv -0.028063 0.024263 -0.004835\nv -0.028063 0.024263 -0.001514\nv -0.025488 0.021687 -0.001514\nv -0.025488 0.021687 -0.004835\nv -0.022912 0.019112 -0.001514\nv -0.022912 0.019112 -0.004835\nv -0.026820 0.030656 -0.004835\nv -0.026820 0.030656 -0.001514\nv -0.029395 0.033232 -0.001514\nv -0.029395 0.033232 -0.004835\nv -0.030638 0.026838 -0.004835\nv -0.030638 0.026838 -0.001514\nv -0.024245 0.028081 -0.004835\nv -0.024245 0.028081 -0.001514\nv -0.021669 0.025506 -0.004835\nv -0.021669 0.025506 -0.001514\nv -0.019094 0.022930 -0.004835\nv -0.019094 0.022930 -0.001514\nv -0.030238 0.027238 -0.001125\nv -0.027663 0.024663 -0.001125\nv -0.025087 0.022088 -0.001125\nv -0.022512 0.019513 -0.001125\nv -0.019937 0.016937 -0.001125\nv -0.014344 0.017380 -0.001125\nv -0.014227 0.017497 -0.001400\nv -0.014325 0.017398 -0.001496\nv -0.014776 0.016947 -0.001496\nv -0.019495 0.022530 -0.001125\nv -0.016919 0.019955 -0.001125\nv -0.022070 0.025105 -0.001125\nv -0.024645 0.027681 -0.001125\nv -0.027220 0.030256 -0.001125\nv -0.029666 0.032739 -0.001496\nv -0.027202 0.030274 -0.001496\nv -0.027202 0.030274 -0.004835\nv -0.029666 0.032739 -0.004835\nv -0.019955 0.016919 -0.004835\nv -0.017380 0.014343 -0.004835\nv -0.019955 0.016919 -0.001496\nv -0.017351 0.019523 -0.001496\nv -0.016901 0.019973 -0.001496\nv -0.019505 0.017369 -0.001496\nv -0.029806 0.027670 -0.001496\nv -0.027230 0.025095 -0.001496\nv -0.025077 0.027248 -0.001496\nv -0.027652 0.029824 -0.001496\nv -0.024655 0.022520 -0.001496\nv -0.022080 0.019945 -0.001496\nv -0.019927 0.022098 -0.001496\nv -0.022502 0.024673 -0.001496\nv -0.032721 0.029684 -0.001496\nv -0.030256 0.027220 -0.001496\nv -0.031971 0.029836 -0.001496\nv -0.031977 0.029832 -0.001496\nv -0.027681 0.024644 -0.001496\nv -0.025106 0.022069 -0.001496\nv -0.022531 0.019494 -0.001496\nv -0.029818 0.031989 -0.001496\nv -0.029814 0.031995 -0.001496\nv -0.024626 0.027699 -0.001496\nv -0.022051 0.025124 -0.001496\nv -0.019476 0.022549 -0.001496\nv -0.030256 0.027220 -0.004835\nv -0.032721 0.029684 -0.004835\nv -0.027681 0.024644 -0.004835\nv -0.025106 0.022069 -0.004835\nv -0.022531 0.019494 -0.004835\nv -0.014325 0.017398 -0.004835\nv -0.016901 0.019973 -0.004835\nv -0.019476 0.022549 -0.004835\nv -0.022051 0.025124 -0.004835\nv -0.024626 0.027699 -0.004835\nv -0.031977 0.029832 -0.001125\nv -0.031971 0.029836 -0.001125\nv -0.032690 0.029690 -0.001125\nv -0.029814 0.031995 -0.001125\nv -0.029672 0.032708 -0.001125\nv -0.029818 0.031989 -0.001125\nv -0.029611 0.033016 -0.004835\nv -0.029611 0.033016 -0.001427\nv -0.029611 0.033016 -0.001304\nv -0.032998 0.029629 -0.001304\nv -0.029283 0.034436 -0.011000\nv -0.029283 0.034436 -0.000200\nv -0.029954 0.035982 -0.000200\nv -0.029954 0.035982 -0.011000\nv -0.031165 0.037155 -0.000200\nv -0.031165 0.037155 -0.011000\nv -0.032733 0.037774 -0.000200\nv -0.032733 0.037774 -0.011000\nv -0.034418 0.037747 -0.000200\nv -0.034418 0.037747 -0.011000\nv -0.035964 0.037076 -0.000200\nv -0.035964 0.037076 -0.011000\nv -0.037137 0.035865 -0.000200\nv -0.037137 0.035865 -0.011000\nv -0.037756 0.034297 -0.000200\nv -0.037756 0.034297 -0.011000\nv -0.037729 0.032612 -0.000200\nv -0.037729 0.032612 -0.011000\nv -0.037058 0.031066 -0.000200\nv -0.037058 0.031066 -0.011000\nv -0.035847 0.029893 -0.000200\nv -0.035847 0.029893 -0.011000\nv -0.034279 0.029274 -0.000200\nv -0.034279 0.029274 -0.011000\nv -0.032594 0.029301 -0.000200\nv -0.032594 0.029301 -0.011000\nv -0.031048 0.029972 -0.000200\nv -0.031048 0.029972 -0.011000\nv -0.029875 0.031183 -0.000200\nv -0.029875 0.031183 -0.011000\nv -0.029256 0.032751 -0.000200\nv -0.029256 0.032751 -0.011000\nv -0.029749 0.034335 -0.000200\nv -0.030345 0.035711 -0.000200\nv -0.031423 0.036754 -0.000200\nv -0.032818 0.037306 -0.000200\nv -0.034317 0.037281 -0.000200\nv -0.035693 0.036685 -0.000200\nv -0.036736 0.035607 -0.000200\nv -0.037288 0.034212 -0.000200\nv -0.037263 0.032713 -0.000200\nv -0.036667 0.031337 -0.000200\nv -0.035589 0.030294 -0.000200\nv -0.034194 0.029742 -0.000200\nv -0.032695 0.029767 -0.000200\nv -0.031319 0.030363 -0.000200\nv -0.030276 0.031441 -0.000200\nv -0.029724 0.032836 -0.000200\nv -0.030276 0.031441 -0.009326\nv -0.029724 0.032836 -0.009326\nv -0.031215 0.035815 -0.009326\nv -0.031784 0.036195 -0.009326\nv -0.031423 0.036754 -0.009326\nv -0.030345 0.035711 -0.009326\nv -0.029749 0.034335 -0.009326\nv -0.031319 0.030363 -0.009326\nv -0.032695 0.029767 -0.009326\nv -0.034194 0.029742 -0.009326\nv -0.035589 0.030294 -0.009326\nv -0.035228 0.030853 -0.009326\nv -0.034746 0.030531 -0.009326\nv -0.033506 0.030284 -0.009326\nv -0.030513 0.034764 -0.009326\nv -0.032266 0.030531 -0.009326\nv -0.030266 0.033524 -0.009326\nv -0.030513 0.032284 -0.009326\nv -0.031215 0.031233 -0.009326\nv -0.035797 0.031233 -0.009326\nv -0.036667 0.031337 -0.009326\nv -0.037263 0.032713 -0.009326\nv -0.037288 0.034212 -0.009326\nv -0.036736 0.035607 -0.009326\nv -0.035693 0.036685 -0.009326\nv -0.034317 0.037281 -0.009326\nv -0.032818 0.037306 -0.009326\nv -0.032266 0.036517 -0.009326\nv -0.033506 0.036764 -0.009326\nv -0.036499 0.032284 -0.009326\nv -0.034746 0.036517 -0.009326\nv -0.036746 0.033524 -0.009326\nv -0.036499 0.034764 -0.009326\nv -0.035797 0.035815 -0.009326\nv -0.030379 0.032955 -0.011000\nv -0.036633 0.034093 -0.011000\nv -0.036499 0.034764 -0.011000\nv -0.030266 0.033524 -0.011000\nv -0.030513 0.034764 -0.011000\nv -0.035797 0.035815 -0.011000\nv -0.034746 0.036517 -0.011000\nv -0.031215 0.035815 -0.011000\nv -0.033506 0.036764 -0.011000\nv -0.032266 0.036517 -0.011000\nv -0.036746 0.033524 -0.011000\nv -0.030513 0.032284 -0.011000\nv -0.031215 0.031233 -0.011000\nv -0.036499 0.032284 -0.011000\nv -0.032266 0.030531 -0.011000\nv -0.035797 0.031233 -0.011000\nv -0.034746 0.030531 -0.011000\nv -0.033506 0.030284 -0.011000\nv 0.041233 -0.033092 -0.000984\nv 0.040449 -0.033099 -0.000200\nv 0.037689 -0.033121 -0.000200\nv 0.037689 -0.033121 -0.011000\nv 0.041233 -0.033092 -0.011000\nv 0.041237 -0.033654 -0.000984\nv 0.041237 -0.033654 -0.011000\nv 0.037693 -0.033683 -0.011000\nv 0.037693 -0.033683 -0.000200\nv 0.040453 -0.033661 -0.000200\nv 0.039263 -0.033108 -0.018602\nv 0.041233 -0.033092 -0.016632\nv 0.037689 -0.033121 -0.018602\nv 0.039267 -0.033670 -0.018602\nv 0.037693 -0.033683 -0.018602\nv 0.041237 -0.033654 -0.016632\nv 0.033862 -0.041212 -0.000984\nv 0.033849 -0.040428 -0.000200\nv 0.033804 -0.037668 -0.000200\nv 0.033804 -0.037668 -0.011000\nv 0.033862 -0.041212 -0.011000\nv 0.033300 -0.041221 -0.000984\nv 0.033300 -0.041221 -0.011000\nv 0.033242 -0.037677 -0.011000\nv 0.033242 -0.037677 -0.000200\nv 0.033288 -0.040437 -0.000200\nv 0.033830 -0.039242 -0.018602\nv 0.033862 -0.041212 -0.016632\nv 0.033804 -0.037668 -0.018602\nv 0.033268 -0.039251 -0.018602\nv 0.033242 -0.037677 -0.018602\nv 0.033300 -0.041221 -0.016632\nv 0.017427 -0.014157 -0.001400\nv 0.017310 -0.014274 -0.001125\nv 0.016877 -0.014706 -0.001125\nv 0.016877 -0.014706 -0.001496\nv 0.017328 -0.014255 -0.001496\nv 0.013892 -0.017692 -0.004835\nv 0.013892 -0.017692 -0.001514\nv 0.016467 -0.020267 -0.001514\nv 0.016467 -0.020267 -0.004835\nv 0.020285 -0.016449 -0.004835\nv 0.020285 -0.016449 -0.001514\nv 0.017710 -0.013874 -0.001514\nv 0.017710 -0.013874 -0.004835\nv 0.019453 -0.017281 -0.001125\nv 0.017299 -0.019435 -0.001125\nv 0.014724 -0.016859 -0.001125\nv 0.029754 -0.027582 -0.001125\nv 0.027600 -0.029736 -0.001125\nv 0.025025 -0.027160 -0.001125\nv 0.027178 -0.025007 -0.001125\nv 0.024603 -0.022432 -0.001125\nv 0.022450 -0.024585 -0.001125\nv 0.019875 -0.022010 -0.001125\nv 0.022028 -0.019857 -0.001125\nv 0.032946 -0.029541 -0.001427\nv 0.033162 -0.029325 -0.001514\nv 0.033162 -0.029325 -0.004835\nv 0.032946 -0.029541 -0.004835\nv 0.028011 -0.024175 -0.004835\nv 0.028011 -0.024175 -0.001514\nv 0.025436 -0.021599 -0.001514\nv 0.025436 -0.021599 -0.004835\nv 0.022860 -0.019024 -0.001514\nv 0.022860 -0.019024 -0.004835\nv 0.026768 -0.030568 -0.004835\nv 0.026768 -0.030568 -0.001514\nv 0.029343 -0.033144 -0.001514\nv 0.029343 -0.033144 -0.004835\nv 0.030586 -0.026750 -0.004835\nv 0.030586 -0.026750 -0.001514\nv 0.024193 -0.027993 -0.004835\nv 0.024193 -0.027993 -0.001514\nv 0.021617 -0.025418 -0.004835\nv 0.021617 -0.025418 -0.001514\nv 0.019042 -0.022842 -0.004835\nv 0.019042 -0.022842 -0.001514\nv 0.030186 -0.027150 -0.001125\nv 0.027611 -0.024575 -0.001125\nv 0.025035 -0.022000 -0.001125\nv 0.022460 -0.019425 -0.001125\nv 0.019885 -0.016849 -0.001125\nv 0.014292 -0.017292 -0.001125\nv 0.014175 -0.017409 -0.001400\nv 0.014273 -0.017310 -0.001496\nv 0.014724 -0.016859 -0.001496\nv 0.019443 -0.022442 -0.001125\nv 0.016867 -0.019867 -0.001125\nv 0.022018 -0.025017 -0.001125\nv 0.024593 -0.027593 -0.001125\nv 0.027168 -0.030168 -0.001125\nv 0.029614 -0.032651 -0.001496\nv 0.027150 -0.030186 -0.001496\nv 0.027150 -0.030186 -0.004835\nv 0.029614 -0.032651 -0.004835\nv 0.019903 -0.016831 -0.004835\nv 0.017328 -0.014255 -0.004835\nv 0.019903 -0.016831 -0.001496\nv 0.017299 -0.019435 -0.001496\nv 0.016849 -0.019885 -0.001496\nv 0.019453 -0.017281 -0.001496\nv 0.029754 -0.027582 -0.001496\nv 0.027178 -0.025007 -0.001496\nv 0.025025 -0.027160 -0.001496\nv 0.027600 -0.029736 -0.001496\nv 0.024603 -0.022432 -0.001496\nv 0.022028 -0.019857 -0.001496\nv 0.019875 -0.022010 -0.001496\nv 0.022450 -0.024585 -0.001496\nv 0.032669 -0.029596 -0.001496\nv 0.030204 -0.027132 -0.001496\nv 0.031919 -0.029748 -0.001496\nv 0.031925 -0.029744 -0.001496\nv 0.027629 -0.024556 -0.001496\nv 0.025054 -0.021981 -0.001496\nv 0.022479 -0.019406 -0.001496\nv 0.029766 -0.031901 -0.001496\nv 0.029762 -0.031907 -0.001496\nv 0.024574 -0.027611 -0.001496\nv 0.021999 -0.025036 -0.001496\nv 0.019424 -0.022461 -0.001496\nv 0.030204 -0.027132 -0.004835\nv 0.032669 -0.029596 -0.004835\nv 0.027629 -0.024556 -0.004835\nv 0.025054 -0.021981 -0.004835\nv 0.022479 -0.019406 -0.004835\nv 0.014273 -0.017310 -0.004835\nv 0.016849 -0.019885 -0.004835\nv 0.019424 -0.022461 -0.004835\nv 0.021999 -0.025036 -0.004835\nv 0.024574 -0.027611 -0.004835\nv 0.031925 -0.029744 -0.001125\nv 0.031919 -0.029748 -0.001125\nv 0.032638 -0.029602 -0.001125\nv 0.029762 -0.031907 -0.001125\nv 0.029620 -0.032620 -0.001125\nv 0.029766 -0.031901 -0.001125\nv 0.029559 -0.032928 -0.004835\nv 0.029559 -0.032928 -0.001427\nv 0.029559 -0.032928 -0.001304\nv 0.032946 -0.029541 -0.001304\nv 0.029231 -0.034348 -0.011000\nv 0.029231 -0.034348 -0.000200\nv 0.029902 -0.035894 -0.000200\nv 0.029902 -0.035894 -0.011000\nv 0.031113 -0.037067 -0.000200\nv 0.031113 -0.037067 -0.011000\nv 0.032681 -0.037686 -0.000200\nv 0.032681 -0.037686 -0.011000\nv 0.034366 -0.037659 -0.000200\nv 0.034366 -0.037659 -0.011000\nv 0.035912 -0.036988 -0.000200\nv 0.035912 -0.036988 -0.011000\nv 0.037085 -0.035777 -0.000200\nv 0.037085 -0.035777 -0.011000\nv 0.037704 -0.034209 -0.000200\nv 0.037704 -0.034209 -0.011000\nv 0.037677 -0.032524 -0.000200\nv 0.037677 -0.032524 -0.011000\nv 0.037006 -0.030978 -0.000200\nv 0.037006 -0.030978 -0.011000\nv 0.035795 -0.029805 -0.000200\nv 0.035795 -0.029805 -0.011000\nv 0.034227 -0.029186 -0.000200\nv 0.034227 -0.029186 -0.011000\nv 0.032542 -0.029213 -0.000200\nv 0.032542 -0.029213 -0.011000\nv 0.030996 -0.029884 -0.000200\nv 0.030996 -0.029884 -0.011000\nv 0.029823 -0.031095 -0.000200\nv 0.029823 -0.031095 -0.011000\nv 0.029204 -0.032663 -0.000200\nv 0.029204 -0.032663 -0.011000\nv 0.029697 -0.034247 -0.000200\nv 0.030293 -0.035623 -0.000200\nv 0.031371 -0.036666 -0.000200\nv 0.032766 -0.037218 -0.000200\nv 0.034265 -0.037193 -0.000200\nv 0.035641 -0.036597 -0.000200\nv 0.036684 -0.035519 -0.000200\nv 0.037236 -0.034124 -0.000200\nv 0.037211 -0.032625 -0.000200\nv 0.036615 -0.031249 -0.000200\nv 0.035537 -0.030206 -0.000200\nv 0.034142 -0.029654 -0.000200\nv 0.032643 -0.029679 -0.000200\nv 0.031267 -0.030275 -0.000200\nv 0.030224 -0.031353 -0.000200\nv 0.029672 -0.032748 -0.000200\nv 0.030224 -0.031353 -0.009326\nv 0.029672 -0.032748 -0.009326\nv 0.031163 -0.035727 -0.009326\nv 0.031732 -0.036107 -0.009326\nv 0.031371 -0.036666 -0.009326\nv 0.030293 -0.035623 -0.009326\nv 0.029697 -0.034247 -0.009326\nv 0.031267 -0.030275 -0.009326\nv 0.032643 -0.029679 -0.009326\nv 0.034142 -0.029654 -0.009326\nv 0.035537 -0.030206 -0.009326\nv 0.035176 -0.030765 -0.009326\nv 0.034694 -0.030443 -0.009326\nv 0.033454 -0.030196 -0.009326\nv 0.030461 -0.034676 -0.009326\nv 0.032214 -0.030443 -0.009326\nv 0.030214 -0.033436 -0.009326\nv 0.030461 -0.032196 -0.009326\nv 0.031163 -0.031145 -0.009326\nv 0.035745 -0.031145 -0.009326\nv 0.036615 -0.031249 -0.009326\nv 0.037211 -0.032625 -0.009326\nv 0.037236 -0.034124 -0.009326\nv 0.036684 -0.035519 -0.009326\nv 0.035641 -0.036597 -0.009326\nv 0.034265 -0.037193 -0.009326\nv 0.032766 -0.037218 -0.009326\nv 0.032214 -0.036429 -0.009326\nv 0.033454 -0.036676 -0.009326\nv 0.036447 -0.032196 -0.009326\nv 0.034694 -0.036429 -0.009326\nv 0.036694 -0.033436 -0.009326\nv 0.036447 -0.034676 -0.009326\nv 0.035745 -0.035727 -0.009326\nv 0.030327 -0.032867 -0.011000\nv 0.036581 -0.034005 -0.011000\nv 0.036447 -0.034676 -0.011000\nv 0.030214 -0.033436 -0.011000\nv 0.030461 -0.034676 -0.011000\nv 0.035745 -0.035727 -0.011000\nv 0.034694 -0.036429 -0.011000\nv 0.031163 -0.035727 -0.011000\nv 0.033454 -0.036676 -0.011000\nv 0.032214 -0.036429 -0.011000\nv 0.036694 -0.033436 -0.011000\nv 0.030461 -0.032196 -0.011000\nv 0.031163 -0.031145 -0.011000\nv 0.036447 -0.032196 -0.011000\nv 0.032214 -0.030443 -0.011000\nv 0.035745 -0.031145 -0.011000\nv 0.034694 -0.030443 -0.011000\nv 0.033454 -0.030196 -0.011000\nv -0.041285 -0.033092 -0.000984\nv -0.040501 -0.033099 -0.000200\nv -0.037741 -0.033121 -0.000200\nv -0.037741 -0.033121 -0.011000\nv -0.041285 -0.033092 -0.011000\nv -0.041289 -0.033654 -0.000984\nv -0.041289 -0.033654 -0.011000\nv -0.037745 -0.033683 -0.011000\nv -0.037745 -0.033683 -0.000200\nv -0.040505 -0.033661 -0.000200\nv -0.039315 -0.033108 -0.018602\nv -0.041285 -0.033092 -0.016632\nv -0.037741 -0.033121 -0.018602\nv -0.039319 -0.033670 -0.018602\nv -0.037745 -0.033683 -0.018602\nv -0.041289 -0.033654 -0.016632\nv -0.033914 -0.041212 -0.000984\nv -0.033901 -0.040428 -0.000200\nv -0.033856 -0.037668 -0.000200\nv -0.033856 -0.037668 -0.011000\nv -0.033914 -0.041212 -0.011000\nv -0.033352 -0.041221 -0.000984\nv -0.033352 -0.041221 -0.011000\nv -0.033294 -0.037677 -0.011000\nv -0.033294 -0.037677 -0.000200\nv -0.033340 -0.040437 -0.000200\nv -0.033882 -0.039242 -0.018602\nv -0.033914 -0.041212 -0.016632\nv -0.033856 -0.037668 -0.018602\nv -0.033320 -0.039251 -0.018602\nv -0.033294 -0.037677 -0.018602\nv -0.033352 -0.041221 -0.016632\nv -0.017479 -0.014157 -0.001400\nv -0.017362 -0.014274 -0.001125\nv -0.016929 -0.014706 -0.001125\nv -0.016929 -0.014706 -0.001496\nv -0.017380 -0.014255 -0.001496\nv -0.013944 -0.017692 -0.004835\nv -0.013944 -0.017692 -0.001514\nv -0.016519 -0.020267 -0.001514\nv -0.016519 -0.020267 -0.004835\nv -0.020337 -0.016449 -0.004835\nv -0.020337 -0.016449 -0.001514\nv -0.017762 -0.013874 -0.001514\nv -0.017762 -0.013874 -0.004835\nv -0.019505 -0.017281 -0.001125\nv -0.017351 -0.019435 -0.001125\nv -0.014776 -0.016859 -0.001125\nv -0.029806 -0.027582 -0.001125\nv -0.027652 -0.029736 -0.001125\nv -0.025077 -0.027160 -0.001125\nv -0.027230 -0.025007 -0.001125\nv -0.024655 -0.022432 -0.001125\nv -0.022502 -0.024585 -0.001125\nv -0.019927 -0.022010 -0.001125\nv -0.022080 -0.019857 -0.001125\nv -0.032998 -0.029541 -0.001427\nv -0.033214 -0.029325 -0.001514\nv -0.033214 -0.029325 -0.004835\nv -0.032998 -0.029541 -0.004835\nv -0.028063 -0.024175 -0.004835\nv -0.028063 -0.024175 -0.001514\nv -0.025488 -0.021599 -0.001514\nv -0.025488 -0.021599 -0.004835\nv -0.022912 -0.019024 -0.001514\nv -0.022912 -0.019024 -0.004835\nv -0.026820 -0.030568 -0.004835\nv -0.026820 -0.030568 -0.001514\nv -0.029395 -0.033144 -0.001514\nv -0.029395 -0.033144 -0.004835\nv -0.030638 -0.026750 -0.004835\nv -0.030638 -0.026750 -0.001514\nv -0.024245 -0.027993 -0.004835\nv -0.024245 -0.027993 -0.001514\nv -0.021669 -0.025418 -0.004835\nv -0.021669 -0.025418 -0.001514\nv -0.019094 -0.022842 -0.004835\nv -0.019094 -0.022842 -0.001514\nv -0.030238 -0.027150 -0.001125\nv -0.027663 -0.024575 -0.001125\nv -0.025087 -0.022000 -0.001125\nv -0.022512 -0.019425 -0.001125\nv -0.019937 -0.016849 -0.001125\nv -0.014344 -0.017292 -0.001125\nv -0.014227 -0.017409 -0.001400\nv -0.014325 -0.017310 -0.001496\nv -0.014776 -0.016859 -0.001496\nv -0.019495 -0.022442 -0.001125\nv -0.016919 -0.019867 -0.001125\nv -0.022070 -0.025017 -0.001125\nv -0.024645 -0.027593 -0.001125\nv -0.027220 -0.030168 -0.001125\nv -0.029666 -0.032651 -0.001496\nv -0.027202 -0.030186 -0.001496\nv -0.027202 -0.030186 -0.004835\nv -0.029666 -0.032651 -0.004835\nv -0.019955 -0.016831 -0.004835\nv -0.017380 -0.014255 -0.004835\nv -0.019955 -0.016831 -0.001496\nv -0.017351 -0.019435 -0.001496\nv -0.016901 -0.019885 -0.001496\nv -0.019505 -0.017281 -0.001496\nv -0.029806 -0.027582 -0.001496\nv -0.027230 -0.025007 -0.001496\nv -0.025077 -0.027160 -0.001496\nv -0.027652 -0.029736 -0.001496\nv -0.024655 -0.022432 -0.001496\nv -0.022080 -0.019857 -0.001496\nv -0.019927 -0.022010 -0.001496\nv -0.022502 -0.024585 -0.001496\nv -0.032721 -0.029596 -0.001496\nv -0.030256 -0.027132 -0.001496\nv -0.031971 -0.029748 -0.001496\nv -0.031977 -0.029744 -0.001496\nv -0.027681 -0.024556 -0.001496\nv -0.025106 -0.021981 -0.001496\nv -0.022531 -0.019406 -0.001496\nv -0.029818 -0.031901 -0.001496\nv -0.029814 -0.031907 -0.001496\nv -0.024626 -0.027611 -0.001496\nv -0.022051 -0.025036 -0.001496\nv -0.019476 -0.022461 -0.001496\nv -0.030256 -0.027132 -0.004835\nv -0.032721 -0.029596 -0.004835\nv -0.027681 -0.024556 -0.004835\nv -0.025106 -0.021981 -0.004835\nv -0.022531 -0.019406 -0.004835\nv -0.014325 -0.017310 -0.004835\nv -0.016901 -0.019885 -0.004835\nv -0.019476 -0.022461 -0.004835\nv -0.022051 -0.025036 -0.004835\nv -0.024626 -0.027611 -0.004835\nv -0.031977 -0.029744 -0.001125\nv -0.031971 -0.029748 -0.001125\nv -0.032690 -0.029602 -0.001125\nv -0.029814 -0.031907 -0.001125\nv -0.029672 -0.032620 -0.001125\nv -0.029818 -0.031901 -0.001125\nv -0.029611 -0.032928 -0.004835\nv -0.029611 -0.032928 -0.001427\nv -0.029611 -0.032928 -0.001304\nv -0.032998 -0.029541 -0.001304\nv -0.029283 -0.034348 -0.011000\nv -0.029283 -0.034348 -0.000200\nv -0.029954 -0.035894 -0.000200\nv -0.029954 -0.035894 -0.011000\nv -0.031165 -0.037067 -0.000200\nv -0.031165 -0.037067 -0.011000\nv -0.032733 -0.037686 -0.000200\nv -0.032733 -0.037686 -0.011000\nv -0.034418 -0.037659 -0.000200\nv -0.034418 -0.037659 -0.011000\nv -0.035964 -0.036988 -0.000200\nv -0.035964 -0.036988 -0.011000\nv -0.037137 -0.035777 -0.000200\nv -0.037137 -0.035777 -0.011000\nv -0.037756 -0.034209 -0.000200\nv -0.037756 -0.034209 -0.011000\nv -0.037729 -0.032524 -0.000200\nv -0.037729 -0.032524 -0.011000\nv -0.037058 -0.030978 -0.000200\nv -0.037058 -0.030978 -0.011000\nv -0.035847 -0.029805 -0.000200\nv -0.035847 -0.029805 -0.011000\nv -0.034279 -0.029186 -0.000200\nv -0.034279 -0.029186 -0.011000\nv -0.032594 -0.029213 -0.000200\nv -0.032594 -0.029213 -0.011000\nv -0.031048 -0.029884 -0.000200\nv -0.031048 -0.029884 -0.011000\nv -0.029875 -0.031095 -0.000200\nv -0.029875 -0.031095 -0.011000\nv -0.029256 -0.032663 -0.000200\nv -0.029256 -0.032663 -0.011000\nv -0.029749 -0.034247 -0.000200\nv -0.030345 -0.035623 -0.000200\nv -0.031423 -0.036666 -0.000200\nv -0.032818 -0.037218 -0.000200\nv -0.034317 -0.037193 -0.000200\nv -0.035693 -0.036597 -0.000200\nv -0.036736 -0.035519 -0.000200\nv -0.037288 -0.034124 -0.000200\nv -0.037263 -0.032625 -0.000200\nv -0.036667 -0.031249 -0.000200\nv -0.035589 -0.030206 -0.000200\nv -0.034194 -0.029654 -0.000200\nv -0.032695 -0.029679 -0.000200\nv -0.031319 -0.030275 -0.000200\nv -0.030276 -0.031353 -0.000200\nv -0.029724 -0.032748 -0.000200\nv -0.030276 -0.031353 -0.009326\nv -0.029724 -0.032748 -0.009326\nv -0.031215 -0.035727 -0.009326\nv -0.031784 -0.036107 -0.009326\nv -0.031423 -0.036666 -0.009326\nv -0.030345 -0.035623 -0.009326\nv -0.029749 -0.034247 -0.009326\nv -0.031319 -0.030275 -0.009326\nv -0.032695 -0.029679 -0.009326\nv -0.034194 -0.029654 -0.009326\nv -0.035589 -0.030206 -0.009326\nv -0.035228 -0.030765 -0.009326\nv -0.034746 -0.030443 -0.009326\nv -0.033506 -0.030196 -0.009326\nv -0.030513 -0.034676 -0.009326\nv -0.032266 -0.030443 -0.009326\nv -0.030266 -0.033436 -0.009326\nv -0.030513 -0.032196 -0.009326\nv -0.031215 -0.031145 -0.009326\nv -0.035797 -0.031145 -0.009326\nv -0.036667 -0.031249 -0.009326\nv -0.037263 -0.032625 -0.009326\nv -0.037288 -0.034124 -0.009326\nv -0.036736 -0.035519 -0.009326\nv -0.035693 -0.036597 -0.009326\nv -0.034317 -0.037193 -0.009326\nv -0.032818 -0.037218 -0.009326\nv -0.032266 -0.036429 -0.009326\nv -0.033506 -0.036676 -0.009326\nv -0.036499 -0.032196 -0.009326\nv -0.034746 -0.036429 -0.009326\nv -0.036746 -0.033436 -0.009326\nv -0.036499 -0.034676 -0.009326\nv -0.035797 -0.035727 -0.009326\nv -0.030379 -0.032867 -0.011000\nv -0.036633 -0.034005 -0.011000\nv -0.036499 -0.034676 -0.011000\nv -0.030266 -0.033436 -0.011000\nv -0.030513 -0.034676 -0.011000\nv -0.035797 -0.035727 -0.011000\nv -0.034746 -0.036429 -0.011000\nv -0.031215 -0.035727 -0.011000\nv -0.033506 -0.036676 -0.011000\nv -0.032266 -0.036429 -0.011000\nv -0.036746 -0.033436 -0.011000\nv -0.030513 -0.032196 -0.011000\nv -0.031215 -0.031145 -0.011000\nv -0.036499 -0.032196 -0.011000\nv -0.032266 -0.030443 -0.011000\nv -0.035797 -0.031145 -0.011000\nv -0.034746 -0.030443 -0.011000\nv -0.033506 -0.030196 -0.011000\nv 0.033454 0.036571 -0.003478\nv 0.033454 0.036571 0.007948\nv 0.034620 0.036339 -0.003478\nv 0.034620 0.036339 0.007948\nv 0.035609 0.035679 -0.003478\nv 0.035609 0.035679 0.007948\nv 0.036269 0.034690 -0.003478\nv 0.036269 0.034690 0.007948\nv 0.036501 0.033524 -0.003478\nv 0.036501 0.033524 0.007948\nv 0.036269 0.032358 -0.003478\nv 0.036269 0.032358 0.007948\nv 0.035609 0.031369 -0.003478\nv 0.035609 0.031369 0.007948\nv 0.034620 0.030709 -0.003478\nv 0.034620 0.030709 0.007948\nv 0.033454 0.030477 -0.003478\nv 0.033454 0.030477 0.007948\nv 0.032288 0.030709 -0.003478\nv 0.032288 0.030709 0.007948\nv 0.031299 0.031369 -0.003478\nv 0.031299 0.031369 0.007948\nv 0.030639 0.032358 -0.003478\nv 0.030639 0.032358 0.007948\nv 0.030407 0.033524 -0.003478\nv 0.030407 0.033524 0.007948\nv 0.030639 0.034690 -0.003478\nv 0.030639 0.034690 0.007948\nv 0.031299 0.035679 -0.003478\nv 0.031299 0.035679 0.007948\nv 0.032288 0.036339 -0.003478\nv 0.032288 0.036339 0.007948\nv -0.033506 0.036571 -0.003478\nv -0.033506 0.036571 0.007948\nv -0.034672 0.036339 -0.003478\nv -0.034672 0.036339 0.007948\nv -0.035661 0.035679 -0.003478\nv -0.035661 0.035679 0.007948\nv -0.036321 0.034690 -0.003478\nv -0.036321 0.034690 0.007948\nv -0.036553 0.033524 -0.003478\nv -0.036553 0.033524 0.007948\nv -0.036321 0.032358 -0.003478\nv -0.036321 0.032358 0.007948\nv -0.035661 0.031369 -0.003478\nv -0.035661 0.031369 0.007948\nv -0.034672 0.030709 -0.003478\nv -0.034672 0.030709 0.007948\nv -0.033506 0.030477 -0.003478\nv -0.033506 0.030477 0.007948\nv -0.032340 0.030709 -0.003478\nv -0.032340 0.030709 0.007948\nv -0.031351 0.031369 -0.003478\nv -0.031351 0.031369 0.007948\nv -0.030691 0.032358 -0.003478\nv -0.030691 0.032358 0.007948\nv -0.030459 0.033524 -0.003478\nv -0.030459 0.033524 0.007948\nv -0.030691 0.034690 -0.003478\nv -0.030691 0.034690 0.007948\nv -0.031351 0.035679 -0.003478\nv -0.031351 0.035679 0.007948\nv -0.032340 0.036339 -0.003478\nv -0.032340 0.036339 0.007948\nv 0.033454 -0.036483 -0.003478\nv 0.033454 -0.036483 0.007948\nv 0.034620 -0.036251 -0.003478\nv 0.034620 -0.036251 0.007948\nv 0.035609 -0.035591 -0.003478\nv 0.035609 -0.035591 0.007948\nv 0.036269 -0.034602 -0.003478\nv 0.036269 -0.034602 0.007948\nv 0.036501 -0.033436 -0.003478\nv 0.036501 -0.033436 0.007948\nv 0.036269 -0.032270 -0.003478\nv 0.036269 -0.032270 0.007948\nv 0.035609 -0.031281 -0.003478\nv 0.035609 -0.031281 0.007948\nv 0.034620 -0.030621 -0.003478\nv 0.034620 -0.030621 0.007948\nv 0.033454 -0.030389 -0.003478\nv 0.033454 -0.030389 0.007948\nv 0.032288 -0.030621 -0.003478\nv 0.032288 -0.030621 0.007948\nv 0.031299 -0.031281 -0.003478\nv 0.031299 -0.031281 0.007948\nv 0.030639 -0.032270 -0.003478\nv 0.030639 -0.032270 0.007948\nv 0.030407 -0.033436 -0.003478\nv 0.030407 -0.033436 0.007948\nv 0.030639 -0.034602 -0.003478\nv 0.030639 -0.034602 0.007948\nv 0.031299 -0.035591 -0.003478\nv 0.031299 -0.035591 0.007948\nv 0.032288 -0.036251 -0.003478\nv 0.032288 -0.036251 0.007948\nv -0.033506 -0.036483 -0.003478\nv -0.033506 -0.036483 0.007948\nv -0.034672 -0.036251 -0.003478\nv -0.034672 -0.036251 0.007948\nv -0.035661 -0.035591 -0.003478\nv -0.035661 -0.035591 0.007948\nv -0.036321 -0.034602 -0.003478\nv -0.036321 -0.034602 0.007948\nv -0.036553 -0.033436 -0.003478\nv -0.036553 -0.033436 0.007948\nv -0.036321 -0.032270 -0.003478\nv -0.036321 -0.032270 0.007948\nv -0.035661 -0.031281 -0.003478\nv -0.035661 -0.031281 0.007948\nv -0.034672 -0.030621 -0.003478\nv -0.034672 -0.030621 0.007948\nv -0.033506 -0.030389 -0.003478\nv -0.033506 -0.030389 0.007948\nv -0.032340 -0.030621 -0.003478\nv -0.032340 -0.030621 0.007948\nv -0.031351 -0.031281 -0.003478\nv -0.031351 -0.031281 0.007948\nv -0.030691 -0.032270 -0.003478\nv -0.030691 -0.032270 0.007948\nv -0.030459 -0.033436 -0.003478\nv -0.030459 -0.033436 0.007948\nv -0.030691 -0.034602 -0.003478\nv -0.030691 -0.034602 0.007948\nv -0.031351 -0.035591 -0.003478\nv -0.031351 -0.035591 0.007948\nv -0.032340 -0.036251 -0.003478\nv -0.032340 -0.036251 0.007948\nv 0.014546 0.003391 -0.002438\nv 0.002798 0.015054 -0.002438\nv 0.002798 0.015054 -0.005132\nv 0.014546 0.003391 -0.005132\nv 0.031170 0.029747 -0.002438\nv 0.031170 0.029747 -0.005132\nv 0.029034 0.031868 -0.005132\nv 0.029034 0.031868 -0.002438\nv 0.017885 0.021506 -0.002438\nv 0.017885 0.021506 -0.005132\nv 0.020889 0.018524 -0.002438\nv 0.020889 0.018524 -0.005132\nv 0.011469 0.017161 -0.005132\nv 0.016590 0.012077 -0.005132\nv 0.016590 0.012077 -0.002438\nv 0.011469 0.017161 -0.002438\nv -0.014598 0.003391 -0.002438\nv -0.014598 0.003391 -0.005132\nv -0.002850 0.015054 -0.005132\nv -0.002850 0.015054 -0.002438\nv -0.031222 0.029747 -0.002438\nv -0.029086 0.031868 -0.002438\nv -0.029086 0.031868 -0.005132\nv -0.031222 0.029747 -0.005132\nv -0.017937 0.021506 -0.002438\nv -0.017937 0.021506 -0.005132\nv -0.020941 0.018524 -0.002438\nv -0.020941 0.018524 -0.005132\nv -0.011521 0.017161 -0.005132\nv -0.016642 0.012077 -0.005132\nv -0.016642 0.012077 -0.002438\nv -0.011521 0.017161 -0.002438\nv 0.014546 -0.003303 -0.002438\nv 0.014546 -0.003303 -0.005132\nv 0.002798 -0.014966 -0.005132\nv 0.002798 -0.014966 -0.002438\nv 0.031170 -0.029659 -0.002438\nv 0.029034 -0.031780 -0.002438\nv 0.029034 -0.031780 -0.005132\nv 0.031170 -0.029659 -0.005132\nv 0.017885 -0.021418 -0.002438\nv 0.017885 -0.021418 -0.005132\nv 0.020889 -0.018436 -0.002438\nv 0.020889 -0.018436 -0.005132\nv 0.011469 -0.017073 -0.005132\nv 0.016590 -0.011989 -0.005132\nv 0.016590 -0.011989 -0.002438\nv 0.011469 -0.017073 -0.002438\nv -0.014598 -0.003303 -0.002438\nv -0.002850 -0.014966 -0.002438\nv -0.002850 -0.014966 -0.005132\nv -0.014598 -0.003303 -0.005132\nv -0.031222 -0.029659 -0.002438\nv -0.031222 -0.029659 -0.005132\nv -0.029086 -0.031780 -0.005132\nv -0.029086 -0.031780 -0.002438\nv -0.017937 -0.021418 -0.002438\nv -0.017937 -0.021418 -0.005132\nv -0.020941 -0.018436 -0.002438\nv -0.020941 -0.018436 -0.005132\nv -0.011521 -0.017073 -0.005132\nv -0.016642 -0.011989 -0.005132\nv -0.016642 -0.011989 -0.002438\nv -0.011521 -0.017073 -0.002438\nv -0.016779 0.005194 -0.002438\nv -0.014011 0.007300 -0.002438\nv -0.008688 0.011145 -0.002438\nv -0.003371 0.014989 -0.002438\nv -0.003371 0.014989 -0.005132\nv -0.016779 0.005194 -0.005132\nv 0.006736 0.011145 -0.002438\nv 0.006736 0.011145 -0.005132\nv 0.002864 0.014989 -0.005132\nv 0.002864 0.014989 -0.002438\nv 0.019682 0.001711 -0.002438\nv 0.019682 0.000044 -0.002438\nv 0.019682 0.000044 -0.005132\nv 0.019682 0.001711 -0.005132\nv -0.016779 0.000044 -0.002438\nv -0.016779 0.000044 -0.005132\nv -0.016779 0.001477 -0.002438\nv -0.016779 0.001477 -0.005132\nv 0.014481 0.003456 -0.002438\nv 0.014481 0.003456 -0.005132\nv 0.010608 0.007300 -0.005132\nv 0.010608 0.007300 -0.002438\nv -0.008688 -0.011057 -0.002438\nv -0.014011 -0.007212 -0.002438\nv -0.016779 -0.005106 -0.002438\nv -0.016779 -0.005106 -0.005132\nv -0.003371 -0.014901 -0.005132\nv -0.003371 -0.014901 -0.002438\nv 0.006736 -0.011057 -0.002438\nv 0.002864 -0.014901 -0.002438\nv 0.002864 -0.014901 -0.005132\nv 0.006736 -0.011057 -0.005132\nv 0.019682 -0.001623 -0.002438\nv 0.019682 -0.001623 -0.005132\nv -0.016779 -0.001389 -0.002438\nv -0.016779 -0.001389 -0.005132\nv 0.014481 -0.003368 -0.002438\nv 0.010608 -0.007212 -0.002438\nv 0.010608 -0.007212 -0.005132\nv 0.014481 -0.003368 -0.005132\nv -0.010826 0.010844 -0.002369\nv -0.010826 0.013004 -0.002369\nv -0.010826 0.013004 -0.000209\nv -0.010826 0.010844 -0.000209\nv 0.010774 0.013004 -0.002369\nv 0.010774 0.013004 -0.000209\nv 0.010774 0.010844 -0.002369\nv 0.010774 0.010844 -0.000209\nv -0.010826 -0.010756 -0.002369\nv -0.010826 -0.010756 -0.000209\nv -0.010826 -0.012916 -0.000209\nv -0.010826 -0.012916 -0.002369\nv 0.010774 -0.012916 -0.000209\nv 0.010774 -0.012916 -0.002369\nv 0.010774 -0.010756 -0.000209\nv 0.010774 -0.010756 -0.002369\nv -0.016779 0.005194 -0.002438\nv -0.014011 0.007300 -0.002438\nv -0.008688 0.011145 -0.002438\nv -0.016779 0.005194 -0.005132\nv 0.006736 0.011145 -0.002438\nv 0.006736 0.011145 -0.005132\nv 0.019682 0.001711 -0.002438\nv 0.019682 0.000044 -0.002438\nv 0.019682 0.000044 -0.005132\nv 0.019682 0.001711 -0.005132\nv -0.016779 0.000044 -0.002438\nv -0.016779 0.000044 -0.005132\nv -0.016779 0.001477 -0.002438\nv -0.016779 0.001477 -0.005132\nv 0.014481 0.003456 -0.002438\nv 0.014481 0.003456 -0.005132\nv 0.010608 0.007300 -0.005132\nv 0.010608 0.007300 -0.002438\nv -0.008688 -0.011057 -0.002438\nv -0.014011 -0.007212 -0.002438\nv -0.016779 -0.005106 -0.002438\nv -0.016779 -0.005106 -0.005132\nv -0.003371 -0.014901 -0.005132\nv -0.003371 -0.014901 -0.002438\nv 0.006736 -0.011057 -0.002438\nv 0.002864 -0.014901 -0.002438\nv 0.002864 -0.014901 -0.005132\nv 0.006736 -0.011057 -0.005132\nv 0.019682 -0.001623 -0.002438\nv 0.019682 -0.001623 -0.005132\nv -0.016779 -0.001389 -0.002438\nv -0.016779 -0.001389 -0.005132\nv 0.014481 -0.003368 -0.002438\nv 0.010608 -0.007212 -0.002438\nv 0.010608 -0.007212 -0.005132\nv 0.014481 -0.003368 -0.005132\nv -0.010826 0.010844 -0.002369\nv -0.010826 0.010844 -0.000209\nv -0.010826 0.013004 -0.000209\nv 0.010774 0.013004 -0.000209\nv 0.010774 0.010844 -0.000209\nv 0.010774 0.010844 -0.002369\nv -0.010826 -0.010756 -0.002369\nv -0.010826 -0.012916 -0.002369\nv -0.010826 -0.012916 -0.000209\nv -0.010826 -0.010756 -0.000209\nv 0.010774 -0.012916 -0.002369\nv 0.010774 -0.012916 -0.000209\nv 0.010774 -0.010756 -0.002369\nv 0.010774 -0.010756 -0.000209\nv 0.011768 -0.009676 -0.000457\nv 0.011768 -0.009676 0.003687\nv -0.011820 -0.009676 0.003687\nv -0.011820 -0.009676 -0.000457\nv 0.015094 0.007626 -0.000457\nv 0.015094 0.007626 0.003687\nv 0.015094 -0.007538 0.003687\nv 0.015094 -0.007538 -0.000457\nv 0.011768 0.007626 0.004271\nv -0.011820 0.007626 0.004271\nv -0.011820 -0.007538 0.004271\nv 0.011768 -0.007538 0.004271\nv -0.015146 -0.007538 -0.000457\nv -0.015146 -0.007538 0.003687\nv -0.015146 0.007626 0.003687\nv -0.015146 0.007626 -0.000457\nv -0.011820 0.009764 -0.000457\nv -0.011820 0.009764 0.003687\nv 0.011768 0.009764 0.003687\nv 0.011768 0.009764 -0.000457\nv -0.011820 -0.007538 -0.001041\nv -0.011820 0.007626 -0.001041\nv 0.011768 -0.007538 -0.001041\nv 0.011768 0.007626 -0.001041\nv -0.009548 0.012194 0.015260\nv -0.010088 0.012194 0.015260\nv -0.010088 0.011654 0.015260\nv -0.009548 0.011654 0.015260\nv -0.009548 0.011654 -0.009798\nv -0.010088 0.011654 -0.009798\nv -0.010088 0.012194 -0.009798\nv -0.009548 0.012194 -0.009798\nv -0.007388 0.012194 0.015260\nv -0.007928 0.012194 0.015260\nv -0.007928 0.011654 0.015260\nv -0.007388 0.011654 0.015260\nv -0.007388 0.011654 -0.009798\nv -0.007928 0.011654 -0.009798\nv -0.007928 0.012194 -0.009798\nv -0.007388 0.012194 -0.009798\nv -0.005228 0.012194 0.015260\nv -0.005768 0.012194 0.015260\nv -0.005768 0.011654 0.015260\nv -0.005228 0.011654 0.015260\nv -0.005228 0.011654 -0.009798\nv -0.005768 0.011654 -0.009798\nv -0.005768 0.012194 -0.009798\nv -0.005228 0.012194 -0.009798\nv -0.003068 0.012194 0.015260\nv -0.003608 0.012194 0.015260\nv -0.003608 0.011654 0.015260\nv -0.003068 0.011654 0.015260\nv -0.003068 0.011654 -0.009798\nv -0.003608 0.011654 -0.009798\nv -0.003608 0.012194 -0.009798\nv -0.003068 0.012194 -0.009798\nv -0.000908 0.012194 0.015260\nv -0.001448 0.012194 0.015260\nv -0.001448 0.011654 0.015260\nv -0.000908 0.011654 0.015260\nv -0.000908 0.011654 -0.009798\nv -0.001448 0.011654 -0.009798\nv -0.001448 0.012194 -0.009798\nv -0.000908 0.012194 -0.009798\nv 0.001252 0.012194 0.015260\nv 0.000712 0.012194 0.015260\nv 0.000712 0.011654 0.015260\nv 0.001252 0.011654 0.015260\nv 0.001252 0.011654 -0.009798\nv 0.000712 0.011654 -0.009798\nv 0.000712 0.012194 -0.009798\nv 0.001252 0.012194 -0.009798\nv 0.003412 0.012194 0.015260\nv 0.002872 0.012194 0.015260\nv 0.002872 0.011654 0.015260\nv 0.003412 0.011654 0.015260\nv 0.003412 0.011654 -0.009798\nv 0.002872 0.011654 -0.009798\nv 0.002872 0.012194 -0.009798\nv 0.003412 0.012194 -0.009798\nv 0.005572 0.012194 0.015260\nv 0.005032 0.012194 0.015260\nv 0.005032 0.011654 0.015260\nv 0.005572 0.011654 0.015260\nv 0.005572 0.011654 -0.009798\nv 0.005032 0.011654 -0.009798\nv 0.005032 0.012194 -0.009798\nv 0.005572 0.012194 -0.009798\nv 0.007732 0.012194 0.015260\nv 0.007192 0.012194 0.015260\nv 0.007192 0.011654 0.015260\nv 0.007732 0.011654 0.015260\nv 0.007732 0.011654 -0.009798\nv 0.007192 0.011654 -0.009798\nv 0.007192 0.012194 -0.009798\nv 0.007732 0.012194 -0.009798\nv 0.009892 0.012194 0.015260\nv 0.009352 0.012194 0.015260\nv 0.009352 0.011654 0.015260\nv 0.009892 0.011654 0.015260\nv 0.009892 0.011654 -0.009798\nv 0.009352 0.011654 -0.009798\nv 0.009352 0.012194 -0.009798\nv 0.009892 0.012194 -0.009798\nv -0.010826 0.010844 -0.006257\nv -0.010826 0.010844 -0.003473\nv -0.010826 0.013004 -0.003473\nv -0.010826 0.013004 -0.006257\nv 0.010774 0.013004 -0.003473\nv 0.010774 0.013004 -0.006257\nv 0.010774 0.010844 -0.003473\nv 0.010774 0.010844 -0.006257\nv -0.009548 -0.012106 0.015260\nv -0.010088 -0.012106 0.015260\nv -0.010088 -0.011566 0.015260\nv -0.009548 -0.011566 0.015260\nv -0.009548 -0.011566 -0.009798\nv -0.010088 -0.011566 -0.009798\nv -0.010088 -0.012106 -0.009798\nv -0.009548 -0.012106 -0.009798\nv -0.007388 -0.012106 0.015260\nv -0.007928 -0.012106 0.015260\nv -0.007928 -0.011566 0.015260\nv -0.007388 -0.011566 0.015260\nv -0.007388 -0.011566 -0.009798\nv -0.007928 -0.011566 -0.009798\nv -0.007928 -0.012106 -0.009798\nv -0.007388 -0.012106 -0.009798\nv -0.005228 -0.012106 0.015260\nv -0.005768 -0.012106 0.015260\nv -0.005768 -0.011566 0.015260\nv -0.005228 -0.011566 0.015260\nv -0.005228 -0.011566 -0.009798\nv -0.005768 -0.011566 -0.009798\nv -0.005768 -0.012106 -0.009798\nv -0.005228 -0.012106 -0.009798\nv -0.003068 -0.012106 0.015260\nv -0.003608 -0.012106 0.015260\nv -0.003608 -0.011566 0.015260\nv -0.003068 -0.011566 0.015260\nv -0.003068 -0.011566 -0.009798\nv -0.003608 -0.011566 -0.009798\nv -0.003608 -0.012106 -0.009798\nv -0.003068 -0.012106 -0.009798\nv -0.000908 -0.012106 0.015260\nv -0.001448 -0.012106 0.015260\nv -0.001448 -0.011566 0.015260\nv -0.000908 -0.011566 0.015260\nv -0.000908 -0.011566 -0.009798\nv -0.001448 -0.011566 -0.009798\nv -0.001448 -0.012106 -0.009798\nv -0.000908 -0.012106 -0.009798\nv 0.001252 -0.012106 0.015260\nv 0.000712 -0.012106 0.015260\nv 0.000712 -0.011566 0.015260\nv 0.001252 -0.011566 0.015260\nv 0.001252 -0.011566 -0.009798\nv 0.000712 -0.011566 -0.009798\nv 0.000712 -0.012106 -0.009798\nv 0.001252 -0.012106 -0.009798\nv 0.003412 -0.012106 0.015260\nv 0.002872 -0.012106 0.015260\nv 0.002872 -0.011566 0.015260\nv 0.003412 -0.011566 0.015260\nv 0.003412 -0.011566 -0.009798\nv 0.002872 -0.011566 -0.009798\nv 0.002872 -0.012106 -0.009798\nv 0.003412 -0.012106 -0.009798\nv 0.005572 -0.012106 0.015260\nv 0.005032 -0.012106 0.015260\nv 0.005032 -0.011566 0.015260\nv 0.005572 -0.011566 0.015260\nv 0.005572 -0.011566 -0.009798\nv 0.005032 -0.011566 -0.009798\nv 0.005032 -0.012106 -0.009798\nv 0.005572 -0.012106 -0.009798\nv 0.007732 -0.012106 0.015260\nv 0.007192 -0.012106 0.015260\nv 0.007192 -0.011566 0.015260\nv 0.007732 -0.011566 0.015260\nv 0.007732 -0.011566 -0.009798\nv 0.007192 -0.011566 -0.009798\nv 0.007192 -0.012106 -0.009798\nv 0.007732 -0.012106 -0.009798\nv 0.009892 -0.012106 0.015260\nv 0.009352 -0.012106 0.015260\nv 0.009352 -0.011566 0.015260\nv 0.009892 -0.011566 0.015260\nv 0.009892 -0.011566 -0.009798\nv 0.009352 -0.011566 -0.009798\nv 0.009352 -0.012106 -0.009798\nv 0.009892 -0.012106 -0.009798\nv -0.010826 -0.010756 -0.006257\nv -0.010826 -0.010756 -0.003473\nv -0.010826 -0.012916 -0.003473\nv -0.010826 -0.012916 -0.006257\nv 0.010774 -0.012916 -0.003473\nv 0.010774 -0.012916 -0.006257\nv 0.010774 -0.010756 -0.003473\nv 0.010774 -0.010756 -0.006257\nv -0.010826 0.010844 0.007555\nv -0.010826 0.010844 0.009715\nv -0.010826 0.013004 0.009715\nv -0.010826 0.013004 0.007555\nv 0.010774 0.013004 0.009715\nv 0.010774 0.013004 0.007555\nv 0.010774 0.010844 0.009715\nv 0.010774 0.010844 0.007555\nv -0.010826 -0.010756 0.007555\nv -0.010826 -0.012916 0.007555\nv -0.010826 -0.012916 0.009715\nv -0.010826 -0.010756 0.009715\nv 0.010774 -0.012916 0.007555\nv 0.010774 -0.012916 0.009715\nv 0.010774 -0.010756 0.007555\nv 0.010774 -0.010756 0.009715\nv -0.010826 -0.015076 0.006475\nv -0.010826 -0.015076 0.007555\nv -0.010826 0.015164 0.007555\nv -0.010826 0.015164 0.006475\nv 0.010774 0.015164 0.007555\nv 0.010774 0.015164 0.006475\nv 0.010774 -0.015076 0.007555\nv 0.010774 -0.015076 0.006475\nv -0.001210 0.009764 0.006475\nv 0.001158 0.009764 0.006475\nv 0.001158 -0.009676 0.006475\nv -0.001210 -0.009676 0.006475\nv -0.008770 0.009764 0.006475\nv -0.008770 -0.009676 0.006475\nv 0.008718 -0.009676 0.006475\nv 0.008718 0.009764 0.006475\nv -0.001210 -0.009676 0.007555\nv -0.008770 -0.009676 0.007555\nv -0.008770 0.009764 0.007555\nv -0.001210 0.009764 0.007555\nv 0.001158 0.009764 0.007555\nv 0.008718 0.009764 0.007555\nv 0.008718 -0.009676 0.007555\nv 0.001158 -0.009676 0.007555\nvn -0.5388 -0.5161 -0.6658\nvn -0.6625 -0.7469 0.0569\nvn -0.9317 -0.3631 -0.0000\nvn -0.6953 -0.2709 -0.6657\nvn -0.6833 0.3000 -0.6657\nvn -0.6917 0.7222 -0.0000\nvn -0.5165 0.5387 -0.6656\nvn -0.3631 0.9317 -0.0000\nvn -0.2710 0.6953 -0.6657\nvn 0.3004 0.6831 -0.6657\nvn 0.4026 0.9154 -0.0000\nvn 0.7222 0.6917 -0.0000\nvn 0.5388 0.5164 -0.6656\nvn 0.5388 0.5161 0.6658\nvn 0.6953 0.2710 0.6657\nvn 0.5165 -0.5387 -0.6656\nvn 0.5161 -0.5388 0.6658\nvn 0.2710 -0.6953 0.6657\nvn -0.5388 -0.5161 0.6658\nvn -0.3001 -0.6832 0.6657\nvn -0.0158 -0.7461 0.6657\nvn 0.6831 -0.3004 0.6657\nvn 0.7461 -0.0158 0.6657\nvn -0.7461 0.0158 0.6657\nvn 0.0158 0.7461 0.6657\nvn -0.5161 0.5388 0.6658\nvn -0.7461 0.0158 -0.6657\nvn 0.6953 0.2710 -0.6657\nvn 0.6833 -0.3000 -0.6657\nvn 0.2709 -0.6953 -0.6657\nvn -0.3004 -0.6831 -0.6657\nvn -0.9998 0.0212 -0.0000\nvn -0.6953 -0.2709 0.6657\nvn 0.0212 0.9998 -0.0000\nvn -0.2710 0.6953 0.6657\nvn -0.9154 0.4026 -0.0000\nvn -0.6833 0.3000 0.6657\nvn 0.3000 0.6833 0.6657\nvn -0.8237 -0.2703 0.4985\nvn 0.5644 -0.3333 0.7552\nvn 0.7117 -0.0450 0.7011\nvn -0.6780 -0.4304 0.5958\nvn 0.6790 0.2941 0.6727\nvn -0.7968 0.2171 0.5639\nvn -0.6335 0.3738 0.6774\nvn 0.2216 -0.7156 0.6624\nvn -0.5556 0.6002 0.5753\nvn 0.5329 0.5498 0.6433\nvn -0.3894 0.4333 0.8128\nvn -0.0390 0.4575 0.8883\nvn -0.5696 -0.7784 0.2639\nvn -0.1232 -0.9008 0.4164\nvn -0.0997 -0.6676 0.7378\nvn 0.7671 -0.6019 0.2219\nvn 0.7551 0.6168 0.2220\nvn 0.5696 0.7784 0.2639\nvn 0.8691 0.0185 0.4942\nvn 0.7971 -0.2171 0.5635\nvn -0.3800 0.5660 0.7316\nvn -0.5644 0.3333 0.7552\nvn 0.8237 0.2703 0.4985\nvn 0.6335 -0.3738 0.6774\nvn -0.3212 0.8037 0.5009\nvn 0.6780 0.4304 0.5959\nvn -0.6789 -0.2941 0.6727\nvn 0.3894 -0.4335 0.8127\nvn 0.0061 0.9864 0.1645\nvn 0.4259 0.7233 -0.5436\nvn -0.3080 -0.3599 -0.8807\nvn -0.4508 0.6744 -0.5848\nvn -0.2433 0.6578 -0.7128\nvn 0.7628 -0.2967 -0.5745\nvn 0.7022 -0.4123 -0.5804\nvn -0.0814 0.7683 -0.6349\nvn -0.4060 0.4475 -0.7969\nvn 0.7714 -0.0710 -0.6324\nvn -0.5337 0.0213 -0.8454\nvn 0.7129 0.3133 -0.6274\nvn 0.6276 -0.4678 -0.6222\nvn -0.5830 0.6371 -0.5043\nvn 0.4706 0.5030 -0.7249\nvn 0.2558 0.8370 -0.4838\nvn -0.0274 -0.4166 -0.9087\nvn -0.4264 -0.7231 -0.5434\nvn -0.1447 0.1847 -0.9721\nvn 0.2250 0.2569 -0.9399\nvn 0.4508 -0.6744 -0.5848\nvn 0.2433 -0.6575 -0.7131\nvn -0.7628 0.2967 -0.5745\nvn -0.7022 0.4123 -0.5804\nvn 0.4060 -0.4475 -0.7969\nvn -0.7714 0.0710 -0.6324\nvn -0.3405 -0.6842 -0.6449\nvn -0.3125 0.6247 -0.7156\nvn -0.2071 -0.7086 -0.6746\nvn -0.6137 0.4766 -0.6294\nvn -0.7517 0.4906 0.4407\nvn 0.3800 -0.5660 0.7316\nvn -0.6958 -0.5912 0.4079\nvn 0.5337 -0.0212 -0.8454\nvn 0.0810 -0.7684 -0.6348\nvn 0.7672 -0.6018 0.2219\nvn -0.7118 0.0450 0.7010\nvn -0.5329 -0.5498 0.6433\nvn -0.7128 -0.3133 -0.6275\nvn -0.4706 -0.5030 -0.7250\nvn 0.0158 0.7461 -0.6657\nvn 0.7461 -0.0158 -0.6657\nvn -0.0158 -0.7461 -0.6657\nvn -0.8691 -0.0185 0.4942\nvn 0.0846 0.8289 -0.5530\nvn 0.3125 -0.6247 -0.7156\nvn 0.5827 -0.6372 -0.5044\nvn 0.5388 -0.5161 -0.6658\nvn 0.9317 -0.3631 -0.0000\nvn 0.6625 -0.7469 0.0569\nvn 0.6953 -0.2709 -0.6657\nvn 0.6833 0.3000 -0.6657\nvn 0.5161 0.5388 -0.6658\nvn 0.6917 0.7222 -0.0000\nvn 0.2709 0.6953 -0.6657\nvn 0.3631 0.9317 -0.0000\nvn -0.2998 0.6833 -0.6657\nvn -0.7222 0.6917 -0.0000\nvn -0.4026 0.9154 -0.0000\nvn -0.5388 0.5161 -0.6658\nvn -0.6953 0.2710 0.6657\nvn -0.5388 0.5161 0.6658\nvn -0.5161 -0.5388 -0.6658\nvn -0.2710 -0.6953 0.6657\nvn -0.5161 -0.5388 0.6658\nvn 0.5388 -0.5161 0.6658\nvn 0.0158 -0.7461 0.6657\nvn 0.3004 -0.6831 0.6657\nvn -0.7461 -0.0158 0.6657\nvn -0.6833 -0.3000 0.6657\nvn 0.7461 0.0158 0.6657\nvn -0.0158 0.7461 0.6657\nvn 0.5161 0.5388 0.6658\nvn 0.7461 0.0158 -0.6657\nvn -0.6953 0.2710 -0.6657\nvn -0.6831 -0.3004 -0.6657\nvn -0.2709 -0.6953 -0.6657\nvn 0.3004 -0.6831 -0.6657\nvn 0.9998 0.0212 -0.0000\nvn 0.6953 -0.2710 0.6657\nvn -0.0212 0.9998 -0.0000\nvn 0.2709 0.6953 0.6657\nvn 0.9154 0.4026 -0.0000\nvn 0.6832 0.3001 0.6657\nvn -0.3004 0.6831 0.6657\nvn 0.8235 -0.2706 0.4985\nvn -0.7119 -0.0449 0.7009\nvn -0.5644 -0.3333 0.7552\nvn 0.6780 -0.4304 0.5958\nvn -0.6790 0.2941 0.6727\nvn 0.7968 0.2171 0.5639\nvn -0.2216 -0.7156 0.6624\nvn 0.6335 0.3738 0.6774\nvn 0.5553 0.6005 0.5754\nvn -0.5329 0.5498 0.6433\nvn 0.3894 0.4335 0.8127\nvn 0.5696 -0.7784 0.2639\nvn 0.0390 0.4575 0.8883\nvn 0.1232 -0.9008 0.4164\nvn 0.0997 -0.6676 0.7378\nvn -0.7551 0.6168 0.2220\nvn -0.7671 -0.6019 0.2219\nvn -0.5696 0.7784 0.2639\nvn -0.8691 0.0185 0.4942\nvn 0.3800 0.5660 0.7316\nvn -0.7968 -0.2171 0.5639\nvn 0.5644 0.3333 0.7552\nvn -0.8235 0.2706 0.4985\nvn 0.3212 0.8037 0.5009\nvn -0.6335 -0.3738 0.6774\nvn 0.6625 -0.7469 0.0570\nvn 0.6789 -0.2941 0.6727\nvn -0.6779 0.4304 0.5959\nvn -0.0061 0.9864 0.1645\nvn -0.3894 -0.4334 0.8127\nvn -0.4259 0.7233 -0.5435\nvn 0.4508 0.6744 -0.5848\nvn 0.3074 -0.3595 -0.8810\nvn 0.2433 0.6575 -0.7131\nvn -0.7023 -0.4123 -0.5803\nvn -0.7629 -0.2970 -0.5742\nvn 0.0814 0.7683 -0.6349\nvn 0.4058 0.4477 -0.7968\nvn -0.7714 -0.0710 -0.6324\nvn 0.5337 0.0212 -0.8454\nvn -0.7129 0.3133 -0.6274\nvn -0.6276 -0.4678 -0.6222\nvn 0.5827 0.6372 -0.5044\nvn -0.4706 0.5030 -0.7249\nvn -0.2558 0.8370 -0.4837\nvn 0.0275 -0.4167 -0.9086\nvn 0.4264 -0.7231 -0.5434\nvn -0.2250 0.2569 -0.9399\nvn 0.1447 0.1847 -0.9721\nvn -0.4506 -0.6745 -0.5848\nvn -0.2433 -0.6578 -0.7128\nvn 0.7022 0.4123 -0.5804\nvn 0.7628 0.2967 -0.5745\nvn -0.4058 -0.4477 -0.7968\nvn 0.7714 0.0710 -0.6324\nvn 0.3405 -0.6842 -0.6449\nvn 0.3125 0.6247 -0.7156\nvn 0.2071 -0.7086 -0.6746\nvn 0.6137 0.4766 -0.6294\nvn 0.7518 0.4906 0.4405\nvn -0.3800 -0.5660 0.7316\nvn 0.6960 -0.5913 0.4074\nvn -0.5337 -0.0212 -0.8454\nvn -0.0814 -0.7683 -0.6349\nvn -0.7672 -0.6018 0.2219\nvn 0.7117 0.0450 0.7011\nvn 0.5329 -0.5498 0.6433\nvn 0.4706 -0.5030 -0.7249\nvn 0.7129 -0.3133 -0.6274\nvn -0.0158 0.7461 -0.6657\nvn -0.7461 -0.0158 -0.6657\nvn 0.0158 -0.7461 -0.6657\nvn 0.8691 -0.0185 0.4942\nvn -0.0846 0.8289 -0.5530\nvn -0.3125 -0.6247 -0.7156\nvn -0.5826 -0.6372 -0.5045\nvn -0.9317 0.3631 -0.0000\nvn -0.6625 0.7469 0.0569\nvn -0.6833 -0.3000 -0.6657\nvn -0.6917 -0.7222 -0.0000\nvn -0.2710 -0.6953 -0.6657\nvn -0.3631 -0.9317 -0.0000\nvn 0.3001 -0.6832 -0.6657\nvn 0.7222 -0.6917 -0.0000\nvn 0.4022 -0.9155 -0.0000\nvn 0.2710 0.6953 0.6657\nvn 0.6831 0.3004 0.6657\nvn 0.6953 -0.2710 -0.6657\nvn -0.3000 0.6833 -0.6657\nvn -0.9998 -0.0212 -0.0000\nvn -0.6953 0.2709 0.6657\nvn 0.0212 -0.9998 -0.0000\nvn -0.9154 -0.4026 -0.0000\nvn 0.3001 -0.6832 0.6657\nvn 0.7114 0.0451 0.7014\nvn -0.6780 0.4304 0.5958\nvn 0.6791 -0.2944 0.6724\nvn 0.2216 0.7156 0.6624\nvn -0.5553 -0.6005 0.5754\nvn -0.3894 -0.4335 0.8127\nvn -0.0390 -0.4575 0.8883\nvn -0.1232 0.9008 0.4164\nvn -0.0997 0.6676 0.7378\nvn 0.7551 -0.6168 0.2220\nvn 0.7672 0.6019 0.2219\nvn -0.3212 -0.8037 0.5009\nvn -0.6625 0.7469 0.0568\nvn -0.6789 0.2941 0.6727\nvn 0.6780 -0.4304 0.5959\nvn 0.0061 -0.9864 0.1645\nvn 0.4263 -0.7232 -0.5435\nvn -0.4503 -0.6746 -0.5849\nvn -0.3074 0.3595 -0.8810\nvn 0.7023 0.4123 -0.5803\nvn -0.4060 -0.4475 -0.7969\nvn 0.7715 0.0715 -0.6321\nvn 0.7126 -0.3132 -0.6278\nvn 0.6276 0.4678 -0.6222\nvn -0.5827 -0.6372 -0.5044\nvn 0.4706 -0.5030 -0.7250\nvn 0.2558 -0.8370 -0.4837\nvn -0.0274 0.4166 -0.9087\nvn -0.4259 0.7233 -0.5436\nvn 0.2250 -0.2569 -0.9399\nvn -0.1447 -0.1847 -0.9721\nvn 0.2433 0.6578 -0.7128\nvn -0.7026 -0.4125 -0.5799\nvn -0.7628 -0.2967 -0.5745\nvn 0.4060 0.4475 -0.7969\nvn -0.7714 -0.0711 -0.6323\nvn -0.3405 0.6842 -0.6449\nvn -0.2071 0.7086 -0.6746\nvn -0.6137 -0.4766 -0.6294\nvn -0.7518 -0.4906 0.4405\nvn -0.6960 0.5913 0.4074\nvn 0.0810 0.7684 -0.6348\nvn 0.7672 0.6018 0.2219\nvn -0.7117 -0.0450 0.7011\nvn -0.0163 0.7459 -0.6658\nvn 0.0846 -0.8289 -0.5530\nvn 0.3123 0.6251 -0.7153\nvn 0.5826 0.6372 -0.5045\nvn 0.5388 0.5161 -0.6658\nvn 0.6625 0.7469 0.0569\nvn 0.9317 0.3631 -0.0000\nvn 0.6953 0.2709 -0.6657\nvn 0.6917 -0.7222 -0.0000\nvn 0.5164 -0.5388 -0.6656\nvn 0.3631 -0.9317 -0.0000\nvn -0.3000 -0.6833 -0.6657\nvn -0.4026 -0.9154 -0.0000\nvn -0.7222 -0.6917 -0.0000\nvn -0.6953 -0.2710 0.6657\nvn -0.5161 0.5388 -0.6658\nvn 0.2999 0.6833 0.6657\nvn -0.6953 -0.2710 -0.6657\nvn -0.2709 0.6953 -0.6657\nvn 0.2998 0.6833 -0.6657\nvn 0.9998 -0.0212 -0.0000\nvn -0.0212 -0.9998 -0.0000\nvn 0.9154 -0.4026 -0.0000\nvn 0.6832 -0.3001 0.6657\nvn -0.3004 -0.6831 0.6657\nvn 0.8237 0.2702 0.4985\nvn -0.7114 0.0451 0.7014\nvn 0.7968 -0.2171 0.5639\nvn -0.2216 0.7156 0.6624\nvn 0.5556 -0.6004 0.5752\nvn 0.0390 -0.4575 0.8883\nvn 0.1232 0.9008 0.4164\nvn 0.0997 0.6676 0.7378\nvn -0.7671 0.6019 0.2219\nvn -0.7551 -0.6168 0.2220\nvn -0.8236 -0.2703 0.4985\nvn 0.3212 -0.8037 0.5009\nvn -0.6779 -0.4304 0.5959\nvn 0.6789 0.2941 0.6727\nvn -0.0061 -0.9864 0.1645\nvn -0.4262 -0.7232 -0.5435\nvn 0.3078 0.3597 -0.8808\nvn -0.7023 0.4123 -0.5803\nvn 0.0814 -0.7683 -0.6349\nvn 0.4058 -0.4477 -0.7968\nvn 0.5337 -0.0213 -0.8454\nvn -0.6276 0.4678 -0.6222\nvn 0.5826 -0.6373 -0.5044\nvn -0.2558 -0.8370 -0.4837\nvn 0.0275 0.4166 -0.9087\nvn 0.4264 0.7231 -0.5434\nvn 0.1447 -0.1847 -0.9721\nvn -0.2250 -0.2569 -0.9399\nvn 0.7026 -0.4125 -0.5799\nvn -0.4058 0.4477 -0.7968\nvn 0.3405 0.6842 -0.6449\nvn 0.2071 0.7086 -0.6746\nvn 0.6137 -0.4766 -0.6294\nvn 0.7517 -0.4906 0.4407\nvn -0.3801 0.5660 0.7316\nvn 0.6959 0.5913 0.4076\nvn -0.5336 0.0213 -0.8454\nvn -0.7672 0.6018 0.2219\nvn 0.7118 -0.0450 0.7010\nvn 0.4706 0.5030 -0.7250\nvn -0.0846 -0.8289 -0.5530\nvn -0.5827 0.6372 -0.5044\nvn -0.0081 -1.0000 -0.0001\nvn -0.0082 -1.0000 -0.0000\nvn 0.0082 1.0000 -0.0000\nvn 0.0083 1.0000 -0.0000\nvn 1.0000 -0.0081 -0.0000\nvn -0.0081 -1.0000 -0.0000\nvn -0.0079 -1.0000 -0.0000\nvn 0.0079 1.0000 -0.0000\nvn 0.0081 1.0000 -0.0000\nvn -1.0000 0.0082 -0.0000\nvn -1.0000 0.0080 -0.0000\nvn -0.0000 -0.0000 -1.0000\nvn 0.7071 -0.0055 -0.7071\nvn 1.0000 -0.0080 -0.0000\nvn 0.7071 -0.0057 0.7071\nvn 0.7071 -0.0055 0.7071\nvn -0.0000 -0.0000 1.0000\nvn 0.9999 -0.0164 -0.0000\nvn -0.9999 0.0164 -0.0000\nvn -0.9999 0.0162 -0.0000\nvn 0.0163 0.9999 -0.0000\nvn 0.9999 -0.0162 -0.0000\nvn 0.9999 -0.0162 -0.0001\nvn -0.9999 0.0165 -0.0000\nvn -0.9999 0.0163 -0.0000\nvn -0.0163 -0.9999 -0.0000\nvn 0.0118 0.7070 -0.7071\nvn 0.0119 0.7071 -0.7071\nvn 0.0160 0.9999 -0.0000\nvn 0.0119 0.7070 0.7071\nvn 0.0117 0.7070 0.7071\nvn -0.7070 -0.7072 0.0001\nvn -0.7071 -0.7071 -0.0000\nvn -0.7071 0.7071 -0.0000\nvn 0.7071 -0.7071 -0.0000\nvn 0.7071 0.7071 -0.0000\nvn 0.7072 -0.7070 -0.0000\nvn 0.7070 -0.7072 -0.0000\nvn -0.7070 0.7072 -0.0000\nvn -0.7072 0.7070 -0.0000\nvn -0.7071 -0.7071 0.0001\nvn -0.7072 -0.7070 -0.0000\nvn 0.7073 -0.7070 -0.0000\nvn -0.7070 0.7073 -0.0000\nvn -0.7073 0.7069 -0.0000\nvn 0.7069 -0.7073 -0.0000\nvn -0.4004 0.4004 0.8242\nvn -0.4003 0.4003 0.8243\nvn 0.4005 -0.4005 0.8242\nvn 0.4004 -0.4004 0.8243\nvn -0.4004 0.4004 0.8243\nvn -0.4005 0.4005 0.8242\nvn -0.4002 0.4004 0.8243\nvn -0.4004 0.4002 0.8243\nvn 0.4004 -0.4004 0.8242\nvn 0.4005 -0.4006 0.8241\nvn 0.4007 -0.4007 0.8240\nvn 0.4003 -0.4003 0.8243\nvn 0.4007 -0.4006 0.8240\nvn 0.1952 0.9808 -0.0000\nvn 0.1951 0.9808 -0.0000\nvn 0.1950 0.9808 -0.0000\nvn 0.1951 0.9808 -0.0001\nvn 0.5552 0.8317 -0.0000\nvn 0.5558 0.8313 -0.0000\nvn 0.8311 0.5561 -0.0000\nvn 0.8315 0.5555 -0.0000\nvn 0.9808 0.1951 -0.0000\nvn 0.9807 0.1953 -0.0000\nvn 0.9808 0.1950 -0.0001\nvn 0.9808 0.1950 0.0001\nvn -0.9175 0.3977 -0.0000\nvn -0.6954 0.7186 -0.0000\nvn -0.3672 0.9301 -0.0000\nvn 0.0164 0.9999 -0.0000\nvn 0.3977 0.9175 -0.0000\nvn 0.3976 0.9176 -0.0000\nvn 0.7188 0.6953 -0.0000\nvn 0.7186 0.6954 -0.0000\nvn 0.9301 0.3672 -0.0000\nvn 0.9999 -0.0166 -0.0000\nvn 0.9175 -0.3977 -0.0000\nvn 0.9176 -0.3975 -0.0000\nvn 0.6954 -0.7186 -0.0000\nvn 0.3672 -0.9301 -0.0000\nvn -0.0164 -0.9999 -0.0000\nvn -0.3975 -0.9176 -0.0000\nvn -0.3976 -0.9176 -0.0000\nvn -0.7186 -0.6954 -0.0000\nvn -0.9300 -0.3675 -0.0000\nvn -0.9301 -0.3672 -0.0000\nvn 0.9300 0.3676 -0.0000\nvn 0.9299 0.3679 -0.0000\nvn -0.9999 0.0167 -0.0000\nvn 0.9174 -0.3979 -0.0000\nvn 0.9999 -0.0163 -0.0000\nvn -0.9175 0.3978 -0.0000\nvn -0.9176 0.3975 -0.0000\nvn 0.6953 -0.7187 -0.0000\nvn -0.6953 0.7187 -0.0000\nvn 0.3676 -0.9300 -0.0000\nvn 0.3675 -0.9300 -0.0000\nvn -0.3676 0.9300 -0.0000\nvn -0.3679 0.9298 -0.0000\nvn -0.0162 -0.9999 -0.0000\nvn 0.0167 0.9999 -0.0000\nvn -0.3978 -0.9175 -0.0000\nvn 0.3980 0.9174 -0.0000\nvn 0.3979 0.9174 -0.0000\nvn -0.7187 -0.6953 -0.0000\nvn 0.7187 0.6953 -0.0000\nvn -0.8316 -0.5554 -0.0000\nvn -0.9808 -0.1950 -0.0000\nvn -0.9808 -0.1949 -0.0000\nvn -0.9808 -0.1952 0.0001\nvn -0.9808 0.1950 -0.0000\nvn -0.9808 0.1948 -0.0000\nvn -0.8316 0.5554 -0.0000\nvn -0.5554 0.8316 -0.0000\nvn -0.5555 0.8315 -0.0000\nvn -0.5554 0.8316 -0.0001\nvn -0.1948 0.9808 -0.0000\nvn -0.1954 0.9807 -0.0000\nvn 0.1948 0.9808 -0.0000\nvn 0.5554 0.8316 -0.0000\nvn 0.8316 0.5554 -0.0000\nvn 0.9808 0.1948 -0.0000\nvn 0.9808 -0.1948 -0.0000\nvn 0.9808 -0.1950 -0.0000\nvn 0.8316 -0.5554 -0.0000\nvn 0.5554 -0.8316 -0.0000\nvn 0.5555 -0.8315 -0.0001\nvn 0.1949 -0.9808 -0.0000\nvn -0.1949 -0.9808 -0.0000\nvn -0.1950 -0.9808 -0.0000\nvn -0.5554 -0.8316 -0.0000\nvn 0.0081 -1.0000 -0.0000\nvn 0.0082 -1.0000 -0.0000\nvn -0.0082 1.0000 -0.0000\nvn -0.0080 1.0000 -0.0000\nvn -0.0081 1.0000 -0.0000\nvn -1.0000 -0.0081 -0.0000\nvn 0.0079 -1.0000 -0.0000\nvn -0.0079 1.0000 -0.0000\nvn 1.0000 0.0080 -0.0000\nvn 1.0000 0.0082 -0.0000\nvn -0.7071 -0.0055 -0.7071\nvn -1.0000 -0.0080 -0.0000\nvn -0.7071 -0.0055 0.7071\nvn -0.7071 -0.0057 0.7071\nvn -0.9999 -0.0163 0.0003\nvn -0.9999 -0.0164 -0.0000\nvn 0.9999 0.0164 -0.0000\nvn 0.9999 0.0163 -0.0000\nvn -0.0163 0.9999 -0.0000\nvn -0.9999 -0.0166 -0.0000\nvn -0.9999 -0.0165 0.0001\nvn 0.9999 0.0165 -0.0000\nvn 0.0163 -0.9999 -0.0000\nvn -0.0116 0.7070 -0.7071\nvn -0.0117 0.7070 0.7071\nvn -0.7070 -0.7072 -0.0000\nvn 0.7070 0.7072 -0.0000\nvn 0.7072 0.7070 -0.0000\nvn 0.7071 -0.7071 0.0001\nvn -0.7073 -0.7070 -0.0000\nvn 0.7070 0.7073 -0.0000\nvn 0.7073 0.7069 -0.0000\nvn 0.7069 0.7073 -0.0000\nvn -0.7069 -0.7073 -0.0000\nvn 0.4004 0.4005 0.8242\nvn 0.4004 0.4004 0.8242\nvn 0.4003 0.4003 0.8243\nvn -0.4007 -0.4007 0.8240\nvn -0.4004 -0.4004 0.8243\nvn 0.4004 0.4004 0.8243\nvn 0.4005 0.4005 0.8242\nvn 0.4002 0.4004 0.8243\nvn 0.4004 0.4002 0.8243\nvn -0.4004 -0.4004 0.8242\nvn -0.4005 -0.4005 0.8242\nvn -0.4007 -0.4006 0.8240\nvn -0.4003 -0.4003 0.8243\nvn -0.1952 0.9808 -0.0000\nvn -0.1951 0.9808 -0.0000\nvn -0.1950 0.9808 -0.0000\nvn -0.1951 0.9808 -0.0001\nvn -0.5552 0.8317 -0.0000\nvn -0.5561 0.8311 -0.0000\nvn -0.8317 0.5552 -0.0000\nvn -0.8312 0.5559 -0.0000\nvn -0.9808 0.1951 -0.0000\nvn -0.9807 0.1953 -0.0000\nvn -0.9808 0.1951 -0.0001\nvn -0.9808 0.1950 0.0001\nvn 0.9175 0.3977 -0.0000\nvn 0.6954 0.7186 -0.0000\nvn 0.3672 0.9301 -0.0000\nvn -0.0164 0.9999 -0.0000\nvn -0.0160 0.9999 -0.0000\nvn -0.3975 0.9176 -0.0000\nvn -0.3976 0.9176 -0.0000\nvn -0.7186 0.6954 -0.0000\nvn -0.9301 0.3672 -0.0000\nvn -0.9175 -0.3977 -0.0000\nvn -0.6954 -0.7186 -0.0000\nvn -0.3672 -0.9301 -0.0000\nvn 0.0164 -0.9999 -0.0000\nvn 0.0160 -0.9999 -0.0000\nvn 0.3977 -0.9175 -0.0000\nvn 0.3976 -0.9176 -0.0000\nvn 0.7185 -0.6955 -0.0000\nvn 0.7188 -0.6953 -0.0000\nvn 0.9301 -0.3672 -0.0000\nvn -0.9300 0.3676 -0.0000\nvn -0.9299 0.3679 -0.0000\nvn 0.9999 0.0167 -0.0000\nvn -0.9174 -0.3979 -0.0000\nvn -0.9176 -0.3975 -0.0000\nvn -0.9999 -0.0163 -0.0000\nvn -0.9999 -0.0162 -0.0000\nvn 0.9174 0.3979 -0.0000\nvn 0.9176 0.3975 -0.0000\nvn -0.6953 -0.7187 -0.0000\nvn 0.6953 0.7187 -0.0000\nvn -0.3676 -0.9300 -0.0000\nvn -0.3679 -0.9298 -0.0000\nvn 0.3676 0.9300 -0.0000\nvn 0.3679 0.9298 -0.0000\nvn -0.0167 0.9999 -0.0000\nvn 0.3978 -0.9175 -0.0000\nvn -0.3979 0.9174 -0.0000\nvn 0.7187 -0.6953 -0.0000\nvn -0.7187 0.6953 -0.0000\nvn 0.9300 -0.3676 -0.0000\nvn 0.9300 -0.3675 -0.0000\nvn 0.9808 -0.1949 -0.0000\nvn 0.9808 -0.1951 -0.0000\nvn 0.9808 0.1950 -0.0000\nvn 0.5555 0.8315 -0.0000\nvn 0.5554 0.8316 -0.0001\nvn -0.1949 0.9808 -0.0000\nvn -0.9808 -0.1948 -0.0000\nvn -0.5555 -0.8315 -0.0001\nvn -0.0081 1.0000 -0.0001\nvn 0.0083 -1.0000 -0.0000\nvn 1.0000 0.0081 -0.0000\nvn -1.0000 -0.0082 -0.0000\nvn 0.7071 0.0055 -0.7071\nvn 0.7071 0.0055 0.7071\nvn 0.9999 0.0163 0.0003\nvn 0.9999 0.0162 -0.0000\nvn 0.9999 0.0162 -0.0001\nvn -0.9999 -0.0165 -0.0000\nvn 0.0118 -0.7070 -0.7071\nvn 0.0119 -0.7071 -0.7071\nvn 0.0118 -0.7070 0.7071\nvn 0.0117 -0.7070 0.7071\nvn -0.7071 0.7071 0.0001\nvn 0.7073 0.7070 -0.0000\nvn -0.7070 -0.7073 -0.0000\nvn -0.7073 -0.7069 -0.0000\nvn -0.4004 -0.4005 0.8242\nvn -0.4002 -0.4004 0.8243\nvn -0.4004 -0.4002 0.8243\nvn 0.4006 0.4007 0.8240\nvn 0.4007 0.4007 0.8240\nvn 0.4007 0.4006 0.8240\nvn 0.1952 -0.9808 -0.0000\nvn 0.1951 -0.9808 -0.0000\nvn 0.1951 -0.9808 -0.0001\nvn 0.1950 -0.9808 -0.0000\nvn 0.5547 -0.8321 -0.0000\nvn 0.5561 -0.8311 -0.0000\nvn 0.8314 -0.5556 -0.0000\nvn 0.8313 -0.5558 -0.0000\nvn 0.9807 -0.1953 -0.0000\nvn 0.9808 -0.1950 -0.0001\nvn 0.9808 -0.1950 0.0001\nvn 0.7183 -0.6957 -0.0000\nvn 0.7186 -0.6954 -0.0000\nvn 0.9999 0.0166 -0.0000\nvn -0.7183 0.6957 -0.0000\nvn -0.9999 -0.0167 -0.0000\nvn 0.9175 0.3978 -0.0000\nvn -0.9175 -0.3978 -0.0000\nvn -0.0162 0.9999 -0.0000\nvn 0.0162 -0.9999 -0.0000\nvn -0.9300 0.3675 -0.0000\nvn -0.9808 0.1949 -0.0000\nvn -0.9808 0.1952 0.0001\nvn -0.5555 -0.8315 -0.0000\nvn -0.5554 -0.8316 -0.0001\nvn -0.1954 -0.9807 -0.0000\nvn 0.5555 0.8315 -0.0001\nvn 0.1949 0.9808 -0.0000\nvn -0.0080 -1.0000 -0.0000\nvn -1.0000 0.0081 -0.0000\nvn -0.0083 -1.0000 -0.0000\nvn 1.0000 -0.0082 -0.0000\nvn -0.7071 0.0055 -0.7071\nvn -0.7071 0.0055 0.7071\nvn -0.9999 0.0166 -0.0000\nvn -0.9999 0.0165 0.0001\nvn 0.9999 -0.0165 -0.0000\nvn -0.0116 -0.7070 -0.7071\nvn -0.0118 -0.7070 0.7071\nvn -0.0117 -0.7070 0.7071\nvn 0.7071 0.7071 0.0001\nvn 0.7070 -0.7073 -0.0000\nvn 0.7073 -0.7069 -0.0000\nvn -0.7069 0.7073 -0.0000\nvn 0.4002 -0.4004 0.8243\nvn 0.4004 -0.4002 0.8243\nvn -0.4006 0.4007 0.8240\nvn -0.4005 0.4006 0.8241\nvn -0.4007 0.4007 0.8240\nvn -0.4007 0.4006 0.8240\nvn -0.1952 -0.9808 -0.0000\nvn -0.1951 -0.9808 -0.0000\nvn -0.1951 -0.9808 -0.0001\nvn -0.5557 -0.8314 -0.0000\nvn -0.8316 -0.5553 -0.0000\nvn -0.9808 -0.1951 -0.0000\nvn -0.9807 -0.1953 -0.0000\nvn -0.9808 -0.1951 -0.0001\nvn -0.9808 -0.1950 0.0001\nvn 0.9300 0.3675 -0.0000\nvn -0.9300 -0.3676 -0.0000\nvn 0.9999 -0.0167 -0.0000\nvn -0.9174 0.3979 -0.0000\nvn 0.3679 -0.9298 -0.0000\nvn 0.7184 0.6956 -0.0000\nvn 0.9808 0.1949 -0.0000\nvn 0.5555 -0.8315 -0.0000\nvn 0.5554 -0.8316 -0.0001\nvn -0.5555 0.8315 -0.0001\nvn 0.8315 -0.5555 -0.0000\nvn -0.8315 -0.5556 -0.0000\nvn -0.8314 0.5556 -0.0000\nvn -0.5551 0.8318 -0.0000\nvn -0.8315 0.5555 -0.0000\nvn -0.8315 -0.5555 -0.0000\nvn 0.8314 0.5556 -0.0000\nvn -0.8315 0.5556 -0.0000\nvn 0.8315 -0.5556 -0.0000\nvn -0.8318 -0.5551 -0.0000\nvn 0.8318 -0.5551 -0.0000\nvn -0.8318 0.5551 -0.0000\nvn 0.8318 0.5551 -0.0000\nvn -0.7045 -0.7097 -0.0000\nvn 0.7046 0.7096 -0.0000\nvn -0.6808 0.7325 -0.0000\nvn 0.7374 -0.6755 -0.0000\nvn 0.8320 -0.5548 -0.0000\nvn -0.5607 0.8280 -0.0000\nvn -0.2361 0.9717 -0.0000\nvn 0.9734 -0.2291 -0.0000\nvn 0.7045 -0.7097 -0.0000\nvn -0.7046 0.7096 -0.0000\nvn 0.6808 0.7325 -0.0000\nvn -0.7374 -0.6755 -0.0000\nvn -0.8320 -0.5548 -0.0000\nvn 0.5607 0.8280 -0.0000\nvn 0.2361 0.9717 -0.0000\nvn -0.9734 -0.2291 -0.0000\nvn -0.7045 0.7097 -0.0000\nvn 0.7046 -0.7096 -0.0000\nvn -0.6808 -0.7325 -0.0000\nvn 0.7374 0.6755 -0.0000\nvn 0.8320 0.5548 -0.0000\nvn -0.5607 -0.8280 -0.0000\nvn -0.2361 -0.9717 -0.0000\nvn 0.9734 0.2291 -0.0000\nvn 0.7045 0.7097 -0.0000\nvn -0.7046 -0.7096 -0.0000\nvn 0.6808 -0.7325 -0.0000\nvn -0.7374 0.6755 -0.0000\nvn -0.8320 0.5548 -0.0000\nvn 0.5607 -0.8280 -0.0000\nvn 0.2361 -0.9717 -0.0000\nvn -0.9734 0.2291 -0.0000\nvn -0.5859 0.8104 -0.0000\nvn -0.5899 0.8075 -0.0000\nvn -0.5924 0.8054 -0.0199\nvn 1.0000 -0.0000 -0.0000\nvn -0.0000 -1.0000 -0.0000\nvn 0.7044 0.7098 -0.0000\nvn -1.0000 -0.0000 -0.0000\nvn 0.3181 0.9481 -0.0000\nvn -0.0000 1.0000 -0.0000\nvn -0.5899 -0.8075 -0.0000\nvn -0.5859 -0.8104 -0.0000\nvn -0.5924 -0.8054 -0.0199\nvn 0.7044 -0.7098 -0.0000\nvn 0.3181 -0.9481 -0.0000\nvn -0.1670 -0.2598 -0.9511\nvn -0.1670 -0.2598 0.9511\nvn -0.1670 0.2598 -0.9511\nvn -0.1670 0.2598 0.9511\nvn 0.1670 -0.2598 -0.9511\nvn 0.1670 -0.2598 0.9511\nvn 0.1670 0.2598 -0.9511\nvn 0.1670 0.2598 0.9511\nvn -0.1729 -0.0000 -0.9849\nvn -0.5407 -0.8412 -0.0000\nvn -0.1729 -0.0000 0.9849\nvn -0.5407 0.8412 -0.0000\nvn -0.0000 0.2635 -0.9647\nvn -0.0000 0.2635 0.9647\nvn 0.5407 0.8412 -0.0000\nvn 0.1729 -0.0000 -0.9849\nvn 0.1729 -0.0000 0.9849\nvn 0.5407 -0.8412 -0.0000\nvn -0.0000 -0.2635 -0.9647\nvn -0.0000 -0.2635 0.9647\nvn -0.0000 -0.0000 -0.0000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 1.000000 0.500000\nvt 0.000000 0.500000\nvt 0.750000 0.490000\nvt 1.000000 1.000000\nvt 0.250000 0.490000\nvt 0.000000 1.000000\nvt 0.937500 0.500000\nvt 0.841844 0.471731\nvt 0.937500 1.000000\nvt 0.341844 0.471731\nvt 0.875000 0.500000\nvt 0.919706 0.419706\nvt 0.875000 1.000000\nvt 0.419706 0.419706\nvt 0.812500 0.500000\nvt 0.971731 0.341844\nvt 0.812500 1.000000\nvt 0.471731 0.341844\nvt 0.750000 0.500000\nvt 0.990000 0.250000\nvt 0.750000 1.000000\nvt 0.490000 0.250000\nvt 0.687500 0.500000\nvt 0.971731 0.158156\nvt 0.687500 1.000000\nvt 0.471731 0.158156\nvt 0.625000 0.500000\nvt 0.919706 0.080294\nvt 0.625000 1.000000\nvt 0.419706 0.080294\nvt 0.562500 0.500000\nvt 0.841844 0.028269\nvt 0.562500 1.000000\nvt 0.341844 0.028269\nvt 0.500000 0.500000\nvt 0.750000 0.010000\nvt 0.500000 1.000000\nvt 0.250000 0.010000\nvt 0.437500 0.500000\nvt 0.658156 0.028269\nvt 0.437500 1.000000\nvt 0.158156 0.028269\nvt 0.375000 0.500000\nvt 0.580294 0.080294\nvt 0.375000 1.000000\nvt 0.080294 0.080294\nvt 0.312500 0.500000\nvt 0.528269 0.158156\nvt 0.312500 1.000000\nvt 0.028269 0.158156\nvt 0.250000 0.500000\nvt 0.510000 0.250000\nvt 0.250000 1.000000\nvt 0.010000 0.250000\nvt 0.187500 0.500000\nvt 0.528269 0.341844\nvt 0.187500 1.000000\nvt 0.028269 0.341844\nvt 0.125000 0.500000\nvt 0.580294 0.419706\nvt 0.080294 0.419706\nvt 0.125000 1.000000\nvt 0.062500 0.500000\nvt 0.658156 0.471731\nvt 0.158156 0.471731\nvt 0.062500 1.000000\nvt 1.000000 0.500000\nvt 0.000000 0.500000\nvt 0.750000 0.490000\nvt 1.000000 1.000000\nvt 0.250000 0.490000\nvt 0.000000 1.000000\nvt 0.937500 0.500000\nvt 0.841844 0.471731\nvt 0.937500 1.000000\nvt 0.341844 0.471731\nvt 0.875000 0.500000\nvt 0.919706 0.419706\nvt 0.875000 1.000000\nvt 0.419706 0.419706\nvt 0.812500 0.500000\nvt 0.971731 0.341844\nvt 0.812500 1.000000\nvt 0.471731 0.341844\nvt 0.750000 0.500000\nvt 0.990000 0.250000\nvt 0.750000 1.000000\nvt 0.490000 0.250000\nvt 0.687500 0.500000\nvt 0.971731 0.158156\nvt 0.687500 1.000000\nvt 0.471731 0.158156\nvt 0.625000 0.500000\nvt 0.919706 0.080294\nvt 0.625000 1.000000\nvt 0.419706 0.080294\nvt 0.562500 0.500000\nvt 0.841844 0.028269\nvt 0.562500 1.000000\nvt 0.341844 0.028269\nvt 0.500000 0.500000\nvt 0.750000 0.010000\nvt 0.500000 1.000000\nvt 0.250000 0.010000\nvt 0.437500 0.500000\nvt 0.658156 0.028269\nvt 0.437500 1.000000\nvt 0.158156 0.028269\nvt 0.375000 0.500000\nvt 0.580294 0.080294\nvt 0.375000 1.000000\nvt 0.080294 0.080294\nvt 0.312500 0.500000\nvt 0.528269 0.158156\nvt 0.312500 1.000000\nvt 0.028269 0.158156\nvt 0.250000 0.500000\nvt 0.510000 0.250000\nvt 0.250000 1.000000\nvt 0.010000 0.250000\nvt 0.187500 0.500000\nvt 0.528269 0.341844\nvt 0.187500 1.000000\nvt 0.028269 0.341844\nvt 0.125000 0.500000\nvt 0.580294 0.419706\nvt 0.080294 0.419706\nvt 0.125000 1.000000\nvt 0.062500 0.500000\nvt 0.658156 0.471731\nvt 0.158156 0.471731\nvt 0.062500 1.000000\nvt 1.000000 0.500000\nvt 0.000000 0.500000\nvt 0.750000 0.490000\nvt 1.000000 1.000000\nvt 0.250000 0.490000\nvt 0.000000 1.000000\nvt 0.937500 0.500000\nvt 0.841844 0.471731\nvt 0.937500 1.000000\nvt 0.341844 0.471731\nvt 0.875000 0.500000\nvt 0.919706 0.419706\nvt 0.875000 1.000000\nvt 0.419706 0.419706\nvt 0.812500 0.500000\nvt 0.971731 0.341844\nvt 0.812500 1.000000\nvt 0.471731 0.341844\nvt 0.750000 0.500000\nvt 0.990000 0.250000\nvt 0.750000 1.000000\nvt 0.490000 0.250000\nvt 0.687500 0.500000\nvt 0.971731 0.158156\nvt 0.687500 1.000000\nvt 0.471731 0.158156\nvt 0.625000 0.500000\nvt 0.919706 0.080294\nvt 0.625000 1.000000\nvt 0.419706 0.080294\nvt 0.562500 0.500000\nvt 0.841844 0.028269\nvt 0.562500 1.000000\nvt 0.341844 0.028269\nvt 0.500000 0.500000\nvt 0.750000 0.010000\nvt 0.500000 1.000000\nvt 0.250000 0.010000\nvt 0.437500 0.500000\nvt 0.658156 0.028269\nvt 0.437500 1.000000\nvt 0.158156 0.028269\nvt 0.375000 0.500000\nvt 0.580294 0.080294\nvt 0.375000 1.000000\nvt 0.080294 0.080294\nvt 0.312500 0.500000\nvt 0.528269 0.158156\nvt 0.312500 1.000000\nvt 0.028269 0.158156\nvt 0.250000 0.500000\nvt 0.510000 0.250000\nvt 0.250000 1.000000\nvt 0.010000 0.250000\nvt 0.187500 0.500000\nvt 0.528269 0.341844\nvt 0.187500 1.000000\nvt 0.028269 0.341844\nvt 0.125000 0.500000\nvt 0.580294 0.419706\nvt 0.080294 0.419706\nvt 0.125000 1.000000\nvt 0.062500 0.500000\nvt 0.658156 0.471731\nvt 0.158156 0.471731\nvt 0.062500 1.000000\nvt 1.000000 0.500000\nvt 0.000000 0.500000\nvt 0.750000 0.490000\nvt 1.000000 1.000000\nvt 0.250000 0.490000\nvt 0.000000 1.000000\nvt 0.937500 0.500000\nvt 0.841844 0.471731\nvt 0.937500 1.000000\nvt 0.341844 0.471731\nvt 0.875000 0.500000\nvt 0.919706 0.419706\nvt 0.875000 1.000000\nvt 0.419706 0.419706\nvt 0.812500 0.500000\nvt 0.971731 0.341844\nvt 0.812500 1.000000\nvt 0.471731 0.341844\nvt 0.750000 0.500000\nvt 0.990000 0.250000\nvt 0.750000 1.000000\nvt 0.490000 0.250000\nvt 0.687500 0.500000\nvt 0.971731 0.158156\nvt 0.687500 1.000000\nvt 0.471731 0.158156\nvt 0.625000 0.500000\nvt 0.919706 0.080294\nvt 0.625000 1.000000\nvt 0.419706 0.080294\nvt 0.562500 0.500000\nvt 0.841844 0.028269\nvt 0.562500 1.000000\nvt 0.341844 0.028269\nvt 0.500000 0.500000\nvt 0.750000 0.010000\nvt 0.500000 1.000000\nvt 0.250000 0.010000\nvt 0.437500 0.500000\nvt 0.658156 0.028269\nvt 0.437500 1.000000\nvt 0.158156 0.028269\nvt 0.375000 0.500000\nvt 0.580294 0.080294\nvt 0.375000 1.000000\nvt 0.080294 0.080294\nvt 0.312500 0.500000\nvt 0.528269 0.158156\nvt 0.312500 1.000000\nvt 0.028269 0.158156\nvt 0.250000 0.500000\nvt 0.510000 0.250000\nvt 0.250000 1.000000\nvt 0.010000 0.250000\nvt 0.187500 0.500000\nvt 0.528269 0.341844\nvt 0.187500 1.000000\nvt 0.028269 0.341844\nvt 0.125000 0.500000\nvt 0.580294 0.419706\nvt 0.080294 0.419706\nvt 0.125000 1.000000\nvt 0.062500 0.500000\nvt 0.658156 0.471731\nvt 0.158156 0.471731\nvt 0.062500 1.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\nvt 0.000000 0.000000\ns 1\ng off\ng cf_pcb\nusemtl pcb\nf 1/1/1 2/2/2 3/3/3\nf 1/1/1 3/3/3 4/4/4\nf 8/8/5 9/9/6 10/10/7\nf 10/10/7 11/11/8 12/12/9\nf 16/16/10 15/15/11 17/17/12\nf 16/16/10 17/17/12 18/18/13\nf 17/17/12 20/20/14 21/21/15\nf 27/27/16 26/26/17 28/28/18\nf 34/34/19 35/35/20 30/30/21\nf 30/30/21 28/28/18 26/26/17\nf 26/26/17 24/24/22 22/22/23\nf 22/22/23 21/21/15 20/20/14\nf 32/32/24 34/34/19 30/30/21\nf 22/22/23 20/20/14 37/37/25\nf 37/37/25 39/39/26 32/32/24\nf 22/22/23 37/37/25 32/32/24\nf 35/35/20 2/2/2 1/1/1\nf 4/4/4 6/6/27 8/8/5\nf 16/16/10 18/18/13 19/19/28\nf 25/25/29 27/27/16 29/29/30\nf 41/41/31 4/4/4 8/8/5\nf 16/16/10 19/19/28 25/25/29\nf 5/5/32 3/3/3 33/33/33\nf 13/13/34 11/11/8 38/38/35\nf 13/13/34 38/38/35 37/37/25\nf 7/7/36 5/5/32 32/32/24\nf 7/7/36 32/32/24 40/40/37\nf 9/9/6 40/40/37 39/39/26\nf 3/3/3 2/2/2 34/34/19\nf 3/3/3 34/34/19 33/33/33\nf 17/17/12 15/15/11 36/36/38\nf 11/11/8 9/9/6 39/39/26\nf 50/50/39 49/49/40 51/51/41\nf 52/52/42 50/50/39 51/51/41\nf 52/52/42 51/51/41 53/53/43\nf 47/47/44 54/54/45 55/55/46\nf 56/56/47 53/53/43 57/57/48\nf 58/58/49 42/42/50 45/45/51\nf 58/58/49 45/45/51 59/59/52\nf 54/54/45 58/58/49 59/59/52\nf 54/54/45 59/59/52 55/55/46\nf 60/60/53 61/61/54 62/62/55\nf 60/60/53 62/62/55 63/63/56\nf 64/64/57 65/65/58 66/66/59\nf 64/64/57 66/66/59 67/67/60\nf 68/68/61 64/64/57 67/67/60\nf 65/65/58 72/72/62 73/73/63\nf 2/2/2 70/70/64 71/71/65\nf 72/72/62 75/75/66 76/76/67\nf 77/77/68 79/79/69 80/80/70\nf 81/81/71 82/82/72 83/83/73\nf 81/81/71 83/83/73 84/84/74\nf 85/85/75 86/86/76 82/82/72\nf 85/85/75 82/82/72 81/81/71\nf 87/87/77 88/88/78 86/86/76\nf 84/84/74 83/83/73 89/89/79\nf 91/91/80 92/92/81 88/88/78\nf 93/93/82 78/78/83 77/77/68\nf 95/95/84 96/96/85 97/97/86\nf 95/95/84 97/97/86 98/98/87\nf 99/99/88 100/100/89 101/101/90\nf 103/103/91 104/104/92 100/100/89\nf 103/103/91 100/100/89 99/99/88\nf 111/111/93 112/112/94 96/96/85\nf 111/111/93 96/96/85 95/95/84\nf 108/108/95 107/107/96 112/112/94\nf 108/108/95 112/112/94 111/111/93\nf 42/42/50 93/93/82 77/77/68\nf 52/52/42 56/56/47 91/91/80\nf 52/52/42 91/91/80 87/87/77\nf 43/43/97 77/77/68 80/80/70\nf 54/54/45 47/47/44 84/84/74\nf 53/53/43 51/51/41 86/86/76\nf 53/53/43 86/86/76 88/88/78\nf 51/51/41 49/49/40 82/82/72\nf 51/51/41 82/82/72 86/86/76\nf 49/49/40 48/48/98 83/83/73\nf 45/45/51 44/44/99 79/79/69\nf 48/48/98 55/55/46 89/89/79\nf 48/48/98 89/89/79 83/83/73\nf 44/44/99 43/43/97 80/80/70\nf 56/56/47 92/92/81 91/91/80\nf 68/68/61 70/70/64 105/105/100\nf 64/64/57 68/68/61 103/103/91\nf 60/60/53 111/111/93 95/95/84\nf 65/65/58 99/99/88 102/102/101\nf 61/61/102 60/60/53 95/95/84\nf 61/61/102 95/95/84 98/98/87\nf 72/72/62 65/65/58 102/102/101\nf 72/72/62 102/102/101 108/108/95\nf 73/73/63 76/76/67 112/112/94\nf 73/73/63 112/112/94 107/107/96\nf 69/69/103 67/67/60 100/100/89\nf 76/76/67 96/96/85 112/112/94\nf 74/74/104 106/106/105 110/110/106\nf 63/63/56 62/62/55 97/97/86\nf 66/66/59 107/107/96 101/101/90\nf 62/62/55 61/61/102 98/98/87\nf 62/62/55 98/98/87 97/97/86\nf 4/4/4 3/3/3 5/5/32\nf 4/4/4 5/5/32 6/6/27\nf 6/6/27 5/5/32 7/7/36\nf 6/6/27 7/7/36 8/8/5\nf 8/8/5 7/7/36 9/9/6\nf 10/10/7 9/9/6 11/11/8\nf 12/12/9 11/11/8 13/13/34\nf 12/12/9 13/13/34 14/14/107\nf 14/14/107 13/13/34 15/15/11\nf 14/14/107 15/15/11 16/16/10\nf 19/19/28 18/18/13 17/17/12\nf 17/17/12 21/21/15 19/19/28\nf 19/19/28 21/21/15 22/22/23\nf 19/19/28 22/22/23 23/23/108\nf 23/23/108 22/22/23 24/24/22\nf 23/23/108 24/24/22 25/25/29\nf 25/25/29 24/24/22 26/26/17\nf 25/25/29 26/26/17 27/27/16\nf 27/27/16 28/28/18 29/29/30\nf 29/29/30 28/28/18 30/30/21\nf 29/29/30 30/30/21 31/31/109\nf 32/32/24 33/33/33 34/34/19\nf 20/20/14 36/36/38 37/37/25\nf 37/37/25 38/38/35 39/39/26\nf 39/39/26 40/40/37 32/32/24\nf 30/30/21 26/26/17 22/22/23\nf 32/32/24 30/30/21 22/22/23\nf 31/31/109 30/30/21 35/35/20\nf 31/31/109 35/35/20 41/41/31\nf 1/1/1 41/41/31 35/35/20\nf 35/35/20 34/34/19 2/2/2\nf 41/41/31 1/1/1 4/4/4\nf 8/8/5 10/10/7 12/12/9\nf 12/12/9 14/14/107 16/16/10\nf 19/19/28 23/23/108 25/25/29\nf 29/29/30 31/31/109 41/41/31\nf 8/8/5 12/12/9 16/16/10\nf 25/25/29 29/29/30 41/41/31\nf 41/41/31 8/8/5 16/16/10\nf 16/16/10 25/25/29 41/41/31\nf 5/5/32 33/33/33 32/32/24\nf 15/15/11 13/13/34 37/37/25\nf 15/15/11 37/37/25 36/36/38\nf 9/9/6 7/7/36 40/40/37\nf 17/17/12 36/36/38 20/20/14\nf 11/11/8 39/39/26 38/38/35\nf 42/42/50 43/43/97 44/44/99\nf 42/42/50 44/44/99 45/45/51\nf 46/46/110 47/47/44 48/48/98\nf 46/46/110 48/48/98 49/49/40\nf 50/50/39 46/46/110 49/49/40\nf 47/47/44 55/55/46 48/48/98\nf 56/56/47 52/52/42 53/53/43\nf 77/77/68 78/78/83 79/79/69\nf 87/87/77 86/86/76 85/85/75\nf 84/84/74 89/89/79 90/90/111\nf 91/91/80 88/88/78 87/87/77\nf 93/93/82 94/94/112 78/78/83\nf 90/90/111 89/89/79 94/94/112\nf 90/90/111 94/94/112 93/93/82\nf 50/50/39 52/52/42 87/87/77\nf 50/50/39 87/87/77 85/85/75\nf 58/58/49 54/54/45 90/90/111\nf 58/58/49 90/90/111 93/93/82\nf 46/46/110 50/50/39 85/85/75\nf 46/46/110 85/85/75 81/81/71\nf 42/42/50 58/58/49 93/93/82\nf 47/47/44 46/46/110 81/81/71\nf 47/47/44 81/81/71 84/84/74\nf 43/43/97 42/42/50 77/77/68\nf 54/54/45 84/84/74 90/90/111\nf 55/55/46 59/59/52 94/94/112\nf 55/55/46 94/94/112 89/89/79\nf 59/59/52 45/45/51 78/78/83\nf 59/59/52 78/78/83 94/94/112\nf 49/49/40 83/83/73 82/82/72\nf 57/57/48 53/53/43 88/88/78\nf 57/57/48 88/88/78 92/92/81\nf 45/45/51 79/79/69 78/78/83\nf 44/44/99 80/80/70 79/79/69\nf 56/56/47 57/57/48 92/92/81\nf 68/68/61 67/67/60 69/69/103\nf 70/70/64 68/68/61 69/69/103\nf 70/70/64 69/69/103 71/71/65\nf 65/65/58 73/73/63 66/66/59\nf 2/2/2 71/71/65 74/74/104\nf 75/75/66 60/60/53 63/63/56\nf 75/75/66 63/63/56 76/76/67\nf 72/72/62 76/76/67 73/73/63\nf 113/113/84 96/96/85 97/97/86\nf 113/113/84 97/97/86 114/114/87\nf 99/99/88 101/101/90 102/102/101\nf 105/105/100 106/106/105 104/104/92\nf 105/105/100 104/104/92 103/103/91\nf 102/102/101 101/101/90 107/107/96\nf 102/102/101 107/107/96 108/108/95\nf 109/109/113 110/110/106 106/106/105\nf 109/109/113 106/106/105 105/105/100\nf 111/111/93 115/115/94 96/96/85\nf 111/111/93 96/96/85 113/113/84\nf 108/108/95 107/107/96 115/115/94\nf 108/108/95 115/115/94 111/111/93\nf 68/68/61 105/105/100 103/103/91\nf 75/75/66 72/72/62 108/108/95\nf 75/75/66 108/108/95 111/111/93\nf 64/64/57 103/103/91 99/99/88\nf 60/60/53 75/75/66 111/111/93\nf 60/60/53 111/111/93 113/113/84\nf 65/65/58 64/64/57 99/99/88\nf 70/70/64 2/2/2 109/109/113\nf 70/70/64 109/109/113 105/105/100\nf 61/61/102 60/60/53 113/113/84\nf 61/61/102 113/113/84 114/114/87\nf 71/71/65 69/69/103 104/104/92\nf 71/71/65 104/104/92 106/106/105\nf 73/73/63 76/76/67 115/115/94\nf 73/73/63 115/115/94 107/107/96\nf 69/69/103 100/100/89 104/104/92\nf 76/76/67 63/63/56 96/96/85\nf 76/76/67 96/96/85 115/115/94\nf 67/67/60 66/66/59 101/101/90\nf 67/67/60 101/101/90 100/100/89\nf 74/74/104 71/71/65 106/106/105\nf 63/63/56 97/97/86 96/96/85\nf 66/66/59 73/73/63 107/107/96\nf 62/62/55 61/61/102 114/114/87\nf 62/62/55 114/114/87 97/97/86\nf 2/2/2 74/74/104 110/110/106\nf 2/2/2 110/110/106 109/109/113\nf 116/116/114 118/118/115 117/117/116\nf 116/116/114 119/119/117 118/118/115\nf 123/123/118 125/125/119 124/124/120\nf 125/125/119 127/127/121 126/126/122\nf 131/131/123 132/132/124 130/130/125\nf 131/131/123 133/133/126 132/132/124\nf 132/132/124 136/136/127 135/135/128\nf 142/142/129 143/143/130 141/141/131\nf 149/149/132 145/145/133 150/150/134\nf 145/145/133 141/141/131 143/143/130\nf 141/141/131 137/137/135 139/139/136\nf 137/137/135 135/135/128 136/136/127\nf 147/147/137 145/145/133 149/149/132\nf 137/137/135 152/152/138 135/135/128\nf 152/152/138 147/147/137 154/154/139\nf 137/137/135 147/147/137 152/152/138\nf 150/150/134 116/116/114 117/117/116\nf 119/119/117 123/123/118 121/121/140\nf 131/131/123 134/134/141 133/133/126\nf 140/140/142 144/144/143 142/142/129\nf 156/156/144 123/123/118 119/119/117\nf 131/131/123 140/140/142 134/134/141\nf 120/120/145 148/148/146 118/118/115\nf 128/128/147 153/153/148 126/126/122\nf 128/128/147 152/152/138 153/153/148\nf 122/122/149 147/147/137 120/120/145\nf 122/122/149 155/155/150 147/147/137\nf 124/124/120 154/154/139 155/155/150\nf 118/118/115 149/149/132 117/117/116\nf 118/118/115 148/148/146 149/149/132\nf 132/132/124 151/151/151 130/130/125\nf 126/126/122 154/154/139 124/124/120\nf 165/165/152 166/166/153 164/164/154\nf 167/167/155 166/166/153 165/165/152\nf 167/167/155 168/168/156 166/166/153\nf 162/162/157 170/170/158 169/169/159\nf 171/171/160 172/172/161 168/168/156\nf 173/173/162 160/160/163 157/157/164\nf 173/173/162 174/174/165 160/160/163\nf 169/169/159 174/174/165 173/173/162\nf 169/169/159 170/170/158 174/174/165\nf 175/175/166 177/177/167 176/176/168\nf 175/175/166 178/178/169 177/177/167\nf 179/179/170 181/181/171 180/180/172\nf 179/179/170 182/182/173 181/181/171\nf 183/183/174 182/182/173 179/179/170\nf 180/180/172 188/188/175 187/187/176\nf 117/117/177 186/186/178 185/185/179\nf 187/187/176 191/191/180 190/190/181\nf 192/192/182 195/195/183 194/194/184\nf 196/196/185 198/198/186 197/197/187\nf 196/196/185 199/199/188 198/198/186\nf 200/200/189 197/197/187 201/201/190\nf 200/200/189 196/196/185 197/197/187\nf 202/202/191 201/201/190 203/203/192\nf 199/199/188 204/204/193 198/198/186\nf 206/206/194 203/203/192 207/207/195\nf 208/208/196 192/192/182 193/193/197\nf 210/210/198 212/212/199 211/211/200\nf 210/210/198 213/213/201 212/212/199\nf 214/214/202 216/216/203 215/215/204\nf 218/218/205 215/215/204 219/219/206\nf 218/218/205 214/214/202 215/215/204\nf 226/226/207 211/211/200 227/227/208\nf 226/226/207 210/210/198 211/211/200\nf 223/223/209 227/227/208 222/222/210\nf 223/223/209 226/226/207 227/227/208\nf 157/157/164 192/192/182 208/208/196\nf 167/167/155 206/206/194 171/171/160\nf 167/167/155 202/202/191 206/206/194\nf 158/158/211 195/195/183 192/192/182\nf 169/169/159 199/199/188 162/162/157\nf 168/168/156 201/201/190 166/166/153\nf 168/168/156 203/203/192 201/201/190\nf 166/166/153 197/197/187 164/164/154\nf 166/166/153 201/201/190 197/197/187\nf 164/164/154 198/198/186 163/163/212\nf 160/160/163 194/194/184 159/159/213\nf 163/163/212 204/204/193 170/170/158\nf 163/163/212 198/198/186 204/204/193\nf 159/159/213 195/195/183 158/158/211\nf 171/171/160 206/206/194 207/207/195\nf 183/183/174 220/220/214 185/185/179\nf 179/179/170 218/218/205 183/183/174\nf 175/175/166 210/210/198 226/226/207\nf 180/180/172 217/217/215 214/214/202\nf 176/176/216 210/210/198 175/175/166\nf 176/176/216 213/213/201 210/210/198\nf 187/187/176 217/217/215 180/180/172\nf 187/187/176 223/223/209 217/217/215\nf 188/188/175 227/227/208 191/191/180\nf 188/188/175 222/222/210 227/227/208\nf 184/184/217 215/215/204 182/182/173\nf 191/191/180 227/227/208 211/211/200\nf 189/189/218 225/225/219 221/221/220\nf 178/178/169 212/212/199 177/177/167\nf 181/181/171 216/216/203 222/222/210\nf 177/177/167 213/213/201 176/176/216\nf 177/177/167 212/212/199 213/213/201\nf 119/119/117 120/120/145 118/118/115\nf 119/119/117 121/121/140 120/120/145\nf 121/121/140 122/122/149 120/120/145\nf 121/121/140 123/123/118 122/122/149\nf 123/123/118 124/124/120 122/122/149\nf 125/125/119 126/126/122 124/124/120\nf 127/127/121 128/128/147 126/126/122\nf 127/127/121 129/129/221 128/128/147\nf 129/129/221 130/130/125 128/128/147\nf 129/129/221 131/131/123 130/130/125\nf 134/134/141 132/132/124 133/133/126\nf 132/132/124 134/134/141 136/136/127\nf 134/134/141 137/137/135 136/136/127\nf 134/134/141 138/138/222 137/137/135\nf 138/138/222 139/139/136 137/137/135\nf 138/138/222 140/140/142 139/139/136\nf 140/140/142 141/141/131 139/139/136\nf 140/140/142 142/142/129 141/141/131\nf 142/142/129 144/144/143 143/143/130\nf 144/144/143 145/145/133 143/143/130\nf 144/144/143 146/146/223 145/145/133\nf 147/147/137 149/149/132 148/148/146\nf 135/135/128 152/152/138 151/151/151\nf 152/152/138 154/154/139 153/153/148\nf 154/154/139 147/147/137 155/155/150\nf 145/145/133 137/137/135 141/141/131\nf 147/147/137 137/137/135 145/145/133\nf 146/146/223 150/150/134 145/145/133\nf 146/146/223 156/156/144 150/150/134\nf 116/116/114 150/150/134 156/156/144\nf 150/150/134 117/117/116 149/149/132\nf 156/156/144 119/119/117 116/116/114\nf 123/123/118 127/127/121 125/125/119\nf 127/127/121 131/131/123 129/129/221\nf 134/134/141 140/140/142 138/138/222\nf 144/144/143 156/156/144 146/146/223\nf 123/123/118 131/131/123 127/127/121\nf 140/140/142 156/156/144 144/144/143\nf 156/156/144 131/131/123 123/123/118\nf 131/131/123 156/156/144 140/140/142\nf 120/120/145 147/147/137 148/148/146\nf 130/130/125 152/152/138 128/128/147\nf 130/130/125 151/151/151 152/152/138\nf 124/124/120 155/155/150 122/122/149\nf 132/132/124 135/135/128 151/151/151\nf 126/126/122 153/153/148 154/154/139\nf 157/157/164 159/159/213 158/158/211\nf 157/157/164 160/160/163 159/159/213\nf 161/161/224 163/163/212 162/162/157\nf 161/161/224 164/164/154 163/163/212\nf 165/165/152 164/164/154 161/161/224\nf 162/162/157 163/163/212 170/170/158\nf 171/171/160 168/168/156 167/167/155\nf 192/192/182 194/194/184 193/193/197\nf 202/202/191 200/200/189 201/201/190\nf 199/199/188 205/205/225 204/204/193\nf 206/206/194 202/202/191 203/203/192\nf 208/208/196 193/193/197 209/209/226\nf 205/205/225 209/209/226 204/204/193\nf 205/205/225 208/208/196 209/209/226\nf 165/165/152 202/202/191 167/167/155\nf 165/165/152 200/200/189 202/202/191\nf 173/173/162 205/205/225 169/169/159\nf 173/173/162 208/208/196 205/205/225\nf 161/161/224 200/200/189 165/165/152\nf 161/161/224 196/196/185 200/200/189\nf 157/157/164 208/208/196 173/173/162\nf 162/162/157 196/196/185 161/161/224\nf 162/162/157 199/199/188 196/196/185\nf 158/158/211 192/192/182 157/157/164\nf 169/169/159 205/205/225 199/199/188\nf 170/170/158 209/209/226 174/174/165\nf 170/170/158 204/204/193 209/209/226\nf 174/174/165 193/193/197 160/160/163\nf 174/174/165 209/209/226 193/193/197\nf 164/164/154 197/197/187 198/198/186\nf 172/172/161 203/203/192 168/168/156\nf 172/172/161 207/207/195 203/203/192\nf 160/160/163 193/193/197 194/194/184\nf 159/159/213 194/194/184 195/195/183\nf 171/171/160 207/207/195 172/172/161\nf 183/183/174 184/184/217 182/182/173\nf 185/185/179 184/184/217 183/183/174\nf 185/185/179 186/186/178 184/184/217\nf 180/180/172 181/181/171 188/188/175\nf 117/117/177 189/189/218 186/186/178\nf 190/190/181 178/178/169 175/175/166\nf 190/190/181 191/191/180 178/178/169\nf 187/187/176 188/188/175 191/191/180\nf 228/228/198 212/212/199 211/211/200\nf 228/228/198 229/229/201 212/212/199\nf 214/214/202 217/217/215 216/216/203\nf 220/220/214 219/219/206 221/221/220\nf 220/220/214 218/218/205 219/219/206\nf 217/217/215 222/222/210 216/216/203\nf 217/217/215 223/223/209 222/222/210\nf 224/224/227 221/221/220 225/225/219\nf 224/224/227 220/220/214 221/221/220\nf 226/226/207 211/211/200 230/230/208\nf 226/226/207 228/228/198 211/211/200\nf 223/223/209 230/230/208 222/222/210\nf 223/223/209 226/226/207 230/230/208\nf 183/183/174 218/218/205 220/220/214\nf 190/190/181 223/223/209 187/187/176\nf 190/190/181 226/226/207 223/223/209\nf 179/179/170 214/214/202 218/218/205\nf 175/175/166 226/226/207 190/190/181\nf 175/175/166 228/228/198 226/226/207\nf 180/180/172 214/214/202 179/179/170\nf 185/185/179 224/224/227 117/117/177\nf 185/185/179 220/220/214 224/224/227\nf 176/176/216 228/228/198 175/175/166\nf 176/176/216 229/229/201 228/228/198\nf 186/186/178 219/219/206 184/184/217\nf 186/186/178 221/221/220 219/219/206\nf 188/188/175 230/230/208 191/191/180\nf 188/188/175 222/222/210 230/230/208\nf 184/184/217 219/219/206 215/215/204\nf 191/191/180 211/211/200 178/178/169\nf 191/191/180 230/230/208 211/211/200\nf 182/182/173 216/216/203 181/181/171\nf 182/182/173 215/215/204 216/216/203\nf 189/189/218 221/221/220 186/186/178\nf 178/178/169 211/211/200 212/212/199\nf 181/181/171 222/222/210 188/188/175\nf 177/177/167 229/229/201 176/176/216\nf 177/177/167 212/212/199 229/229/201\nf 117/117/177 225/225/219 189/189/218\nf 117/117/177 224/224/227 225/225/219\nf 231/231/126 233/233/228 232/232/229\nf 231/231/126 234/234/141 233/233/228\nf 238/238/230 240/240/129 239/239/231\nf 240/240/129 242/242/232 241/241/233\nf 246/246/234 247/247/235 245/245/236\nf 246/246/234 248/248/114 247/247/235\nf 247/247/235 251/251/146 250/250/132\nf 257/257/119 258/258/237 256/256/139\nf 264/264/128 260/260/138 265/265/151\nf 260/260/138 256/256/139 258/258/237\nf 256/256/139 252/252/137 254/254/238\nf 252/252/137 250/250/132 251/251/146\nf 262/262/135 260/260/138 264/264/128\nf 252/252/137 267/267/133 250/250/132\nf 267/267/133 262/262/135 269/269/131\nf 252/252/137 262/262/135 267/267/133\nf 265/265/151 231/231/126 232/232/229\nf 234/234/141 238/238/230 236/236/222\nf 246/246/234 249/249/239 248/248/114\nf 255/255/118 259/259/121 257/257/119\nf 271/271/240 238/238/230 234/234/141\nf 246/246/234 255/255/118 249/249/239\nf 235/235/241 263/263/242 233/233/228\nf 243/243/243 268/268/130 241/241/233\nf 243/243/243 267/267/133 268/268/130\nf 237/237/244 262/262/135 235/235/241\nf 237/237/244 270/270/136 262/262/135\nf 239/239/231 269/269/131 270/270/136\nf 233/233/228 264/264/128 232/232/229\nf 233/233/228 263/263/242 264/264/128\nf 247/247/235 266/266/245 245/245/236\nf 241/241/233 269/269/131 239/239/231\nf 280/280/174 281/281/246 279/279/173\nf 282/282/247 281/281/246 280/280/174\nf 282/282/247 283/283/248 281/281/246\nf 277/277/172 285/285/249 284/284/176\nf 286/286/250 287/287/218 283/283/248\nf 288/288/251 275/275/169 272/272/252\nf 288/288/251 289/289/253 275/275/169\nf 284/284/176 289/289/253 288/288/251\nf 284/284/176 285/285/249 289/289/253\nf 290/290/254 292/292/255 291/291/256\nf 290/290/254 293/293/163 292/292/255\nf 294/294/224 296/296/212 295/295/157\nf 294/294/224 297/297/154 296/296/212\nf 298/298/152 297/297/154 294/294/224\nf 295/295/157 303/303/257 302/302/159\nf 232/232/258 301/301/259 300/300/260\nf 302/302/159 306/306/261 305/305/162\nf 307/307/262 310/310/263 309/309/264\nf 311/311/202 313/313/265 312/312/204\nf 311/311/202 314/314/215 313/313/265\nf 315/315/266 312/312/204 316/316/267\nf 315/315/266 311/311/202 312/312/204\nf 317/317/214 316/316/267 318/318/268\nf 314/314/215 319/319/269 313/313/265\nf 321/321/270 318/318/268 322/322/271\nf 323/323/272 307/307/262 308/308/273\nf 325/325/274 327/327/275 326/326/276\nf 325/325/274 328/328/183 327/327/275\nf 329/329/277 331/331/278 330/330/279\nf 333/333/280 330/330/279 334/334/281\nf 333/333/280 329/329/277 330/330/279\nf 341/341/282 326/326/276 342/342/226\nf 341/341/282 325/325/274 326/326/276\nf 338/338/283 342/342/226 337/337/284\nf 338/338/283 341/341/282 342/342/226\nf 272/272/252 307/307/262 323/323/272\nf 282/282/247 321/321/270 286/286/250\nf 282/282/247 317/317/214 321/321/270\nf 273/273/285 310/310/263 307/307/262\nf 284/284/176 314/314/215 277/277/172\nf 283/283/248 316/316/267 281/281/246\nf 283/283/248 318/318/268 316/316/267\nf 281/281/246 312/312/204 279/279/173\nf 281/281/246 316/316/267 312/312/204\nf 279/279/173 313/313/265 278/278/171\nf 275/275/169 309/309/264 274/274/286\nf 278/278/171 319/319/269 285/285/249\nf 278/278/171 313/313/265 319/319/269\nf 274/274/286 310/310/263 273/273/285\nf 286/286/250 321/321/270 322/322/271\nf 298/298/152 335/335/191 300/300/260\nf 294/294/224 333/333/280 298/298/152\nf 290/290/254 325/325/274 341/341/282\nf 295/295/157 332/332/287 329/329/277\nf 291/291/288 325/325/274 290/290/254\nf 291/291/288 328/328/183 325/325/274\nf 302/302/159 332/332/287 295/295/157\nf 302/302/159 338/338/283 332/332/287\nf 303/303/257 342/342/226 306/306/261\nf 303/303/257 337/337/284 342/342/226\nf 299/299/289 330/330/279 297/297/154\nf 306/306/261 342/342/226 326/326/276\nf 304/304/161 340/340/195 336/336/192\nf 293/293/163 327/327/275 292/292/255\nf 296/296/212 331/331/278 337/337/284\nf 292/292/255 328/328/183 291/291/288\nf 292/292/255 327/327/275 328/328/183\nf 234/234/141 235/235/241 233/233/228\nf 234/234/141 236/236/222 235/235/241\nf 236/236/222 237/237/244 235/235/241\nf 236/236/222 238/238/230 237/237/244\nf 238/238/230 239/239/231 237/237/244\nf 240/240/129 241/241/233 239/239/231\nf 242/242/232 243/243/243 241/241/233\nf 242/242/232 244/244/223 243/243/243\nf 244/244/223 245/245/236 243/243/243\nf 244/244/223 246/246/234 245/245/236\nf 249/249/239 247/247/235 248/248/114\nf 247/247/235 249/249/239 251/251/146\nf 249/249/239 252/252/137 251/251/146\nf 249/249/239 253/253/140 252/252/137\nf 253/253/140 254/254/238 252/252/137\nf 253/253/140 255/255/118 254/254/238\nf 255/255/118 256/256/139 254/254/238\nf 255/255/118 257/257/119 256/256/139\nf 257/257/119 259/259/121 258/258/237\nf 259/259/121 260/260/138 258/258/237\nf 259/259/121 261/261/290 260/260/138\nf 262/262/135 264/264/128 263/263/242\nf 250/250/132 267/267/133 266/266/245\nf 267/267/133 269/269/131 268/268/130\nf 269/269/131 262/262/135 270/270/136\nf 260/260/138 252/252/137 256/256/139\nf 262/262/135 252/252/137 260/260/138\nf 261/261/290 265/265/151 260/260/138\nf 261/261/290 271/271/240 265/265/151\nf 231/231/126 265/265/151 271/271/240\nf 265/265/151 232/232/229 264/264/128\nf 271/271/240 234/234/141 231/231/126\nf 238/238/230 242/242/232 240/240/129\nf 242/242/232 246/246/234 244/244/223\nf 249/249/239 255/255/118 253/253/140\nf 259/259/121 271/271/240 261/261/290\nf 238/238/230 246/246/234 242/242/232\nf 255/255/118 271/271/240 259/259/121\nf 271/271/240 246/246/234 238/238/230\nf 246/246/234 271/271/240 255/255/118\nf 235/235/241 262/262/135 263/263/242\nf 245/245/236 267/267/133 243/243/243\nf 245/245/236 266/266/245 267/267/133\nf 239/239/231 270/270/136 237/237/244\nf 247/247/235 250/250/132 266/266/245\nf 241/241/233 268/268/130 269/269/131\nf 272/272/252 274/274/286 273/273/285\nf 272/272/252 275/275/169 274/274/286\nf 276/276/170 278/278/171 277/277/172\nf 276/276/170 279/279/173 278/278/171\nf 280/280/174 279/279/173 276/276/170\nf 277/277/172 278/278/171 285/285/249\nf 286/286/250 283/283/248 282/282/247\nf 307/307/262 309/309/264 308/308/273\nf 317/317/214 315/315/266 316/316/267\nf 314/314/215 320/320/291 319/319/269\nf 321/321/270 317/317/214 318/318/268\nf 323/323/272 308/308/273 324/324/292\nf 320/320/291 324/324/292 319/319/269\nf 320/320/291 323/323/272 324/324/292\nf 280/280/174 317/317/214 282/282/247\nf 280/280/174 315/315/266 317/317/214\nf 288/288/251 320/320/291 284/284/176\nf 288/288/251 323/323/272 320/320/291\nf 276/276/170 315/315/266 280/280/174\nf 276/276/170 311/311/202 315/315/266\nf 272/272/252 323/323/272 288/288/251\nf 277/277/172 311/311/202 276/276/170\nf 277/277/172 314/314/215 311/311/202\nf 273/273/285 307/307/262 272/272/252\nf 284/284/176 320/320/291 314/314/215\nf 285/285/249 324/324/292 289/289/253\nf 285/285/249 319/319/269 324/324/292\nf 289/289/253 308/308/273 275/275/169\nf 289/289/253 324/324/292 308/308/273\nf 279/279/173 312/312/204 313/313/265\nf 287/287/218 318/318/268 283/283/248\nf 287/287/218 322/322/271 318/318/268\nf 275/275/169 308/308/273 309/309/264\nf 274/274/286 309/309/264 310/310/263\nf 286/286/250 322/322/271 287/287/218\nf 298/298/152 299/299/289 297/297/154\nf 300/300/260 299/299/289 298/298/152\nf 300/300/260 301/301/259 299/299/289\nf 295/295/157 296/296/212 303/303/257\nf 232/232/258 304/304/161 301/301/259\nf 305/305/162 293/293/163 290/290/254\nf 305/305/162 306/306/261 293/293/163\nf 302/302/159 303/303/257 306/306/261\nf 343/343/274 327/327/275 326/326/276\nf 343/343/274 344/344/183 327/327/275\nf 329/329/277 332/332/287 331/331/278\nf 335/335/191 334/334/281 336/336/192\nf 335/335/191 333/333/280 334/334/281\nf 332/332/287 337/337/284 331/331/278\nf 332/332/287 338/338/283 337/337/284\nf 339/339/293 336/336/192 340/340/195\nf 339/339/293 335/335/191 336/336/192\nf 341/341/282 326/326/276 345/345/226\nf 341/341/282 343/343/274 326/326/276\nf 338/338/283 345/345/226 337/337/284\nf 338/338/283 341/341/282 345/345/226\nf 298/298/152 333/333/280 335/335/191\nf 305/305/162 338/338/283 302/302/159\nf 305/305/162 341/341/282 338/338/283\nf 294/294/224 329/329/277 333/333/280\nf 290/290/254 341/341/282 305/305/162\nf 290/290/254 343/343/274 341/341/282\nf 295/295/157 329/329/277 294/294/224\nf 300/300/260 339/339/293 232/232/258\nf 300/300/260 335/335/191 339/339/293\nf 291/291/288 343/343/274 290/290/254\nf 291/291/288 344/344/183 343/343/274\nf 301/301/259 334/334/281 299/299/289\nf 301/301/259 336/336/192 334/334/281\nf 303/303/257 345/345/226 306/306/261\nf 303/303/257 337/337/284 345/345/226\nf 299/299/289 334/334/281 330/330/279\nf 306/306/261 326/326/276 293/293/163\nf 306/306/261 345/345/226 326/326/276\nf 297/297/154 331/331/278 296/296/212\nf 297/297/154 330/330/279 331/331/278\nf 304/304/161 336/336/192 301/301/259\nf 293/293/163 326/326/276 327/327/275\nf 296/296/212 337/337/284 303/303/257\nf 292/292/255 344/344/183 291/291/288\nf 292/292/255 327/327/275 344/344/183\nf 232/232/258 340/340/195 304/304/161\nf 232/232/258 339/339/293 340/340/195\nf 346/346/294 347/347/295 348/348/296\nf 346/346/294 348/348/296 349/349/297\nf 353/353/29 354/354/298 355/355/299\nf 355/355/299 356/356/300 357/357/30\nf 361/361/301 360/360/302 362/362/303\nf 361/361/301 362/362/303 363/363/1\nf 362/362/303 365/365/19 366/366/304\nf 372/372/305 371/371/26 373/373/35\nf 379/379/14 380/380/306 375/375/25\nf 375/375/25 373/373/35 371/371/26\nf 371/371/26 369/369/37 367/367/24\nf 367/367/24 366/366/304 365/365/19\nf 377/377/23 379/379/14 375/375/25\nf 367/367/24 365/365/19 382/382/21\nf 382/382/21 384/384/17 377/377/23\nf 367/367/24 382/382/21 377/377/23\nf 380/380/306 347/347/295 346/346/294\nf 349/349/297 351/351/108 353/353/29\nf 361/361/301 363/363/1 364/364/307\nf 370/370/5 372/372/305 374/374/308\nf 386/386/309 349/349/297 353/353/29\nf 361/361/301 364/364/307 370/370/5\nf 350/350/310 348/348/296 378/378/15\nf 358/358/311 356/356/300 383/383/18\nf 358/358/311 383/383/18 382/382/21\nf 352/352/312 350/350/310 377/377/23\nf 352/352/312 377/377/23 385/385/313\nf 354/354/298 385/385/313 384/384/17\nf 348/348/296 347/347/295 379/379/14\nf 348/348/296 379/379/14 378/378/15\nf 362/362/303 360/360/302 381/381/314\nf 356/356/300 354/354/298 384/384/17\nf 395/395/315 394/394/60 396/396/316\nf 397/397/64 395/395/315 396/396/316\nf 397/397/64 396/396/316 398/398/65\nf 392/392/317 399/399/62 400/400/318\nf 401/401/319 398/398/65 402/402/104\nf 403/403/66 387/387/320 390/390/56\nf 403/403/66 390/390/56 404/404/321\nf 399/399/62 403/403/66 404/404/321\nf 399/399/62 404/404/321 400/400/318\nf 405/405/322 406/406/323 407/407/324\nf 405/405/322 407/407/324 408/408/51\nf 409/409/110 410/410/44 411/411/98\nf 409/409/110 411/411/98 412/412/40\nf 413/413/325 409/409/110 412/412/40\nf 410/410/44 417/417/45 418/418/326\nf 347/347/295 415/415/327 416/416/328\nf 417/417/45 420/420/49 421/421/329\nf 422/422/330 424/424/331 425/425/87\nf 426/426/88 427/427/89 428/428/332\nf 426/426/88 428/428/332 429/429/333\nf 430/430/334 431/431/92 427/427/89\nf 430/430/334 427/427/89 426/426/88\nf 432/432/335 433/433/105 431/431/92\nf 429/429/333 428/428/332 434/434/336\nf 436/436/337 437/437/106 433/433/105\nf 438/438/338 423/423/339 422/422/330\nf 440/440/340 441/441/341 442/442/342\nf 440/440/340 442/442/342 443/443/70\nf 444/444/71 445/445/72 446/446/343\nf 448/448/344 449/449/76 445/445/72\nf 448/448/344 445/445/72 444/444/71\nf 456/456/345 457/457/112 441/441/341\nf 456/456/345 441/441/341 440/440/340\nf 453/453/346 452/452/347 457/457/112\nf 453/453/346 457/457/112 456/456/345\nf 387/387/320 438/438/338 422/422/330\nf 397/397/64 401/401/319 436/436/337\nf 397/397/64 436/436/337 432/432/335\nf 388/388/348 422/422/330 425/425/87\nf 399/399/62 392/392/317 429/429/333\nf 398/398/65 396/396/316 431/431/92\nf 398/398/65 431/431/92 433/433/105\nf 396/396/316 394/394/60 427/427/89\nf 396/396/316 427/427/89 431/431/92\nf 394/394/60 393/393/349 428/428/332\nf 390/390/56 389/389/350 424/424/331\nf 393/393/349 400/400/318 434/434/336\nf 393/393/349 434/434/336 428/428/332\nf 389/389/350 388/388/348 425/425/87\nf 401/401/319 437/437/106 436/436/337\nf 413/413/325 415/415/327 450/450/351\nf 409/409/110 413/413/325 448/448/344\nf 405/405/322 456/456/345 440/440/340\nf 410/410/44 444/444/71 447/447/74\nf 406/406/352 405/405/322 440/440/340\nf 406/406/352 440/440/340 443/443/70\nf 417/417/45 410/410/44 447/447/74\nf 417/417/45 447/447/74 453/453/346\nf 418/418/326 421/421/329 457/457/112\nf 418/418/326 457/457/112 452/452/347\nf 414/414/353 412/412/40 445/445/72\nf 421/421/329 441/441/341 457/457/112\nf 419/419/48 451/451/78 455/455/354\nf 408/408/51 407/407/324 442/442/342\nf 411/411/98 452/452/347 446/446/343\nf 407/407/324 406/406/352 443/443/70\nf 407/407/324 443/443/70 442/442/342\nf 349/349/297 348/348/296 350/350/310\nf 349/349/297 350/350/310 351/351/108\nf 351/351/108 350/350/310 352/352/312\nf 351/351/108 352/352/312 353/353/29\nf 353/353/29 352/352/312 354/354/298\nf 355/355/299 354/354/298 356/356/300\nf 357/357/30 356/356/300 358/358/311\nf 357/357/30 358/358/311 359/359/109\nf 359/359/109 358/358/311 360/360/302\nf 359/359/109 360/360/302 361/361/301\nf 364/364/307 363/363/1 362/362/303\nf 362/362/303 366/366/304 364/364/307\nf 364/364/307 366/366/304 367/367/24\nf 364/364/307 367/367/24 368/368/27\nf 368/368/27 367/367/24 369/369/37\nf 368/368/27 369/369/37 370/370/5\nf 370/370/5 369/369/37 371/371/26\nf 370/370/5 371/371/26 372/372/305\nf 372/372/305 373/373/35 374/374/308\nf 374/374/308 373/373/35 375/375/25\nf 374/374/308 375/375/25 376/376/107\nf 377/377/23 378/378/15 379/379/14\nf 365/365/19 381/381/314 382/382/21\nf 382/382/21 383/383/18 384/384/17\nf 384/384/17 385/385/313 377/377/23\nf 375/375/25 371/371/26 367/367/24\nf 377/377/23 375/375/25 367/367/24\nf 376/376/107 375/375/25 380/380/306\nf 376/376/107 380/380/306 386/386/309\nf 346/346/294 386/386/309 380/380/306\nf 380/380/306 379/379/14 347/347/295\nf 386/386/309 346/346/294 349/349/297\nf 353/353/29 355/355/299 357/357/30\nf 357/357/30 359/359/109 361/361/301\nf 364/364/307 368/368/27 370/370/5\nf 374/374/308 376/376/107 386/386/309\nf 353/353/29 357/357/30 361/361/301\nf 370/370/5 374/374/308 386/386/309\nf 386/386/309 353/353/29 361/361/301\nf 361/361/301 370/370/5 386/386/309\nf 350/350/310 378/378/15 377/377/23\nf 360/360/302 358/358/311 382/382/21\nf 360/360/302 382/382/21 381/381/314\nf 354/354/298 352/352/312 385/385/313\nf 362/362/303 381/381/314 365/365/19\nf 356/356/300 384/384/17 383/383/18\nf 387/387/320 388/388/348 389/389/350\nf 387/387/320 389/389/350 390/390/56\nf 391/391/57 392/392/317 393/393/349\nf 391/391/57 393/393/349 394/394/60\nf 395/395/315 391/391/57 394/394/60\nf 392/392/317 400/400/318 393/393/349\nf 401/401/319 397/397/64 398/398/65\nf 422/422/330 423/423/339 424/424/331\nf 432/432/335 431/431/92 430/430/334\nf 429/429/333 434/434/336 435/435/355\nf 436/436/337 433/433/105 432/432/335\nf 438/438/338 439/439/94 423/423/339\nf 435/435/355 434/434/336 439/439/94\nf 435/435/355 439/439/94 438/438/338\nf 395/395/315 397/397/64 432/432/335\nf 395/395/315 432/432/335 430/430/334\nf 403/403/66 399/399/62 435/435/355\nf 403/403/66 435/435/355 438/438/338\nf 391/391/57 395/395/315 430/430/334\nf 391/391/57 430/430/334 426/426/88\nf 387/387/320 403/403/66 438/438/338\nf 392/392/317 391/391/57 426/426/88\nf 392/392/317 426/426/88 429/429/333\nf 388/388/348 387/387/320 422/422/330\nf 399/399/62 429/429/333 435/435/355\nf 400/400/318 404/404/321 439/439/94\nf 400/400/318 439/439/94 434/434/336\nf 404/404/321 390/390/56 423/423/339\nf 404/404/321 423/423/339 439/439/94\nf 394/394/60 428/428/332 427/427/89\nf 402/402/104 398/398/65 433/433/105\nf 402/402/104 433/433/105 437/437/106\nf 390/390/56 424/424/331 423/423/339\nf 389/389/350 425/425/87 424/424/331\nf 401/401/319 402/402/104 437/437/106\nf 413/413/325 412/412/40 414/414/353\nf 415/415/327 413/413/325 414/414/353\nf 415/415/327 414/414/353 416/416/328\nf 410/410/44 418/418/326 411/411/98\nf 347/347/295 416/416/328 419/419/48\nf 420/420/49 405/405/322 408/408/51\nf 420/420/49 408/408/51 421/421/329\nf 417/417/45 421/421/329 418/418/326\nf 458/458/340 441/441/341 442/442/342\nf 458/458/340 442/442/342 459/459/70\nf 444/444/71 446/446/343 447/447/74\nf 450/450/351 451/451/78 449/449/76\nf 450/450/351 449/449/76 448/448/344\nf 447/447/74 446/446/343 452/452/347\nf 447/447/74 452/452/347 453/453/346\nf 454/454/356 455/455/354 451/451/78\nf 454/454/356 451/451/78 450/450/351\nf 456/456/345 460/460/112 441/441/341\nf 456/456/345 441/441/341 458/458/340\nf 453/453/346 452/452/347 460/460/112\nf 453/453/346 460/460/112 456/456/345\nf 413/413/325 450/450/351 448/448/344\nf 420/420/49 417/417/45 453/453/346\nf 420/420/49 453/453/346 456/456/345\nf 409/409/110 448/448/344 444/444/71\nf 405/405/322 420/420/49 456/456/345\nf 405/405/322 456/456/345 458/458/340\nf 410/410/44 409/409/110 444/444/71\nf 415/415/327 347/347/295 454/454/356\nf 415/415/327 454/454/356 450/450/351\nf 406/406/352 405/405/322 458/458/340\nf 406/406/352 458/458/340 459/459/70\nf 416/416/328 414/414/353 449/449/76\nf 416/416/328 449/449/76 451/451/78\nf 418/418/326 421/421/329 460/460/112\nf 418/418/326 460/460/112 452/452/347\nf 414/414/353 445/445/72 449/449/76\nf 421/421/329 408/408/51 441/441/341\nf 421/421/329 441/441/341 460/460/112\nf 412/412/40 411/411/98 446/446/343\nf 412/412/40 446/446/343 445/445/72\nf 419/419/48 416/416/328 451/451/78\nf 408/408/51 442/442/342 441/441/341\nf 411/411/98 418/418/326 452/452/347\nf 407/407/324 406/406/352 459/459/70\nf 407/407/324 459/459/70 442/442/342\nf 347/347/295 419/419/48 455/455/354\nf 347/347/295 455/455/354 454/454/356\ns 0\nf 1557/1693/707 1558/1694/707 1559/1695/707\nf 1557/1693/707 1559/1695/707 1560/1696/707\nf 1561/1697/708 1562/1698/708 1563/1699/708\nf 1561/1697/708 1563/1699/708 1564/1700/708\nf 1565/1701/709 1564/1700/709 1563/1699/709\nf 1565/1701/709 1563/1699/709 1566/1702/709\nf 1567/1703/373 1561/1697/373 1564/1700/373\nf 1567/1703/373 1564/1700/373 1565/1701/373\nf 1568/1704/710 1562/1698/710 1561/1697/710\nf 1568/1704/710 1561/1697/710 1567/1703/710\nf 1566/1702/368 1563/1699/368 1562/1698/368\nf 1566/1702/368 1562/1698/368 1568/1704/368\nf 1569/1705/368 1566/1702/368 1568/1704/368\nf 1569/1705/368 1568/1704/368 1570/1706/368\nf 1570/1706/711 1568/1704/711 1567/1703/711\nf 1570/1706/711 1567/1703/711 1571/1707/711\nf 1571/1707/373 1567/1703/373 1565/1701/373\nf 1571/1707/373 1565/1701/373 1572/1708/373\nf 1572/1708/712 1565/1701/712 1566/1702/712\nf 1572/1708/712 1566/1702/712 1569/1705/712\nf 1558/1694/713 1572/1708/713 1569/1705/713\nf 1558/1694/713 1569/1705/713 1559/1695/713\nf 1557/1693/373 1571/1707/373 1572/1708/373\nf 1557/1693/373 1572/1708/373 1558/1694/373\nf 1560/1696/714 1570/1706/714 1571/1707/714\nf 1560/1696/714 1571/1707/714 1557/1693/714\nf 1559/1695/368 1569/1705/368 1570/1706/368\nf 1559/1695/368 1570/1706/368 1560/1696/368\nf 1573/1709/715 1574/1710/715 1575/1711/715\nf 1573/1709/715 1575/1711/715 1576/1712/715\nf 1577/1713/716 1578/1714/716 1579/1715/716\nf 1577/1713/716 1579/1715/716 1580/1716/716\nf 1581/1717/717 1582/1718/717 1579/1715/717\nf 1581/1717/717 1579/1715/717 1578/1714/717\nf 1583/1719/373 1581/1717/373 1578/1714/373\nf 1583/1719/373 1578/1714/373 1577/1713/373\nf 1584/1720/718 1583/1719/718 1577/1713/718\nf 1584/1720/718 1577/1713/718 1580/1716/718\nf 1582/1718/368 1584/1720/368 1580/1716/368\nf 1582/1718/368 1580/1716/368 1579/1715/368\nf 1585/1721/368 1586/1722/368 1584/1720/368\nf 1585/1721/368 1584/1720/368 1582/1718/368\nf 1586/1722/719 1587/1723/719 1583/1719/719\nf 1586/1722/719 1583/1719/719 1584/1720/719\nf 1587/1723/373 1588/1724/373 1581/1717/373\nf 1587/1723/373 1581/1717/373 1583/1719/373\nf 1588/1724/720 1585/1721/720 1582/1718/720\nf 1588/1724/720 1582/1718/720 1581/1717/720\nf 1576/1712/721 1575/1711/721 1585/1721/721\nf 1576/1712/721 1585/1721/721 1588/1724/721\nf 1573/1709/373 1576/1712/373 1588/1724/373\nf 1573/1709/373 1588/1724/373 1587/1723/373\nf 1574/1710/722 1573/1709/722 1587/1723/722\nf 1574/1710/722 1587/1723/722 1586/1722/722\nf 1575/1711/368 1574/1710/368 1586/1722/368\nf 1575/1711/368 1586/1722/368 1585/1721/368\nf 1589/1725/723 1590/1726/723 1591/1727/723\nf 1589/1725/723 1591/1727/723 1592/1728/723\nf 1593/1729/724 1594/1730/724 1595/1731/724\nf 1593/1729/724 1595/1731/724 1596/1732/724\nf 1597/1733/725 1598/1734/725 1595/1731/725\nf 1597/1733/725 1595/1731/725 1594/1730/725\nf 1599/1735/373 1597/1733/373 1594/1730/373\nf 1599/1735/373 1594/1730/373 1593/1729/373\nf 1600/1736/726 1599/1735/726 1593/1729/726\nf 1600/1736/726 1593/1729/726 1596/1732/726\nf 1598/1734/368 1600/1736/368 1596/1732/368\nf 1598/1734/368 1596/1732/368 1595/1731/368\nf 1601/1737/368 1602/1738/368 1600/1736/368\nf 1601/1737/368 1600/1736/368 1598/1734/368\nf 1602/1738/727 1603/1739/727 1599/1735/727\nf 1602/1738/727 1599/1735/727 1600/1736/727\nf 1603/1739/373 1604/1740/373 1597/1733/373\nf 1603/1739/373 1597/1733/373 1599/1735/373\nf 1604/1740/728 1601/1737/728 1598/1734/728\nf 1604/1740/728 1598/1734/728 1597/1733/728\nf 1592/1728/729 1591/1727/729 1601/1737/729\nf 1592/1728/729 1601/1737/729 1604/1740/729\nf 1589/1725/373 1592/1728/373 1604/1740/373\nf 1589/1725/373 1604/1740/373 1603/1739/373\nf 1590/1726/730 1589/1725/730 1603/1739/730\nf 1590/1726/730 1603/1739/730 1602/1738/730\nf 1591/1727/368 1590/1726/368 1602/1738/368\nf 1591/1727/368 1602/1738/368 1601/1737/368\nf 1605/1741/731 1606/1742/731 1607/1743/731\nf 1605/1741/731 1607/1743/731 1608/1744/731\nf 1609/1745/732 1610/1746/732 1611/1747/732\nf 1609/1745/732 1611/1747/732 1612/1748/732\nf 1613/1749/733 1612/1748/733 1611/1747/733\nf 1613/1749/733 1611/1747/733 1614/1750/733\nf 1615/1751/373 1609/1745/373 1612/1748/373\nf 1615/1751/373 1612/1748/373 1613/1749/373\nf 1616/1752/734 1610/1746/734 1609/1745/734\nf 1616/1752/734 1609/1745/734 1615/1751/734\nf 1614/1750/368 1611/1747/368 1610/1746/368\nf 1614/1750/368 1610/1746/368 1616/1752/368\nf 1617/1753/368 1614/1750/368 1616/1752/368\nf 1617/1753/368 1616/1752/368 1618/1754/368\nf 1618/1754/735 1616/1752/735 1615/1751/735\nf 1618/1754/735 1615/1751/735 1619/1755/735\nf 1619/1755/373 1615/1751/373 1613/1749/373\nf 1619/1755/373 1613/1749/373 1620/1756/373\nf 1620/1756/736 1613/1749/736 1614/1750/736\nf 1620/1756/736 1614/1750/736 1617/1753/736\nf 1606/1742/737 1620/1756/737 1617/1753/737\nf 1606/1742/737 1617/1753/737 1607/1743/737\nf 1605/1741/373 1619/1755/373 1620/1756/373\nf 1605/1741/373 1620/1756/373 1606/1742/373\nf 1608/1744/738 1618/1754/738 1619/1755/738\nf 1608/1744/738 1619/1755/738 1605/1741/738\nf 1607/1743/368 1617/1753/368 1618/1754/368\nf 1607/1743/368 1618/1754/368 1608/1744/368\nf 1621/1757/368 1622/1758/368 1623/1759/368\nf 1623/1759/739 1624/1760/739 1625/1761/739\nf 1625/1761/740 1626/1762/740 1621/1757/740\nf 1623/1759/741 1625/1761/741 1621/1757/741\nf 1627/1763/731 1628/1764/731 1629/1765/731\nf 1627/1763/731 1629/1765/731 1630/1766/731\nf 1631/1767/742 1632/1768/742 1633/1769/742\nf 1631/1767/742 1633/1769/742 1634/1770/742\nf 1632/1768/743 1635/1771/743 1636/1772/743\nf 1632/1768/743 1636/1772/743 1633/1769/743\nf 1637/1773/373 1635/1771/373 1632/1768/373\nf 1637/1773/373 1632/1768/373 1631/1767/373\nf 1634/1770/368 1633/1769/368 1636/1772/368\nf 1634/1770/368 1636/1772/368 1638/1774/368\nf 1639/1775/744 1640/1776/744 1641/1777/744\nf 1639/1775/744 1641/1777/744 1642/1778/744\nf 1621/1757/373 1639/1775/373 1642/1778/373\nf 1621/1757/373 1642/1778/373 1622/1758/373\nf 1622/1758/373 1642/1778/373 1627/1763/373\nf 1622/1758/373 1627/1763/373 1623/1759/373\nf 1637/1773/745 1621/1757/745 1626/1762/745\nf 1637/1773/745 1626/1762/745 1638/1774/745\nf 1635/1771/745 1637/1773/745 1638/1774/745\nf 1635/1771/745 1638/1774/745 1636/1772/745\nf 1640/1776/368 1634/1770/368 1638/1774/368\nf 1640/1776/368 1638/1774/368 1626/1762/368\nf 1621/1757/373 1637/1773/373 1631/1767/373\nf 1621/1757/373 1631/1767/373 1639/1775/373\nf 1639/1775/746 1631/1767/746 1634/1770/746\nf 1639/1775/746 1634/1770/746 1640/1776/746\nf 1641/1777/368 1640/1776/368 1626/1762/368\nf 1626/1762/368 1625/1761/368 1629/1765/368\nf 1628/1764/368 1641/1777/368 1626/1762/368\nf 1626/1762/368 1629/1765/368 1628/1764/368\nf 1623/1759/373 1627/1763/373 1630/1766/373\nf 1623/1759/373 1630/1766/373 1624/1760/373\nf 1624/1760/747 1630/1766/747 1629/1765/747\nf 1624/1760/747 1629/1765/747 1625/1761/747\nf 1642/1778/744 1641/1777/744 1628/1764/744\nf 1642/1778/744 1628/1764/744 1627/1763/744\nf 1643/1779/368 1644/1780/368 1645/1781/368\nf 1645/1781/748 1646/1782/748 1647/1783/748\nf 1647/1783/749 1648/1784/749 1643/1779/749\nf 1645/1781/750 1647/1783/750 1643/1779/750\nf 1649/1785/715 1650/1786/715 1651/1787/715\nf 1649/1785/715 1651/1787/715 1652/1788/715\nf 1653/1789/742 1654/1790/742 1633/1769/742\nf 1653/1789/742 1633/1769/742 1632/1768/742\nf 1655/1791/373 1653/1789/373 1632/1768/373\nf 1655/1791/373 1632/1768/373 1635/1771/373\nf 1654/1790/368 1656/1792/368 1636/1772/368\nf 1654/1790/368 1636/1772/368 1633/1769/368\nf 1657/1793/751 1658/1794/751 1659/1795/751\nf 1657/1793/751 1659/1795/751 1660/1796/751\nf 1645/1781/373 1644/1780/373 1658/1794/373\nf 1645/1781/373 1658/1794/373 1657/1793/373\nf 1644/1780/373 1643/1779/373 1649/1785/373\nf 1644/1780/373 1649/1785/373 1658/1794/373\nf 1655/1791/745 1656/1792/745 1646/1782/745\nf 1655/1791/745 1646/1782/745 1645/1781/745\nf 1635/1771/745 1636/1772/745 1656/1792/745\nf 1635/1771/745 1656/1792/745 1655/1791/745\nf 1660/1796/368 1646/1782/368 1656/1792/368\nf 1660/1796/368 1656/1792/368 1654/1790/368\nf 1645/1781/373 1657/1793/373 1653/1789/373\nf 1645/1781/373 1653/1789/373 1655/1791/373\nf 1657/1793/752 1660/1796/752 1654/1790/752\nf 1657/1793/752 1654/1790/752 1653/1789/752\nf 1646/1782/368 1660/1796/368 1659/1795/368\nf 1652/1788/368 1651/1787/368 1647/1783/368\nf 1646/1782/368 1659/1795/368 1652/1788/368\nf 1652/1788/368 1647/1783/368 1646/1782/368\nf 1643/1779/373 1648/1784/373 1650/1786/373\nf 1643/1779/373 1650/1786/373 1649/1785/373\nf 1648/1784/743 1647/1783/743 1651/1787/743\nf 1648/1784/743 1651/1787/743 1650/1786/743\nf 1658/1794/751 1649/1785/751 1652/1788/751\nf 1658/1794/751 1652/1788/751 1659/1795/751\nf 1661/1797/742 1662/1798/742 1663/1799/742\nf 1661/1797/742 1663/1799/742 1664/1800/742\nf 1662/1798/743 1665/1801/743 1666/1802/743\nf 1662/1798/743 1666/1802/743 1663/1799/743\nf 1665/1801/745 1667/1803/745 1668/1804/745\nf 1665/1801/745 1668/1804/745 1666/1802/745\nf 1667/1803/747 1661/1797/747 1664/1800/747\nf 1667/1803/747 1664/1800/747 1668/1804/747\nf 1662/1798/373 1661/1797/373 1667/1803/373\nf 1662/1798/373 1667/1803/373 1665/1801/373\nf 1666/1802/368 1668/1804/368 1664/1800/368\nf 1666/1802/368 1664/1800/368 1663/1799/368\nf 1669/1805/742 1670/1806/742 1671/1807/742\nf 1669/1805/742 1671/1807/742 1672/1808/742\nf 1672/1808/747 1671/1807/747 1673/1809/747\nf 1672/1808/747 1673/1809/747 1674/1810/747\nf 1674/1810/745 1673/1809/745 1675/1811/745\nf 1674/1810/745 1675/1811/745 1676/1812/745\nf 1676/1812/743 1675/1811/743 1670/1806/743\nf 1676/1812/743 1670/1806/743 1669/1805/743\nf 1672/1808/373 1674/1810/373 1676/1812/373\nf 1672/1808/373 1676/1812/373 1669/1805/373\nf 1673/1809/368 1671/1807/368 1670/1806/368\nf 1673/1809/368 1670/1806/368 1675/1811/368\nf 1677/1813/368 1678/1814/368 1679/1815/368\nf 1679/1815/739 1624/1760/739 1625/1761/739\nf 1625/1761/740 1680/1816/740 1677/1813/740\nf 1679/1815/741 1625/1761/741 1677/1813/741\nf 1681/1817/731 1682/1818/731 1629/1765/731\nf 1681/1817/731 1629/1765/731 1630/1766/731\nf 1683/1819/742 1684/1820/742 1685/1821/742\nf 1683/1819/742 1685/1821/742 1686/1822/742\nf 1684/1820/743 1687/1823/743 1688/1824/743\nf 1684/1820/743 1688/1824/743 1685/1821/743\nf 1689/1825/373 1687/1823/373 1684/1820/373\nf 1689/1825/373 1684/1820/373 1683/1819/373\nf 1686/1822/368 1685/1821/368 1688/1824/368\nf 1686/1822/368 1688/1824/368 1690/1826/368\nf 1691/1827/744 1692/1828/744 1693/1829/744\nf 1691/1827/744 1693/1829/744 1694/1830/744\nf 1677/1813/373 1691/1827/373 1694/1830/373\nf 1677/1813/373 1694/1830/373 1678/1814/373\nf 1678/1814/373 1694/1830/373 1681/1817/373\nf 1678/1814/373 1681/1817/373 1679/1815/373\nf 1689/1825/745 1677/1813/745 1680/1816/745\nf 1689/1825/745 1680/1816/745 1690/1826/745\nf 1687/1823/745 1689/1825/745 1690/1826/745\nf 1687/1823/745 1690/1826/745 1688/1824/745\nf 1692/1828/368 1686/1822/368 1690/1826/368\nf 1692/1828/368 1690/1826/368 1680/1816/368\nf 1677/1813/373 1689/1825/373 1683/1819/373\nf 1677/1813/373 1683/1819/373 1691/1827/373\nf 1691/1827/746 1683/1819/746 1686/1822/746\nf 1691/1827/746 1686/1822/746 1692/1828/746\nf 1693/1829/368 1692/1828/368 1680/1816/368\nf 1680/1816/368 1625/1761/368 1629/1765/368\nf 1682/1818/368 1693/1829/368 1680/1816/368\nf 1680/1816/368 1629/1765/368 1682/1818/368\nf 1679/1815/373 1681/1817/373 1630/1766/373\nf 1679/1815/373 1630/1766/373 1624/1760/373\nf 1694/1830/744 1693/1829/744 1682/1818/744\nf 1694/1830/744 1682/1818/744 1681/1817/744\nf 1695/1831/368 1696/1832/368 1697/1833/368\nf 1697/1833/748 1698/1834/748 1699/1835/748\nf 1699/1835/749 1700/1836/749 1695/1831/749\nf 1697/1833/750 1699/1835/750 1695/1831/750\nf 1701/1837/715 1702/1838/715 1703/1839/715\nf 1701/1837/715 1703/1839/715 1704/1840/715\nf 1705/1841/742 1706/1842/742 1685/1821/742\nf 1705/1841/742 1685/1821/742 1684/1820/742\nf 1707/1843/373 1705/1841/373 1684/1820/373\nf 1707/1843/373 1684/1820/373 1687/1823/373\nf 1706/1842/368 1708/1844/368 1688/1824/368\nf 1706/1842/368 1688/1824/368 1685/1821/368\nf 1709/1845/751 1710/1846/751 1711/1847/751\nf 1709/1845/751 1711/1847/751 1712/1848/751\nf 1697/1833/373 1696/1832/373 1710/1846/373\nf 1697/1833/373 1710/1846/373 1709/1845/373\nf 1696/1832/373 1695/1831/373 1701/1837/373\nf 1696/1832/373 1701/1837/373 1710/1846/373\nf 1707/1843/745 1708/1844/745 1698/1834/745\nf 1707/1843/745 1698/1834/745 1697/1833/745\nf 1687/1823/745 1688/1824/745 1708/1844/745\nf 1687/1823/745 1708/1844/745 1707/1843/745\nf 1712/1848/368 1698/1834/368 1708/1844/368\nf 1712/1848/368 1708/1844/368 1706/1842/368\nf 1697/1833/373 1709/1845/373 1705/1841/373\nf 1697/1833/373 1705/1841/373 1707/1843/373\nf 1709/1845/752 1712/1848/752 1706/1842/752\nf 1709/1845/752 1706/1842/752 1705/1841/752\nf 1698/1834/368 1712/1848/368 1711/1847/368\nf 1704/1840/368 1703/1839/368 1699/1835/368\nf 1698/1834/368 1711/1847/368 1704/1840/368\nf 1704/1840/368 1699/1835/368 1698/1834/368\nf 1695/1831/373 1700/1836/373 1702/1838/373\nf 1695/1831/373 1702/1838/373 1701/1837/373\nf 1700/1836/743 1699/1835/743 1703/1839/743\nf 1700/1836/743 1703/1839/743 1702/1838/743\nf 1710/1846/751 1701/1837/751 1704/1840/751\nf 1710/1846/751 1704/1840/751 1711/1847/751\nf 1713/1849/745 1714/1850/745 1715/1851/745\nf 1713/1849/745 1715/1851/745 1662/1798/745\nf 1662/1798/747 1715/1851/747 1716/1852/747\nf 1662/1798/747 1716/1852/747 1665/1801/747\nf 1665/1801/742 1716/1852/742 1717/1853/742\nf 1665/1801/742 1717/1853/742 1718/1854/742\nf 1718/1854/743 1717/1853/743 1714/1850/743\nf 1718/1854/743 1714/1850/743 1713/1849/743\nf 1662/1798/368 1665/1801/368 1718/1854/368\nf 1662/1798/368 1718/1854/368 1713/1849/368\nf 1716/1852/373 1715/1851/373 1714/1850/373\nf 1716/1852/373 1714/1850/373 1717/1853/373\nf 1719/1855/745 1720/1856/745 1721/1857/745\nf 1719/1855/745 1721/1857/745 1722/1858/745\nf 1720/1856/743 1723/1859/743 1724/1860/743\nf 1720/1856/743 1724/1860/743 1721/1857/743\nf 1723/1859/742 1725/1861/742 1726/1862/742\nf 1723/1859/742 1726/1862/742 1724/1860/742\nf 1725/1861/747 1719/1855/747 1722/1858/747\nf 1725/1861/747 1722/1858/747 1726/1862/747\nf 1720/1856/368 1719/1855/368 1725/1861/368\nf 1720/1856/368 1725/1861/368 1723/1859/368\nf 1724/1860/373 1726/1862/373 1722/1858/373\nf 1724/1860/373 1722/1858/373 1721/1857/373\nf 1927/2063/745 1928/2064/745 1929/2065/745\nf 1927/2063/745 1929/2065/745 1930/2066/745\nf 1930/2066/747 1929/2065/747 1931/2067/747\nf 1930/2066/747 1931/2067/747 1932/2068/747\nf 1932/2068/742 1931/2067/742 1933/2069/742\nf 1932/2068/742 1933/2069/742 1934/2070/742\nf 1934/2070/743 1933/2069/743 1928/2064/743\nf 1934/2070/743 1928/2064/743 1927/2063/743\nf 1930/2066/368 1932/2068/368 1934/2070/368\nf 1930/2066/368 1934/2070/368 1927/2063/368\nf 1931/2067/373 1929/2065/373 1928/2064/373\nf 1931/2067/373 1928/2064/373 1933/2069/373\nf 1935/2071/745 1936/2072/745 1937/2073/745\nf 1935/2071/745 1937/2073/745 1938/2074/745\nf 1936/2072/743 1939/2075/743 1940/2076/743\nf 1936/2072/743 1940/2076/743 1937/2073/743\nf 1939/2075/742 1941/2077/742 1942/2078/742\nf 1939/2075/742 1942/2078/742 1940/2076/742\nf 1941/2077/747 1935/2071/747 1938/2074/747\nf 1941/2077/747 1938/2074/747 1942/2078/747\nf 1936/2072/368 1935/2071/368 1941/2077/368\nf 1936/2072/368 1941/2077/368 1939/2075/368\nf 1940/2076/373 1942/2078/373 1938/2074/373\nf 1940/2076/373 1938/2074/373 1937/2073/373\nf 1943/2079/745 1944/2080/745 1945/2081/745\nf 1943/2079/745 1945/2081/745 1946/2082/745\nf 1946/2082/747 1945/2081/747 1947/2083/747\nf 1946/2082/747 1947/2083/747 1948/2084/747\nf 1948/2084/742 1947/2083/742 1949/2085/742\nf 1948/2084/742 1949/2085/742 1950/2086/742\nf 1950/2086/743 1949/2085/743 1944/2080/743\nf 1950/2086/743 1944/2080/743 1943/2079/743\nf 1951/2087/368 1952/2088/368 1953/2089/368\nf 1951/2087/368 1953/2089/368 1954/2090/368\nf 1943/2079/368 1946/2082/368 1955/2091/368\nf 1943/2079/368 1955/2091/368 1956/2092/368\nf 1951/2087/368 1955/2091/368 1946/2082/368\nf 1950/2086/368 1943/2079/368 1956/2092/368\nf 1954/2090/773 1953/2089/773 1957/2093/773\nf 1950/2086/368 1956/2092/368 1954/2090/368\nf 1951/2087/368 1946/2082/368 1948/2084/368\nf 1958/2094/373 1952/2088/373 1951/2087/373\nf 1950/2086/368 1954/2090/368 1957/2093/368\nf 1958/2094/368 1951/2087/368 1948/2084/368\nf 1950/2086/368 1957/2093/368 1958/2094/368\nf 1948/2084/368 1950/2086/368 1958/2094/368\nf 1959/2095/373 1960/2096/373 1944/2080/373\nf 1947/2083/373 1945/2081/373 1961/2097/373\nf 1962/2098/773 1963/2099/773 1964/2100/773\nf 1947/2083/373 1961/2097/373 1962/2098/373\nf 1959/2095/373 1944/2080/373 1949/2085/373\nf 1965/2101/368 1966/2102/368 1959/2095/368\nf 1947/2083/373 1962/2098/373 1964/2100/373\nf 1965/2101/373 1959/2095/373 1949/2085/373\nf 1947/2083/373 1964/2100/373 1965/2101/373\nf 1949/2085/373 1947/2083/373 1965/2101/373\nf 1961/2097/373 1945/2081/373 1944/2080/373\nf 1961/2097/373 1944/2080/373 1960/2096/373\nf 1963/2099/373 1962/2098/373 1959/2095/373\nf 1963/2099/373 1959/2095/373 1966/2102/373\nf 1954/2090/747 1956/2092/747 1960/2096/747\nf 1954/2090/747 1960/2096/747 1959/2095/747\nf 1960/2096/742 1956/2092/742 1955/2091/742\nf 1960/2096/742 1955/2091/742 1961/2097/742\nf 1961/2097/743 1955/2091/743 1951/2087/743\nf 1961/2097/743 1951/2087/743 1962/2098/743\nf 1951/2087/745 1954/2090/745 1959/2095/745\nf 1951/2087/745 1959/2095/745 1962/2098/745\nf 1957/2093/747 1953/2089/747 1966/2102/747\nf 1957/2093/747 1966/2102/747 1965/2101/747\nf 1958/2094/745 1957/2093/745 1965/2101/745\nf 1958/2094/745 1965/2101/745 1964/2100/745\nf 1963/2099/743 1952/2088/743 1958/2094/743\nf 1963/2099/743 1958/2094/743 1964/2100/743\nf 1966/2102/742 1953/2089/742 1952/2088/742\nf 1966/2102/742 1952/2088/742 1963/2099/742\ng cf_Material.002\nusemtl Material.002\nf 461/461/357 462/462/357 463/463/357\nf 463/463/358 464/464/358 465/465/358\nf 463/463/358 465/465/358 461/461/358\nf 466/466/359 467/467/359 468/468/359\nf 468/468/360 469/469/360 470/470/360\nf 468/468/359 470/470/359 466/466/359\nf 467/467/361 466/466/361 461/461/361\nf 467/467/361 461/461/361 465/465/361\nf 471/471/362 472/472/362 465/465/362\nf 465/465/358 464/464/358 473/473/358\nf 465/465/363 473/473/363 471/471/363\nf 474/474/364 475/475/364 468/468/364\nf 468/468/359 467/467/359 476/476/359\nf 468/468/365 476/476/365 474/474/365\nf 464/464/366 468/468/366 475/475/366\nf 464/464/367 475/475/367 473/473/367\nf 473/473/368 475/475/368 474/474/368\nf 473/473/368 474/474/368 471/471/368\nf 476/476/369 472/472/369 471/471/369\nf 476/476/369 471/471/369 474/474/369\nf 467/467/361 465/465/361 472/472/361\nf 467/467/370 472/472/370 476/476/370\nf 461/461/371 466/466/371 470/470/371\nf 461/461/372 470/470/372 462/462/372\nf 469/469/373 463/463/373 462/462/373\nf 469/469/373 462/462/373 470/470/373\nf 477/477/374 478/478/374 479/479/374\nf 479/479/374 480/480/374 481/481/374\nf 479/479/374 481/481/374 477/477/374\nf 482/482/375 483/483/375 484/484/375\nf 484/484/376 485/485/376 486/486/376\nf 484/484/375 486/486/375 482/482/375\nf 483/483/377 482/482/377 477/477/377\nf 483/483/377 477/477/377 481/481/377\nf 487/487/378 488/488/378 481/481/378\nf 481/481/374 480/480/374 489/489/374\nf 481/481/379 489/489/379 487/487/379\nf 490/490/380 491/491/380 484/484/380\nf 484/484/375 483/483/375 492/492/375\nf 484/484/381 492/492/381 490/490/381\nf 480/480/382 484/484/382 491/491/382\nf 480/480/382 491/491/382 489/489/382\nf 489/489/368 491/491/368 490/490/368\nf 489/489/368 490/490/368 487/487/368\nf 492/492/383 488/488/383 487/487/383\nf 492/492/384 487/487/384 490/490/384\nf 483/483/385 481/481/385 488/488/385\nf 483/483/377 488/488/377 492/492/377\nf 477/477/386 482/482/386 486/486/386\nf 477/477/387 486/486/387 478/478/387\nf 485/485/373 479/479/373 478/478/373\nf 485/485/373 478/478/373 486/486/373\nf 493/493/388 494/494/388 495/495/388\nf 495/495/389 496/496/389 497/497/389\nf 495/495/389 497/497/389 493/493/389\nf 498/498/390 499/499/390 500/500/390\nf 498/498/390 500/500/390 501/501/390\nf 502/502/391 503/503/391 504/504/391\nf 502/502/391 504/504/391 505/505/391\nf 506/506/373 507/507/373 508/508/373\nf 506/506/373 508/508/373 495/495/373\nf 509/509/373 510/510/373 511/511/373\nf 509/509/373 511/511/373 512/512/373\nf 513/513/373 514/514/373 515/515/373\nf 513/513/373 515/515/373 516/516/373\nf 517/517/392 518/518/392 519/519/392\nf 517/517/392 519/519/392 520/520/392\nf 521/521/393 522/522/393 523/523/393\nf 521/521/393 523/523/393 524/524/393\nf 524/524/394 523/523/394 525/525/394\nf 524/524/394 525/525/394 526/526/394\nf 526/526/391 525/525/391 503/503/391\nf 526/526/391 503/503/391 502/502/391\nf 527/527/395 528/528/395 529/529/395\nf 527/527/396 529/529/396 530/530/396\nf 531/531/391 532/532/391 522/522/391\nf 531/531/391 522/522/391 521/521/391\nf 533/533/390 534/534/390 528/528/390\nf 533/533/390 528/528/390 527/527/390\nf 535/535/395 536/536/395 534/534/395\nf 535/535/395 534/534/395 533/533/395\nf 537/537/396 538/538/396 536/536/396\nf 537/537/396 536/536/396 535/535/396\nf 501/501/390 500/500/390 538/538/390\nf 501/501/390 538/538/390 537/537/390\nf 539/539/373 509/509/373 512/512/373\nf 539/539/373 512/512/373 540/540/373\nf 540/540/373 512/512/373 513/513/373\nf 540/540/373 513/513/373 541/541/373\nf 541/541/373 513/513/373 516/516/373\nf 541/541/373 516/516/373 542/542/373\nf 542/542/373 516/516/373 506/506/373\nf 542/542/373 506/506/373 543/543/373\nf 508/508/389 544/544/389 545/545/389\nf 545/545/397 546/546/397 547/547/397\nf 545/545/398 547/547/398 508/508/398\nf 515/515/373 548/548/373 549/549/373\nf 515/515/373 549/549/373 507/507/373\nf 514/514/373 550/550/373 548/548/373\nf 514/514/373 548/548/373 515/515/373\nf 511/511/373 551/551/373 550/550/373\nf 511/511/373 550/550/373 514/514/373\nf 510/510/373 552/552/373 551/551/373\nf 510/510/373 551/551/373 511/511/373\nf 553/553/399 554/554/399 555/555/399\nf 553/553/399 555/555/399 556/556/399\nf 557/557/396 558/558/396 497/497/396\nf 557/557/396 497/497/396 559/559/396\nf 560/560/368 547/547/368 546/546/368\nf 560/560/368 546/546/368 561/561/368\nf 559/559/368 497/497/368 496/496/368\nf 559/559/368 496/496/368 562/562/368\nf 562/562/368 496/496/368 547/547/368\nf 562/562/368 547/547/368 560/560/368\nf 563/563/368 564/564/368 565/565/368\nf 563/563/368 565/565/368 566/566/368\nf 567/567/368 568/568/368 569/569/368\nf 567/567/368 569/569/368 570/570/368\nf 571/571/368 572/572/368 563/563/368\nf 563/563/368 573/573/368 574/574/368\nf 563/563/368 574/574/368 571/571/368\nf 572/572/368 575/575/368 564/564/368\nf 572/572/368 564/564/368 563/563/368\nf 575/575/368 576/576/368 567/567/368\nf 575/575/368 567/567/368 564/564/368\nf 576/576/368 577/577/368 568/568/368\nf 576/576/368 568/568/368 567/567/368\nf 577/577/368 559/559/368 562/562/368\nf 577/577/368 562/562/368 568/568/368\nf 578/578/368 566/566/368 554/554/368\nf 554/554/368 553/553/368 579/579/368\nf 554/554/368 579/579/368 578/578/368\nf 566/566/368 565/565/368 580/580/368\nf 566/566/368 580/580/368 554/554/368\nf 565/565/368 570/570/368 581/581/368\nf 565/565/368 581/581/368 580/580/368\nf 570/570/368 569/569/368 582/582/368\nf 570/570/368 582/582/368 581/581/368\nf 569/569/368 560/560/368 561/561/368\nf 569/569/368 561/561/368 582/582/368\nf 583/583/395 572/572/395 571/571/395\nf 583/583/400 571/571/400 584/584/400\nf 583/583/396 585/585/396 575/575/396\nf 583/583/396 575/575/396 572/572/396\nf 585/585/390 586/586/390 576/576/390\nf 585/585/390 576/576/390 575/575/390\nf 586/586/390 587/587/390 577/577/390\nf 586/586/390 577/577/390 576/576/390\nf 587/587/395 557/557/395 559/559/395\nf 587/587/395 559/559/395 577/577/395\nf 588/588/394 589/589/394 561/561/394\nf 588/588/394 561/561/394 546/546/394\nf 589/589/393 590/590/393 582/582/393\nf 589/589/393 582/582/393 561/561/393\nf 590/590/391 591/591/391 581/581/391\nf 590/590/391 581/581/391 582/582/391\nf 591/591/391 592/592/391 580/580/391\nf 591/591/391 580/580/391 581/581/391\nf 592/592/394 555/555/394 554/554/394\nf 592/592/394 554/554/394 580/580/394\nf 498/498/368 501/501/368 589/589/368\nf 498/498/368 589/589/368 588/588/368\nf 507/507/373 549/549/373 544/544/373\nf 507/507/373 544/544/373 508/508/373\nf 543/543/373 506/506/373 495/495/373\nf 543/543/373 495/495/373 494/494/373\nf 593/593/373 594/594/373 509/509/373\nf 509/509/373 539/539/373 595/595/373\nf 509/509/373 595/595/373 593/593/373\nf 519/519/394 518/518/394 532/532/394\nf 519/519/394 532/532/394 531/531/394\nf 520/520/368 519/519/368 531/531/368\nf 531/531/368 583/583/368 584/584/368\nf 531/531/368 584/584/368 520/520/368\nf 596/596/373 597/597/373 552/552/373\nf 552/552/373 510/510/373 598/598/373\nf 552/552/373 598/598/373 596/596/373\nf 599/599/392 530/530/392 529/529/392\nf 599/599/392 529/529/392 600/600/392\nf 505/505/389 504/504/389 493/493/389\nf 493/493/389 497/497/389 558/558/389\nf 493/493/389 558/558/389 505/505/389\nf 495/495/389 508/508/389 547/547/389\nf 495/495/389 547/547/389 496/496/389\nf 556/556/368 555/555/368 527/527/368\nf 527/527/368 530/530/368 599/599/368\nf 527/527/368 599/599/368 556/556/368\nf 533/533/368 527/527/368 555/555/368\nf 533/533/368 555/555/368 592/592/368\nf 535/535/368 533/533/368 592/592/368\nf 535/535/368 592/592/368 591/591/368\nf 537/537/368 535/535/368 591/591/368\nf 537/537/368 591/591/368 590/590/368\nf 501/501/368 537/537/368 590/590/368\nf 501/501/368 590/590/368 589/589/368\nf 502/502/368 505/505/368 558/558/368\nf 502/502/368 558/558/368 557/557/368\nf 526/526/368 502/502/368 557/557/368\nf 526/526/368 557/557/368 587/587/368\nf 524/524/368 526/526/368 587/587/368\nf 524/524/368 587/587/368 586/586/368\nf 521/521/368 524/524/368 586/586/368\nf 521/521/368 586/586/368 585/585/368\nf 531/531/368 521/521/368 585/585/368\nf 531/531/368 585/585/368 583/583/368\nf 573/573/401 563/563/401 509/509/401\nf 573/573/401 509/509/401 594/594/401\nf 513/513/390 512/512/390 564/564/390\nf 513/513/390 564/564/390 567/567/390\nf 506/506/396 516/516/396 568/568/396\nf 506/506/396 568/568/396 562/562/396\nf 598/598/402 510/510/402 566/566/402\nf 598/598/402 566/566/402 578/578/402\nf 511/511/391 514/514/391 570/570/391\nf 511/511/391 570/570/391 565/565/391\nf 515/515/394 507/507/394 560/560/394\nf 515/515/394 560/560/394 569/569/394\nf 510/510/392 509/509/392 563/563/392\nf 510/510/392 563/563/392 566/566/392\nf 512/512/389 511/511/389 565/565/389\nf 512/512/389 565/565/389 564/564/389\nf 514/514/392 513/513/392 567/567/392\nf 514/514/392 567/567/392 570/570/392\nf 516/516/389 515/515/389 569/569/389\nf 516/516/389 569/569/389 568/568/389\nf 507/507/392 506/506/392 562/562/392\nf 507/507/392 562/562/392 560/560/392\nf 544/544/389 499/499/389 545/545/389\nf 529/529/392 601/601/392 600/600/392\nf 504/504/389 494/494/389 493/493/389\nf 602/602/392 518/518/392 517/517/392\nf 597/597/403 601/601/403 529/529/403\nf 529/529/403 528/528/403 552/552/403\nf 529/529/404 552/552/404 597/597/404\nf 543/543/405 494/494/405 504/504/405\nf 543/543/406 504/504/406 503/503/406\nf 544/544/407 549/549/407 500/500/407\nf 544/544/408 500/500/408 499/499/408\nf 549/549/409 548/548/409 538/538/409\nf 549/549/407 538/538/407 500/500/407\nf 548/548/407 550/550/407 536/536/407\nf 548/548/410 536/536/410 538/538/410\nf 550/550/408 551/551/408 534/534/408\nf 550/550/407 534/534/407 536/536/407\nf 551/551/408 552/552/408 528/528/408\nf 551/551/407 528/528/407 534/534/407\nf 602/602/411 595/595/411 539/539/411\nf 539/539/405 532/532/405 518/518/405\nf 539/539/412 518/518/412 602/602/412\nf 539/539/413 540/540/413 522/522/413\nf 539/539/406 522/522/406 532/532/406\nf 540/540/414 541/541/414 523/523/414\nf 540/540/415 523/523/415 522/522/415\nf 541/541/414 542/542/414 525/525/414\nf 541/541/411 525/525/411 523/523/411\nf 542/542/411 543/543/411 503/503/411\nf 542/542/414 503/503/414 525/525/414\nf 545/545/389 499/499/389 498/498/389\nf 498/498/398 588/588/398 546/546/398\nf 498/498/389 546/546/389 545/545/389\nf 520/520/416 584/584/416 571/571/416\nf 571/571/417 574/574/417 593/593/417\nf 593/593/417 595/595/417 602/602/417\nf 517/517/417 520/520/417 571/571/417\nf 593/593/418 602/602/418 517/517/418\nf 571/571/419 593/593/419 517/517/419\nf 594/594/420 593/593/420 574/574/420\nf 594/594/421 574/574/421 573/573/421\nf 578/578/422 579/579/422 596/596/422\nf 578/578/423 596/596/423 598/598/423\nf 596/596/424 579/579/424 553/553/424\nf 553/553/425 556/556/425 599/599/425\nf 600/600/424 601/601/424 597/597/424\nf 553/553/424 599/599/424 600/600/424\nf 597/597/426 596/596/426 553/553/426\nf 553/553/427 600/600/427 597/597/427\nf 603/603/428 604/604/428 605/605/428\nf 603/603/428 605/605/428 606/606/428\nf 606/606/429 605/605/429 607/607/429\nf 606/606/429 607/607/429 608/608/429\nf 608/608/430 607/607/430 609/609/430\nf 608/608/430 609/609/430 610/610/430\nf 610/610/431 609/609/431 611/611/431\nf 610/610/431 611/611/431 612/612/431\nf 612/612/432 611/611/432 613/613/432\nf 612/612/433 613/613/433 614/614/433\nf 614/614/434 613/613/434 615/615/434\nf 614/614/435 615/615/435 616/616/435\nf 616/616/436 615/615/436 617/617/436\nf 616/616/436 617/617/436 618/618/436\nf 618/618/437 617/617/437 619/619/437\nf 618/618/437 619/619/437 620/620/437\nf 620/620/438 619/619/438 621/621/438\nf 620/620/439 621/621/439 622/622/439\nf 622/622/440 621/621/440 623/623/440\nf 622/622/440 623/623/440 624/624/440\nf 624/624/441 623/623/441 625/625/441\nf 624/624/441 625/625/441 626/626/441\nf 626/626/442 625/625/442 627/627/442\nf 626/626/442 627/627/442 628/628/442\nf 628/628/443 627/627/443 629/629/443\nf 628/628/444 629/629/444 630/630/444\nf 630/630/445 629/629/445 631/631/445\nf 630/630/445 631/631/445 632/632/445\nf 632/632/446 631/631/446 633/633/446\nf 632/632/447 633/633/447 634/634/447\nf 634/634/375 633/633/375 604/604/375\nf 634/634/380 604/604/380 603/603/380\nf 635/635/373 636/636/373 605/605/373\nf 635/635/373 605/605/373 604/604/373\nf 636/636/373 637/637/373 607/607/373\nf 636/636/373 607/607/373 605/605/373\nf 637/637/373 638/638/373 609/609/373\nf 637/637/373 609/609/373 607/607/373\nf 638/638/373 639/639/373 611/611/373\nf 638/638/373 611/611/373 609/609/373\nf 639/639/373 640/640/373 613/613/373\nf 639/639/373 613/613/373 611/611/373\nf 640/640/373 641/641/373 615/615/373\nf 640/640/373 615/615/373 613/613/373\nf 641/641/373 642/642/373 617/617/373\nf 641/641/373 617/617/373 615/615/373\nf 642/642/373 643/643/373 619/619/373\nf 642/642/373 619/619/373 617/617/373\nf 643/643/373 644/644/373 621/621/373\nf 643/643/373 621/621/373 619/619/373\nf 644/644/373 645/645/373 623/623/373\nf 644/644/373 623/623/373 621/621/373\nf 645/645/373 646/646/373 625/625/373\nf 645/645/373 625/625/373 623/623/373\nf 646/646/373 647/647/373 627/627/373\nf 646/646/373 627/627/373 625/625/373\nf 647/647/373 648/648/373 629/629/373\nf 647/647/373 629/629/373 627/627/373\nf 648/648/373 649/649/373 631/631/373\nf 648/648/373 631/631/373 629/629/373\nf 649/649/373 650/650/373 633/633/373\nf 649/649/373 633/633/373 631/631/373\nf 650/650/373 635/635/373 604/604/373\nf 650/650/373 604/604/373 633/633/373\nf 650/650/448 649/649/448 651/651/448\nf 650/650/449 651/651/449 652/652/449\nf 653/653/373 654/654/373 655/655/373\nf 655/655/373 656/656/373 657/657/373\nf 657/657/373 652/652/373 651/651/373\nf 651/651/373 658/658/373 659/659/373\nf 659/659/373 660/660/373 661/661/373\nf 661/661/373 662/662/373 663/663/373\nf 661/661/373 663/663/373 664/664/373\nf 653/653/373 655/655/373 657/657/373\nf 665/665/373 653/653/373 657/657/373\nf 659/659/373 661/661/373 664/664/373\nf 659/659/373 664/664/373 666/666/373\nf 667/667/373 665/665/373 657/657/373\nf 668/668/373 667/667/373 657/657/373\nf 651/651/373 659/659/373 666/666/373\nf 651/651/373 666/666/373 669/669/373\nf 668/668/373 657/657/373 651/651/373\nf 651/651/373 669/669/373 668/668/373\nf 670/670/373 662/662/373 661/661/373\nf 661/661/373 671/671/373 672/672/373\nf 672/672/373 673/673/373 674/674/373\nf 674/674/373 675/675/373 676/676/373\nf 676/676/373 677/677/373 655/655/373\nf 655/655/373 654/654/373 678/678/373\nf 655/655/373 678/678/373 679/679/373\nf 670/670/373 661/661/373 672/672/373\nf 680/680/373 670/670/373 672/672/373\nf 676/676/373 655/655/373 679/679/373\nf 676/676/373 679/679/373 681/681/373\nf 682/682/373 680/680/373 672/672/373\nf 683/683/373 682/682/373 672/672/373\nf 674/674/373 676/676/373 681/681/373\nf 674/674/373 681/681/373 684/684/373\nf 683/683/373 672/672/373 674/674/373\nf 674/674/373 684/684/373 683/683/373\nf 643/643/450 642/642/450 673/673/450\nf 643/643/381 673/673/381 672/672/381\nf 636/636/451 635/635/451 657/657/451\nf 636/636/451 657/657/451 656/656/451\nf 635/635/452 650/650/452 652/652/452\nf 635/635/378 652/652/378 657/657/378\nf 644/644/453 643/643/453 672/672/453\nf 644/644/454 672/672/454 671/671/454\nf 637/637/455 636/636/455 656/656/455\nf 637/637/455 656/656/455 655/655/455\nf 645/645/456 644/644/456 671/671/456\nf 645/645/456 671/671/456 661/661/456\nf 638/638/457 637/637/457 655/655/457\nf 638/638/458 655/655/458 677/677/458\nf 646/646/459 645/645/459 661/661/459\nf 646/646/460 661/661/460 660/660/460\nf 639/639/382 638/638/382 677/677/382\nf 639/639/461 677/677/461 676/676/461\nf 647/647/377 646/646/377 660/660/377\nf 647/647/462 660/660/462 659/659/462\nf 640/640/463 639/639/463 676/676/463\nf 640/640/443 676/676/443 675/675/443\nf 648/648/464 647/647/464 659/659/464\nf 648/648/465 659/659/465 658/658/465\nf 641/641/466 640/640/466 675/675/466\nf 641/641/466 675/675/466 674/674/466\nf 649/649/467 648/648/467 658/658/467\nf 649/649/467 658/658/467 651/651/467\nf 642/642/446 641/641/446 674/674/446\nf 642/642/446 674/674/446 673/673/446\nf 685/685/368 634/634/368 603/603/368\nf 603/603/368 606/606/368 608/608/368\nf 608/608/368 610/610/368 612/612/368\nf 612/612/368 614/614/368 616/616/368\nf 616/616/368 618/618/368 686/686/368\nf 616/616/368 686/686/368 687/687/368\nf 688/688/368 685/685/368 603/603/368\nf 689/689/368 688/688/368 603/603/368\nf 616/616/368 687/687/368 690/690/368\nf 616/616/368 690/690/368 691/691/368\nf 689/689/368 603/603/368 608/608/368\nf 692/692/368 689/689/368 608/608/368\nf 612/612/368 616/616/368 691/691/368\nf 612/612/368 691/691/368 693/693/368\nf 694/694/368 692/692/368 608/608/368\nf 612/612/368 693/693/368 694/694/368\nf 608/608/368 612/612/368 694/694/368\nf 695/695/368 686/686/368 618/618/368\nf 618/618/368 620/620/368 622/622/368\nf 622/622/368 624/624/368 626/626/368\nf 626/626/368 628/628/368 630/630/368\nf 630/630/368 632/632/368 634/634/368\nf 634/634/368 685/685/368 696/696/368\nf 634/634/368 696/696/368 697/697/368\nf 695/695/368 618/618/368 622/622/368\nf 698/698/368 695/695/368 622/622/368\nf 630/630/368 634/634/368 697/697/368\nf 630/630/368 697/697/368 699/699/368\nf 700/700/368 698/698/368 622/622/368\nf 701/701/368 700/700/368 622/622/368\nf 626/626/368 630/630/368 699/699/368\nf 626/626/368 699/699/368 702/702/368\nf 701/701/368 622/622/368 626/626/368\nf 626/626/368 702/702/368 701/701/368\nf 690/690/468 687/687/468 683/683/468\nf 690/690/468 683/683/468 684/684/468\nf 695/695/469 682/682/469 683/683/469\nf 683/683/470 687/687/470 686/686/470\nf 683/683/471 686/686/471 695/695/471\nf 682/682/472 695/695/472 698/698/472\nf 682/682/473 698/698/473 680/680/473\nf 698/698/474 700/700/474 670/670/474\nf 698/698/474 670/670/474 680/680/474\nf 670/670/475 700/700/475 701/701/475\nf 701/701/476 663/663/476 662/662/476\nf 701/701/477 662/662/477 670/670/477\nf 702/702/478 664/664/478 663/663/478\nf 702/702/479 663/663/479 701/701/479\nf 699/699/480 666/666/480 664/664/480\nf 699/699/418 664/664/418 702/702/418\nf 697/697/481 669/669/481 666/666/481\nf 697/697/481 666/666/481 699/699/481\nf 696/696/482 668/668/482 669/669/482\nf 696/696/482 669/669/482 697/697/482\nf 667/667/483 668/668/483 696/696/483\nf 685/685/424 688/688/424 667/667/424\nf 696/696/427 685/685/427 667/667/427\nf 689/689/484 665/665/484 667/667/484\nf 689/689/485 667/667/485 688/688/485\nf 692/692/486 653/653/486 665/665/486\nf 692/692/486 665/665/486 689/689/486\nf 692/692/487 694/694/487 678/678/487\nf 654/654/487 653/653/487 692/692/487\nf 678/678/488 654/654/488 692/692/488\nf 679/679/489 678/678/489 694/694/489\nf 679/679/489 694/694/489 693/693/489\nf 679/679/490 693/693/490 691/691/490\nf 679/679/491 691/691/491 681/681/491\nf 691/691/492 690/690/492 684/684/492\nf 691/691/492 684/684/492 681/681/492\nf 703/703/493 705/705/493 704/704/493\nf 705/705/494 707/707/494 706/706/494\nf 705/705/494 703/703/494 707/707/494\nf 708/708/495 710/710/495 709/709/495\nf 710/710/496 712/712/496 711/711/496\nf 710/710/497 708/708/497 712/712/497\nf 709/709/498 703/703/498 708/708/498\nf 709/709/498 707/707/498 703/703/498\nf 713/713/493 707/707/493 714/714/493\nf 707/707/494 715/715/494 706/706/494\nf 707/707/499 713/713/499 715/715/499\nf 716/716/500 710/710/500 717/717/500\nf 710/710/495 718/718/495 709/709/495\nf 710/710/497 716/716/497 718/718/497\nf 706/706/501 717/717/501 710/710/501\nf 706/706/502 715/715/502 717/717/502\nf 715/715/368 716/716/368 717/717/368\nf 715/715/368 713/713/368 716/716/368\nf 718/718/503 713/713/503 714/714/503\nf 718/718/503 716/716/503 713/713/503\nf 709/709/504 714/714/504 707/707/504\nf 709/709/504 718/718/504 714/714/504\nf 703/703/505 712/712/505 708/708/505\nf 703/703/506 704/704/506 712/712/506\nf 711/711/373 704/704/373 705/705/373\nf 711/711/373 712/712/373 704/704/373\nf 719/719/507 721/721/507 720/720/507\nf 721/721/508 723/723/508 722/722/508\nf 721/721/508 719/719/508 723/723/508\nf 724/724/509 726/726/509 725/725/509\nf 726/726/510 728/728/510 727/727/510\nf 726/726/509 724/724/509 728/728/509\nf 725/725/511 719/719/511 724/724/511\nf 725/725/511 723/723/511 719/719/511\nf 729/729/512 723/723/512 730/730/512\nf 723/723/508 731/731/508 722/722/508\nf 723/723/513 729/729/513 731/731/513\nf 732/732/514 726/726/514 733/733/514\nf 726/726/509 734/734/509 725/725/509\nf 726/726/510 732/732/510 734/734/510\nf 722/722/515 733/733/515 726/726/515\nf 722/722/515 731/731/515 733/733/515\nf 731/731/368 732/732/368 733/733/368\nf 731/731/368 729/729/368 732/732/368\nf 734/734/516 729/729/516 730/730/516\nf 734/734/516 732/732/516 729/729/516\nf 725/725/511 730/730/511 723/723/511\nf 725/725/511 734/734/511 730/730/511\nf 719/719/517 728/728/517 724/724/517\nf 719/719/517 720/720/517 728/728/517\nf 727/727/373 720/720/373 721/721/373\nf 727/727/373 728/728/373 720/720/373\nf 735/735/391 737/737/391 736/736/391\nf 737/737/391 739/739/391 738/738/391\nf 737/737/391 735/735/391 739/739/391\nf 740/740/392 742/742/392 741/741/392\nf 740/740/392 743/743/392 742/742/392\nf 744/744/389 746/746/389 745/745/389\nf 744/744/389 747/747/389 746/746/389\nf 748/748/373 750/750/373 749/749/373\nf 748/748/373 737/737/373 750/750/373\nf 751/751/373 753/753/373 752/752/373\nf 751/751/373 754/754/373 753/753/373\nf 755/755/373 757/757/373 756/756/373\nf 755/755/373 758/758/373 757/757/373\nf 759/759/390 761/761/390 760/760/390\nf 759/759/390 762/762/390 761/761/390\nf 763/763/398 765/765/398 764/764/398\nf 763/763/398 766/766/398 765/765/398\nf 766/766/518 767/767/518 765/765/518\nf 766/766/518 768/768/518 767/767/518\nf 768/768/389 745/745/389 767/767/389\nf 768/768/389 744/744/389 745/745/389\nf 769/769/519 771/771/519 770/770/519\nf 769/769/520 772/772/520 771/771/520\nf 773/773/389 764/764/389 774/774/389\nf 773/773/389 763/763/389 764/764/389\nf 775/775/392 770/770/392 776/776/392\nf 775/775/392 769/769/392 770/770/392\nf 777/777/519 776/776/519 778/778/519\nf 777/777/519 775/775/519 776/776/519\nf 779/779/520 778/778/520 780/780/520\nf 779/779/520 777/777/520 778/778/520\nf 743/743/392 780/780/392 742/742/392\nf 743/743/392 779/779/392 780/780/392\nf 781/781/373 754/754/373 751/751/373\nf 781/781/373 782/782/373 754/754/373\nf 782/782/373 755/755/373 754/754/373\nf 782/782/373 783/783/373 755/755/373\nf 783/783/373 758/758/373 755/755/373\nf 783/783/373 784/784/373 758/758/373\nf 784/784/373 748/748/373 758/758/373\nf 784/784/373 785/785/373 748/748/373\nf 750/750/391 787/787/391 786/786/391\nf 787/787/521 789/789/521 788/788/521\nf 787/787/393 750/750/393 789/789/393\nf 757/757/373 791/791/373 790/790/373\nf 757/757/373 749/749/373 791/791/373\nf 756/756/373 790/790/373 792/792/373\nf 756/756/373 757/757/373 790/790/373\nf 753/753/373 792/792/373 793/793/373\nf 753/753/373 756/756/373 792/792/373\nf 752/752/373 793/793/373 794/794/373\nf 752/752/373 753/753/373 793/793/373\nf 795/795/522 797/797/522 796/796/522\nf 795/795/522 798/798/522 797/797/522\nf 799/799/520 739/739/520 800/800/520\nf 799/799/520 801/801/520 739/739/520\nf 802/802/368 788/788/368 789/789/368\nf 802/802/368 803/803/368 788/788/368\nf 801/801/368 738/738/368 739/739/368\nf 801/801/368 804/804/368 738/738/368\nf 804/804/368 789/789/368 738/738/368\nf 804/804/368 802/802/368 789/789/368\nf 805/805/368 807/807/368 806/806/368\nf 805/805/368 808/808/368 807/807/368\nf 809/809/368 811/811/368 810/810/368\nf 809/809/368 812/812/368 811/811/368\nf 813/813/368 805/805/368 814/814/368\nf 805/805/368 816/816/368 815/815/368\nf 805/805/368 813/813/368 816/816/368\nf 814/814/368 806/806/368 817/817/368\nf 814/814/368 805/805/368 806/806/368\nf 817/817/368 809/809/368 818/818/368\nf 817/817/368 806/806/368 809/809/368\nf 818/818/368 810/810/368 819/819/368\nf 818/818/368 809/809/368 810/810/368\nf 819/819/368 804/804/368 801/801/368\nf 819/819/368 810/810/368 804/804/368\nf 820/820/368 796/796/368 808/808/368\nf 796/796/368 821/821/368 795/795/368\nf 796/796/368 820/820/368 821/821/368\nf 808/808/368 822/822/368 807/807/368\nf 808/808/368 796/796/368 822/822/368\nf 807/807/368 823/823/368 812/812/368\nf 807/807/368 822/822/368 823/823/368\nf 812/812/368 824/824/368 811/811/368\nf 812/812/368 823/823/368 824/824/368\nf 811/811/368 803/803/368 802/802/368\nf 811/811/368 824/824/368 803/803/368\nf 825/825/519 813/813/519 814/814/519\nf 825/825/523 826/826/523 813/813/523\nf 825/825/520 817/817/520 827/827/520\nf 825/825/520 814/814/520 817/817/520\nf 827/827/392 818/818/392 828/828/392\nf 827/827/392 817/817/392 818/818/392\nf 828/828/392 819/819/392 829/829/392\nf 828/828/392 818/818/392 819/819/392\nf 829/829/519 801/801/519 799/799/519\nf 829/829/519 819/819/519 801/801/519\nf 830/830/518 803/803/518 831/831/518\nf 830/830/518 788/788/518 803/803/518\nf 831/831/398 824/824/398 832/832/398\nf 831/831/398 803/803/398 824/824/398\nf 832/832/389 823/823/389 833/833/389\nf 832/832/389 824/824/389 823/823/389\nf 833/833/389 822/822/389 834/834/389\nf 833/833/389 823/823/389 822/822/389\nf 834/834/518 796/796/518 797/797/518\nf 834/834/518 822/822/518 796/796/518\nf 740/740/368 831/831/368 743/743/368\nf 740/740/368 830/830/368 831/831/368\nf 749/749/373 786/786/373 791/791/373\nf 749/749/373 750/750/373 786/786/373\nf 785/785/373 737/737/373 748/748/373\nf 785/785/373 736/736/373 737/737/373\nf 835/835/373 751/751/373 836/836/373\nf 751/751/373 837/837/373 781/781/373\nf 751/751/373 835/835/373 837/837/373\nf 761/761/518 774/774/518 760/760/518\nf 761/761/518 773/773/518 774/774/518\nf 762/762/368 773/773/368 761/761/368\nf 773/773/368 826/826/368 825/825/368\nf 773/773/368 762/762/368 826/826/368\nf 838/838/373 794/794/373 839/839/373\nf 794/794/373 840/840/373 752/752/373\nf 794/794/373 838/838/373 840/840/373\nf 841/841/390 771/771/390 772/772/390\nf 841/841/390 842/842/390 771/771/390\nf 747/747/391 735/735/391 746/746/391\nf 735/735/391 800/800/391 739/739/391\nf 735/735/391 747/747/391 800/800/391\nf 737/737/391 789/789/391 750/750/391\nf 737/737/391 738/738/391 789/789/391\nf 798/798/368 769/769/368 797/797/368\nf 769/769/368 841/841/368 772/772/368\nf 769/769/368 798/798/368 841/841/368\nf 775/775/368 797/797/368 769/769/368\nf 775/775/368 834/834/368 797/797/368\nf 777/777/368 834/834/368 775/775/368\nf 777/777/368 833/833/368 834/834/368\nf 779/779/368 833/833/368 777/777/368\nf 779/779/368 832/832/368 833/833/368\nf 743/743/368 832/832/368 779/779/368\nf 743/743/368 831/831/368 832/832/368\nf 744/744/368 800/800/368 747/747/368\nf 744/744/368 799/799/368 800/800/368\nf 768/768/368 799/799/368 744/744/368\nf 768/768/368 829/829/368 799/799/368\nf 766/766/368 829/829/368 768/768/368\nf 766/766/368 828/828/368 829/829/368\nf 763/763/368 828/828/368 766/766/368\nf 763/763/368 827/827/368 828/828/368\nf 773/773/368 827/827/368 763/763/368\nf 773/773/368 825/825/368 827/827/368\nf 815/815/524 751/751/524 805/805/524\nf 815/815/524 836/836/524 751/751/524\nf 755/755/392 806/806/392 754/754/392\nf 755/755/392 809/809/392 806/806/392\nf 748/748/520 810/810/520 758/758/520\nf 748/748/525 804/804/525 810/810/525\nf 840/840/526 808/808/526 752/752/526\nf 840/840/526 820/820/526 808/808/526\nf 753/753/389 812/812/389 756/756/389\nf 753/753/389 807/807/389 812/812/389\nf 757/757/398 802/802/398 749/749/398\nf 757/757/518 811/811/518 802/802/518\nf 752/752/390 805/805/390 751/751/390\nf 752/752/390 808/808/390 805/805/390\nf 754/754/391 807/807/391 753/753/391\nf 754/754/391 806/806/391 807/807/391\nf 756/756/390 809/809/390 755/755/390\nf 756/756/390 812/812/390 809/809/390\nf 758/758/391 811/811/391 757/757/391\nf 758/758/391 810/810/391 811/811/391\nf 749/749/390 804/804/390 748/748/390\nf 749/749/390 802/802/390 804/804/390\nf 786/786/391 787/787/391 741/741/391\nf 771/771/390 842/842/390 843/843/390\nf 746/746/391 735/735/391 736/736/391\nf 844/844/390 759/759/390 760/760/390\nf 839/839/527 771/771/527 843/843/527\nf 771/771/528 794/794/528 770/770/528\nf 771/771/529 839/839/529 794/794/529\nf 785/785/530 746/746/530 736/736/530\nf 785/785/531 745/745/531 746/746/531\nf 786/786/532 742/742/532 791/791/532\nf 786/786/533 741/741/533 742/742/533\nf 791/791/534 780/780/534 790/790/534\nf 791/791/532 742/742/532 780/780/532\nf 790/790/532 778/778/532 792/792/532\nf 790/790/535 780/780/535 778/778/535\nf 792/792/533 776/776/533 793/793/533\nf 792/792/529 778/778/529 776/776/529\nf 793/793/532 770/770/532 794/794/532\nf 793/793/532 776/776/532 770/770/532\nf 844/844/536 781/781/536 837/837/536\nf 781/781/537 760/760/537 774/774/537\nf 781/781/536 844/844/536 760/760/536\nf 781/781/537 764/764/537 782/782/537\nf 781/781/531 774/774/531 764/764/531\nf 782/782/536 765/765/536 783/783/536\nf 782/782/538 764/764/538 765/765/538\nf 783/783/539 767/767/539 784/784/539\nf 783/783/536 765/765/536 767/767/536\nf 784/784/537 745/745/537 785/785/537\nf 784/784/539 767/767/539 745/745/539\nf 787/787/391 740/740/391 741/741/391\nf 740/740/393 788/788/393 830/830/393\nf 740/740/391 787/787/391 788/788/391\nf 762/762/540 813/813/540 826/826/540\nf 813/813/541 835/835/541 816/816/541\nf 835/835/541 844/844/541 837/837/541\nf 759/759/540 813/813/540 762/762/540\nf 835/835/542 759/759/542 844/844/542\nf 813/813/543 759/759/543 835/835/543\nf 836/836/544 816/816/544 835/835/544\nf 836/836/545 815/815/545 816/816/545\nf 820/820/546 838/838/546 821/821/546\nf 820/820/547 840/840/547 838/838/547\nf 838/838/548 795/795/548 821/821/548\nf 795/795/549 841/841/549 798/798/549\nf 842/842/472 839/839/472 843/843/472\nf 795/795/548 842/842/548 841/841/548\nf 839/839/550 795/795/550 838/838/550\nf 795/795/551 839/839/551 842/842/551\nf 845/845/552 847/847/552 846/846/552\nf 845/845/552 848/848/552 847/847/552\nf 848/848/553 849/849/553 847/847/553\nf 848/848/553 850/850/553 849/849/553\nf 850/850/554 851/851/554 849/849/554\nf 850/850/554 852/852/554 851/851/554\nf 852/852/555 853/853/555 851/851/555\nf 852/852/556 854/854/556 853/853/556\nf 854/854/557 855/855/557 853/853/557\nf 854/854/558 856/856/558 855/855/558\nf 856/856/559 857/857/559 855/855/559\nf 856/856/559 858/858/559 857/857/559\nf 858/858/560 859/859/560 857/857/560\nf 858/858/560 860/860/560 859/859/560\nf 860/860/512 861/861/512 859/859/512\nf 860/860/512 862/862/512 861/861/512\nf 862/862/561 863/863/561 861/861/561\nf 862/862/561 864/864/561 863/863/561\nf 864/864/562 865/865/562 863/863/562\nf 864/864/562 866/866/562 865/865/562\nf 866/866/563 867/867/563 865/865/563\nf 866/866/563 868/868/563 867/867/563\nf 868/868/564 869/869/564 867/867/564\nf 868/868/565 870/870/565 869/869/565\nf 870/870/566 871/871/566 869/869/566\nf 870/870/567 872/872/567 871/871/567\nf 872/872/568 873/873/568 871/871/568\nf 872/872/569 874/874/569 873/873/569\nf 874/874/570 875/875/570 873/873/570\nf 874/874/570 876/876/570 875/875/570\nf 876/876/509 846/846/509 875/875/509\nf 876/876/514 845/845/514 846/846/514\nf 877/877/373 847/847/373 878/878/373\nf 877/877/373 846/846/373 847/847/373\nf 878/878/373 849/849/373 879/879/373\nf 878/878/373 847/847/373 849/849/373\nf 879/879/373 851/851/373 880/880/373\nf 879/879/373 849/849/373 851/851/373\nf 880/880/373 853/853/373 881/881/373\nf 880/880/373 851/851/373 853/853/373\nf 881/881/373 855/855/373 882/882/373\nf 881/881/373 853/853/373 855/855/373\nf 882/882/373 857/857/373 883/883/373\nf 882/882/373 855/855/373 857/857/373\nf 883/883/373 859/859/373 884/884/373\nf 883/883/373 857/857/373 859/859/373\nf 884/884/373 861/861/373 885/885/373\nf 884/884/373 859/859/373 861/861/373\nf 885/885/373 863/863/373 886/886/373\nf 885/885/373 861/861/373 863/863/373\nf 886/886/373 865/865/373 887/887/373\nf 886/886/373 863/863/373 865/865/373\nf 887/887/373 867/867/373 888/888/373\nf 887/887/373 865/865/373 867/867/373\nf 888/888/373 869/869/373 889/889/373\nf 888/888/373 867/867/373 869/869/373\nf 889/889/373 871/871/373 890/890/373\nf 889/889/373 869/869/373 871/871/373\nf 890/890/373 873/873/373 891/891/373\nf 890/890/373 871/871/373 873/873/373\nf 891/891/373 875/875/373 892/892/373\nf 891/891/373 873/873/373 875/875/373\nf 892/892/373 846/846/373 877/877/373\nf 892/892/373 875/875/373 846/846/373\nf 892/892/571 893/893/571 891/891/571\nf 892/892/572 894/894/572 893/893/572\nf 895/895/373 897/897/373 896/896/373\nf 897/897/373 899/899/373 898/898/373\nf 899/899/373 893/893/373 894/894/373\nf 893/893/373 901/901/373 900/900/373\nf 901/901/373 903/903/373 902/902/373\nf 903/903/373 905/905/373 904/904/373\nf 903/903/373 906/906/373 905/905/373\nf 895/895/373 899/899/373 897/897/373\nf 907/907/373 899/899/373 895/895/373\nf 901/901/373 906/906/373 903/903/373\nf 901/901/373 908/908/373 906/906/373\nf 909/909/373 899/899/373 907/907/373\nf 910/910/373 899/899/373 909/909/373\nf 893/893/373 908/908/373 901/901/373\nf 893/893/373 911/911/373 908/908/373\nf 910/910/373 893/893/373 899/899/373\nf 893/893/373 910/910/373 911/911/373\nf 912/912/373 903/903/373 904/904/373\nf 903/903/373 914/914/373 913/913/373\nf 914/914/373 916/916/373 915/915/373\nf 916/916/373 918/918/373 917/917/373\nf 918/918/373 897/897/373 919/919/373\nf 897/897/373 920/920/373 896/896/373\nf 897/897/373 921/921/373 920/920/373\nf 912/912/373 914/914/373 903/903/373\nf 922/922/373 914/914/373 912/912/373\nf 918/918/373 921/921/373 897/897/373\nf 918/918/373 923/923/373 921/921/373\nf 924/924/373 914/914/373 922/922/373\nf 925/925/373 914/914/373 924/924/373\nf 916/916/373 923/923/373 918/918/373\nf 916/916/373 926/926/373 923/923/373\nf 925/925/373 916/916/373 914/914/373\nf 916/916/373 925/925/373 926/926/373\nf 885/885/573 915/915/573 884/884/573\nf 885/885/510 914/914/510 915/915/510\nf 878/878/574 899/899/574 877/877/574\nf 878/878/575 898/898/575 899/899/575\nf 877/877/576 894/894/576 892/892/576\nf 877/877/577 899/899/577 894/894/577\nf 886/886/578 914/914/578 885/885/578\nf 886/886/579 913/913/579 914/914/579\nf 879/879/580 898/898/580 878/878/580\nf 879/879/580 897/897/580 898/898/580\nf 887/887/581 913/913/581 886/886/581\nf 887/887/581 903/903/581 913/913/581\nf 880/880/582 897/897/582 879/879/582\nf 880/880/583 919/919/583 897/897/583\nf 888/888/584 903/903/584 887/887/584\nf 888/888/585 902/902/585 903/903/585\nf 881/881/515 919/919/515 880/880/515\nf 881/881/515 918/918/515 919/919/515\nf 889/889/511 902/902/511 888/888/511\nf 889/889/586 901/901/586 902/902/586\nf 882/882/587 918/918/587 881/881/587\nf 882/882/587 917/917/587 918/918/587\nf 890/890/588 901/901/588 889/889/588\nf 890/890/588 900/900/588 901/901/588\nf 883/883/589 917/917/589 882/882/589\nf 883/883/589 916/916/589 917/917/589\nf 891/891/590 900/900/590 890/890/590\nf 891/891/590 893/893/590 900/900/590\nf 884/884/591 916/916/591 883/883/591\nf 884/884/592 915/915/592 916/916/592\nf 927/927/368 845/845/368 876/876/368\nf 845/845/368 850/850/368 848/848/368\nf 850/850/368 854/854/368 852/852/368\nf 854/854/368 858/858/368 856/856/368\nf 858/858/368 928/928/368 860/860/368\nf 858/858/368 929/929/368 928/928/368\nf 930/930/368 845/845/368 927/927/368\nf 931/931/368 845/845/368 930/930/368\nf 858/858/368 932/932/368 929/929/368\nf 858/858/368 933/933/368 932/932/368\nf 931/931/368 850/850/368 845/845/368\nf 934/934/368 850/850/368 931/931/368\nf 854/854/368 933/933/368 858/858/368\nf 854/854/368 935/935/368 933/933/368\nf 936/936/368 850/850/368 934/934/368\nf 854/854/368 936/936/368 935/935/368\nf 850/850/368 936/936/368 854/854/368\nf 937/937/368 860/860/368 928/928/368\nf 860/860/368 864/864/368 862/862/368\nf 864/864/368 868/868/368 866/866/368\nf 868/868/368 872/872/368 870/870/368\nf 872/872/368 876/876/368 874/874/368\nf 876/876/368 938/938/368 927/927/368\nf 876/876/368 939/939/368 938/938/368\nf 937/937/368 864/864/368 860/860/368\nf 940/940/368 864/864/368 937/937/368\nf 872/872/368 939/939/368 876/876/368\nf 872/872/368 941/941/368 939/939/368\nf 942/942/368 864/864/368 940/940/368\nf 943/943/368 864/864/368 942/942/368\nf 868/868/368 941/941/368 872/872/368\nf 868/868/368 944/944/368 941/941/368\nf 943/943/368 868/868/368 864/864/368\nf 868/868/368 943/943/368 944/944/368\nf 932/932/486 925/925/486 929/929/486\nf 932/932/486 926/926/486 925/925/486\nf 937/937/484 925/925/484 924/924/484\nf 925/925/593 928/928/593 929/929/593\nf 925/925/594 937/937/594 928/928/594\nf 924/924/483 940/940/483 937/937/483\nf 924/924/595 922/922/595 940/940/595\nf 940/940/482 912/912/482 942/942/482\nf 940/940/482 922/922/482 912/912/482\nf 912/912/481 943/943/481 942/942/481\nf 943/943/596 904/904/596 905/905/596\nf 943/943/597 912/912/597 904/904/597\nf 944/944/480 905/905/480 906/906/480\nf 944/944/418 943/943/418 905/905/418\nf 941/941/598 906/906/598 908/908/598\nf 941/941/542 944/944/542 906/906/542\nf 939/939/475 908/908/475 911/911/475\nf 939/939/475 941/941/475 908/908/475\nf 938/938/474 911/911/474 910/910/474\nf 938/938/474 939/939/474 911/911/474\nf 909/909/472 938/938/472 910/910/472\nf 927/927/548 909/909/548 930/930/548\nf 938/938/551 909/909/551 927/927/551\nf 931/931/469 909/909/469 907/907/469\nf 931/931/599 930/930/599 909/909/599\nf 934/934/468 907/907/468 895/895/468\nf 934/934/468 931/931/468 907/907/468\nf 934/934/492 920/920/492 936/936/492\nf 896/896/492 934/934/492 895/895/492\nf 920/920/600 934/934/600 896/896/600\nf 921/921/491 936/936/491 920/920/491\nf 921/921/490 935/935/490 936/936/490\nf 921/921/489 933/933/489 935/935/489\nf 921/921/489 923/923/489 933/933/489\nf 933/933/487 926/926/487 932/932/487\nf 933/933/487 923/923/487 926/926/487\nf 945/945/601 947/947/601 946/946/601\nf 947/947/495 949/949/495 948/948/495\nf 947/947/495 945/945/495 949/949/495\nf 950/950/494 952/952/494 951/951/494\nf 952/952/602 954/954/602 953/953/602\nf 952/952/494 950/950/494 954/954/494\nf 951/951/603 945/945/603 950/950/603\nf 951/951/603 949/949/603 945/945/603\nf 955/955/497 949/949/497 956/956/497\nf 949/949/495 957/957/495 948/948/495\nf 949/949/500 955/955/500 957/957/500\nf 958/958/602 952/952/602 959/959/602\nf 952/952/494 960/960/494 951/951/494\nf 952/952/493 958/958/493 960/960/493\nf 948/948/604 959/959/604 952/952/604\nf 948/948/504 957/957/504 959/959/504\nf 957/957/368 958/958/368 959/959/368\nf 957/957/368 955/955/368 958/958/368\nf 960/960/605 955/955/605 956/956/605\nf 960/960/605 958/958/605 955/955/605\nf 951/951/603 956/956/603 949/949/603\nf 951/951/501 960/960/501 956/956/501\nf 945/945/606 954/954/606 950/950/606\nf 945/945/606 946/946/606 954/954/606\nf 953/953/373 946/946/373 947/947/373\nf 953/953/373 954/954/373 946/946/373\nf 961/961/607 963/963/607 962/962/607\nf 963/963/509 965/965/509 964/964/509\nf 963/963/509 961/961/509 965/965/509\nf 966/966/508 968/968/508 967/967/508\nf 968/968/577 970/970/577 969/969/577\nf 968/968/576 966/966/576 970/970/576\nf 967/967/515 961/961/515 966/966/515\nf 967/967/515 965/965/515 961/961/515\nf 971/971/608 965/965/608 972/972/608\nf 965/965/509 973/973/509 964/964/509\nf 965/965/609 971/971/609 973/973/609\nf 974/974/610 968/968/610 975/975/610\nf 968/968/508 976/976/508 967/967/508\nf 968/968/576 974/974/576 976/976/576\nf 964/964/511 975/975/511 968/968/511\nf 964/964/511 973/973/511 975/975/511\nf 973/973/368 974/974/368 975/975/368\nf 973/973/368 971/971/368 974/974/368\nf 976/976/611 971/971/611 972/972/611\nf 976/976/612 974/974/612 971/971/612\nf 967/967/565 972/972/565 965/965/565\nf 967/967/515 976/976/515 972/972/515\nf 961/961/613 970/970/613 966/966/613\nf 961/961/614 962/962/614 970/970/614\nf 969/969/373 962/962/373 963/963/373\nf 969/969/373 970/970/373 962/962/373\nf 977/977/390 979/979/390 978/978/390\nf 979/979/390 981/981/390 980/980/390\nf 979/979/390 977/977/390 981/981/390\nf 982/982/389 984/984/389 983/983/389\nf 982/982/389 985/985/389 984/984/389\nf 986/986/392 988/988/392 987/987/392\nf 986/986/392 989/989/392 988/988/392\nf 990/990/373 992/992/373 991/991/373\nf 990/990/373 979/979/373 992/992/373\nf 993/993/373 995/995/373 994/994/373\nf 993/993/373 996/996/373 995/995/373\nf 997/997/373 999/999/373 998/998/373\nf 997/997/373 1000/1000/373 999/999/373\nf 1001/1001/391 1003/1003/391 1002/1002/391\nf 1001/1001/391 1004/1004/391 1003/1003/391\nf 1005/1005/520 1007/1007/520 1006/1006/520\nf 1005/1005/520 1008/1008/520 1007/1007/520\nf 1008/1008/519 1009/1009/519 1007/1007/519\nf 1008/1008/519 1010/1010/519 1009/1009/519\nf 1010/1010/392 987/987/392 1009/1009/392\nf 1010/1010/392 986/986/392 987/987/392\nf 1011/1011/398 1013/1013/398 1012/1012/398\nf 1011/1011/518 1014/1014/518 1013/1013/518\nf 1015/1015/392 1006/1006/392 1016/1016/392\nf 1015/1015/392 1005/1005/392 1006/1006/392\nf 1017/1017/389 1012/1012/389 1018/1018/389\nf 1017/1017/389 1011/1011/389 1012/1012/389\nf 1019/1019/518 1018/1018/518 1020/1020/518\nf 1019/1019/518 1017/1017/518 1018/1018/518\nf 1021/1021/398 1020/1020/398 1022/1022/398\nf 1021/1021/398 1019/1019/398 1020/1020/398\nf 985/985/389 1022/1022/389 984/984/389\nf 985/985/389 1021/1021/389 1022/1022/389\nf 1023/1023/373 996/996/373 993/993/373\nf 1023/1023/373 1024/1024/373 996/996/373\nf 1024/1024/373 997/997/373 996/996/373\nf 1024/1024/373 1025/1025/373 997/997/373\nf 1025/1025/373 1000/1000/373 997/997/373\nf 1025/1025/373 1026/1026/373 1000/1000/373\nf 1026/1026/373 990/990/373 1000/1000/373\nf 1026/1026/373 1027/1027/373 990/990/373\nf 992/992/390 1029/1029/390 1028/1028/390\nf 1029/1029/615 1031/1031/615 1030/1030/615\nf 1029/1029/396 992/992/396 1031/1031/396\nf 999/999/373 1033/1033/373 1032/1032/373\nf 999/999/373 991/991/373 1033/1033/373\nf 998/998/373 1032/1032/373 1034/1034/373\nf 998/998/373 999/999/373 1032/1032/373\nf 995/995/373 1034/1034/373 1035/1035/373\nf 995/995/373 998/998/373 1034/1034/373\nf 994/994/373 1035/1035/373 1036/1036/373\nf 994/994/373 995/995/373 1035/1035/373\nf 1037/1037/616 1039/1039/616 1038/1038/616\nf 1037/1037/616 1040/1040/616 1039/1039/616\nf 1041/1041/398 981/981/398 1042/1042/398\nf 1041/1041/398 1043/1043/398 981/981/398\nf 1044/1044/368 1030/1030/368 1031/1031/368\nf 1044/1044/368 1045/1045/368 1030/1030/368\nf 1043/1043/368 980/980/368 981/981/368\nf 1043/1043/368 1046/1046/368 980/980/368\nf 1046/1046/368 1031/1031/368 980/980/368\nf 1046/1046/368 1044/1044/368 1031/1031/368\nf 1047/1047/368 1049/1049/368 1048/1048/368\nf 1047/1047/368 1050/1050/368 1049/1049/368\nf 1051/1051/368 1053/1053/368 1052/1052/368\nf 1051/1051/368 1054/1054/368 1053/1053/368\nf 1055/1055/368 1047/1047/368 1056/1056/368\nf 1047/1047/368 1058/1058/368 1057/1057/368\nf 1047/1047/368 1055/1055/368 1058/1058/368\nf 1056/1056/368 1048/1048/368 1059/1059/368\nf 1056/1056/368 1047/1047/368 1048/1048/368\nf 1059/1059/368 1051/1051/368 1060/1060/368\nf 1059/1059/368 1048/1048/368 1051/1051/368\nf 1060/1060/368 1052/1052/368 1061/1061/368\nf 1060/1060/368 1051/1051/368 1052/1052/368\nf 1061/1061/368 1046/1046/368 1043/1043/368\nf 1061/1061/368 1052/1052/368 1046/1046/368\nf 1062/1062/368 1038/1038/368 1050/1050/368\nf 1038/1038/368 1063/1063/368 1037/1037/368\nf 1038/1038/368 1062/1062/368 1063/1063/368\nf 1050/1050/368 1064/1064/368 1049/1049/368\nf 1050/1050/368 1038/1038/368 1064/1064/368\nf 1049/1049/368 1065/1065/368 1054/1054/368\nf 1049/1049/368 1064/1064/368 1065/1065/368\nf 1054/1054/368 1066/1066/368 1053/1053/368\nf 1054/1054/368 1065/1065/368 1066/1066/368\nf 1053/1053/368 1045/1045/368 1044/1044/368\nf 1053/1053/368 1066/1066/368 1045/1045/368\nf 1067/1067/518 1055/1055/518 1056/1056/518\nf 1067/1067/617 1068/1068/617 1055/1055/617\nf 1067/1067/398 1059/1059/398 1069/1069/398\nf 1067/1067/398 1056/1056/398 1059/1059/398\nf 1069/1069/389 1060/1060/389 1070/1070/389\nf 1069/1069/389 1059/1059/389 1060/1060/389\nf 1070/1070/389 1061/1061/389 1071/1071/389\nf 1070/1070/389 1060/1060/389 1061/1061/389\nf 1071/1071/518 1043/1043/518 1041/1041/518\nf 1071/1071/518 1061/1061/518 1043/1043/518\nf 1072/1072/519 1045/1045/519 1073/1073/519\nf 1072/1072/519 1030/1030/519 1045/1045/519\nf 1073/1073/520 1066/1066/520 1074/1074/520\nf 1073/1073/520 1045/1045/520 1066/1066/520\nf 1074/1074/392 1065/1065/392 1075/1075/392\nf 1074/1074/392 1066/1066/392 1065/1065/392\nf 1075/1075/392 1064/1064/392 1076/1076/392\nf 1075/1075/392 1065/1065/392 1064/1064/392\nf 1076/1076/519 1038/1038/519 1039/1039/519\nf 1076/1076/519 1064/1064/519 1038/1038/519\nf 982/982/368 1073/1073/368 985/985/368\nf 982/982/368 1072/1072/368 1073/1073/368\nf 991/991/373 1028/1028/373 1033/1033/373\nf 991/991/373 992/992/373 1028/1028/373\nf 1027/1027/373 979/979/373 990/990/373\nf 1027/1027/373 978/978/373 979/979/373\nf 1077/1077/373 993/993/373 1078/1078/373\nf 993/993/373 1079/1079/373 1023/1023/373\nf 993/993/373 1077/1077/373 1079/1079/373\nf 1003/1003/519 1016/1016/519 1002/1002/519\nf 1003/1003/519 1015/1015/519 1016/1016/519\nf 1004/1004/368 1015/1015/368 1003/1003/368\nf 1015/1015/368 1068/1068/368 1067/1067/368\nf 1015/1015/368 1004/1004/368 1068/1068/368\nf 1080/1080/373 1036/1036/373 1081/1081/373\nf 1036/1036/373 1082/1082/373 994/994/373\nf 1036/1036/373 1080/1080/373 1082/1082/373\nf 1083/1083/391 1013/1013/391 1014/1014/391\nf 1083/1083/391 1084/1084/391 1013/1013/391\nf 989/989/390 977/977/390 988/988/390\nf 977/977/390 1042/1042/390 981/981/390\nf 977/977/390 989/989/390 1042/1042/390\nf 979/979/390 1031/1031/390 992/992/390\nf 979/979/390 980/980/390 1031/1031/390\nf 1040/1040/368 1011/1011/368 1039/1039/368\nf 1011/1011/368 1083/1083/368 1014/1014/368\nf 1011/1011/368 1040/1040/368 1083/1083/368\nf 1017/1017/368 1039/1039/368 1011/1011/368\nf 1017/1017/368 1076/1076/368 1039/1039/368\nf 1019/1019/368 1076/1076/368 1017/1017/368\nf 1019/1019/368 1075/1075/368 1076/1076/368\nf 1021/1021/368 1075/1075/368 1019/1019/368\nf 1021/1021/368 1074/1074/368 1075/1075/368\nf 985/985/368 1074/1074/368 1021/1021/368\nf 985/985/368 1073/1073/368 1074/1074/368\nf 986/986/368 1042/1042/368 989/989/368\nf 986/986/368 1041/1041/368 1042/1042/368\nf 1010/1010/368 1041/1041/368 986/986/368\nf 1010/1010/368 1071/1071/368 1041/1041/368\nf 1008/1008/368 1071/1071/368 1010/1010/368\nf 1008/1008/368 1070/1070/368 1071/1071/368\nf 1005/1005/368 1070/1070/368 1008/1008/368\nf 1005/1005/368 1069/1069/368 1070/1070/368\nf 1015/1015/368 1069/1069/368 1005/1005/368\nf 1015/1015/368 1067/1067/368 1069/1069/368\nf 1057/1057/618 993/993/618 1047/1047/618\nf 1057/1057/618 1078/1078/618 993/993/618\nf 997/997/389 1048/1048/389 996/996/389\nf 997/997/389 1051/1051/389 1048/1048/389\nf 990/990/398 1052/1052/398 1000/1000/398\nf 990/990/398 1046/1046/398 1052/1052/398\nf 1082/1082/525 1050/1050/525 994/994/525\nf 1082/1082/525 1062/1062/525 1050/1050/525\nf 995/995/392 1054/1054/392 998/998/392\nf 995/995/392 1049/1049/392 1054/1054/392\nf 999/999/519 1044/1044/519 991/991/519\nf 999/999/519 1053/1053/519 1044/1044/519\nf 994/994/391 1047/1047/391 993/993/391\nf 994/994/391 1050/1050/391 1047/1047/391\nf 996/996/390 1049/1049/390 995/995/390\nf 996/996/390 1048/1048/390 1049/1049/390\nf 998/998/391 1051/1051/391 997/997/391\nf 998/998/391 1054/1054/391 1051/1051/391\nf 1000/1000/390 1053/1053/390 999/999/390\nf 1000/1000/390 1052/1052/390 1053/1053/390\nf 991/991/391 1046/1046/391 990/990/391\nf 991/991/391 1044/1044/391 1046/1046/391\nf 1028/1028/390 1029/1029/390 983/983/390\nf 1013/1013/391 1084/1084/391 1085/1085/391\nf 988/988/390 977/977/390 978/978/390\nf 1086/1086/391 1001/1001/391 1002/1002/391\nf 1081/1081/619 1013/1013/619 1085/1085/619\nf 1013/1013/537 1036/1036/537 1012/1012/537\nf 1013/1013/539 1081/1081/539 1036/1036/539\nf 1027/1027/532 988/988/532 978/978/532\nf 1027/1027/532 987/987/532 988/988/532\nf 1028/1028/531 984/984/531 1033/1033/531\nf 1028/1028/530 983/983/530 984/984/530\nf 1033/1033/620 1022/1022/620 1032/1032/620\nf 1033/1033/531 984/984/531 1022/1022/531\nf 1032/1032/539 1020/1020/539 1034/1034/539\nf 1032/1032/621 1022/1022/621 1020/1020/621\nf 1034/1034/537 1018/1018/537 1035/1035/537\nf 1034/1034/531 1020/1020/531 1018/1018/531\nf 1035/1035/530 1012/1012/530 1036/1036/530\nf 1035/1035/531 1018/1018/531 1012/1012/531\nf 1086/1086/528 1023/1023/528 1079/1079/528\nf 1023/1023/622 1002/1002/622 1016/1016/622\nf 1023/1023/528 1086/1086/528 1002/1002/528\nf 1023/1023/623 1006/1006/623 1024/1024/623\nf 1023/1023/532 1016/1016/532 1006/1006/532\nf 1024/1024/528 1007/1007/528 1025/1025/528\nf 1024/1024/624 1006/1006/624 1007/1007/624\nf 1025/1025/529 1009/1009/529 1026/1026/529\nf 1025/1025/529 1007/1007/529 1009/1009/529\nf 1026/1026/624 987/987/624 1027/1027/624\nf 1026/1026/529 1009/1009/529 987/987/529\nf 1029/1029/390 982/982/390 983/983/390\nf 982/982/390 1030/1030/390 1072/1072/390\nf 982/982/390 1029/1029/390 1030/1030/390\nf 1004/1004/625 1055/1055/625 1068/1068/625\nf 1055/1055/626 1077/1077/626 1058/1058/626\nf 1077/1077/627 1086/1086/627 1079/1079/627\nf 1001/1001/626 1055/1055/626 1004/1004/626\nf 1077/1077/628 1001/1001/628 1086/1086/628\nf 1055/1055/626 1001/1001/626 1077/1077/626\nf 1078/1078/629 1058/1058/629 1077/1077/629\nf 1078/1078/630 1057/1057/630 1058/1058/630\nf 1062/1062/631 1080/1080/631 1063/1063/631\nf 1062/1062/632 1082/1082/632 1080/1080/632\nf 1080/1080/594 1037/1037/594 1063/1063/594\nf 1037/1037/633 1083/1083/633 1040/1040/633\nf 1084/1084/594 1081/1081/594 1085/1085/594\nf 1037/1037/594 1084/1084/594 1083/1083/594\nf 1081/1081/634 1037/1037/634 1080/1080/634\nf 1037/1037/635 1081/1081/635 1084/1084/635\nf 1087/1087/561 1089/1089/561 1088/1088/561\nf 1087/1087/561 1090/1090/561 1089/1089/561\nf 1090/1090/562 1091/1091/562 1089/1089/562\nf 1090/1090/580 1092/1092/580 1091/1091/580\nf 1092/1092/563 1093/1093/563 1091/1091/563\nf 1092/1092/563 1094/1094/563 1093/1093/563\nf 1094/1094/564 1095/1095/564 1093/1093/564\nf 1094/1094/564 1096/1096/564 1095/1095/564\nf 1096/1096/566 1097/1097/566 1095/1095/566\nf 1096/1096/567 1098/1098/567 1097/1097/567\nf 1098/1098/636 1099/1099/636 1097/1097/636\nf 1098/1098/637 1100/1100/637 1099/1099/637\nf 1100/1100/570 1101/1101/570 1099/1099/570\nf 1100/1100/592 1102/1102/592 1101/1101/592\nf 1102/1102/638 1103/1103/638 1101/1101/638\nf 1102/1102/509 1104/1104/509 1103/1103/509\nf 1104/1104/552 1105/1105/552 1103/1103/552\nf 1104/1104/579 1106/1106/579 1105/1105/579\nf 1106/1106/553 1107/1107/553 1105/1105/553\nf 1106/1106/553 1108/1108/553 1107/1107/553\nf 1108/1108/554 1109/1109/554 1107/1107/554\nf 1108/1108/554 1110/1110/554 1109/1109/554\nf 1110/1110/555 1111/1111/555 1109/1109/555\nf 1110/1110/556 1112/1112/556 1111/1111/556\nf 1112/1112/557 1113/1113/557 1111/1111/557\nf 1112/1112/558 1114/1114/558 1113/1113/558\nf 1114/1114/639 1115/1115/639 1113/1113/639\nf 1114/1114/559 1116/1116/559 1115/1115/559\nf 1116/1116/560 1117/1117/560 1115/1115/560\nf 1116/1116/560 1118/1118/560 1117/1117/560\nf 1118/1118/508 1088/1088/508 1117/1117/508\nf 1118/1118/512 1087/1087/512 1088/1088/512\nf 1119/1119/373 1089/1089/373 1120/1120/373\nf 1119/1119/373 1088/1088/373 1089/1089/373\nf 1120/1120/373 1091/1091/373 1121/1121/373\nf 1120/1120/373 1089/1089/373 1091/1091/373\nf 1121/1121/373 1093/1093/373 1122/1122/373\nf 1121/1121/373 1091/1091/373 1093/1093/373\nf 1122/1122/373 1095/1095/373 1123/1123/373\nf 1122/1122/373 1093/1093/373 1095/1095/373\nf 1123/1123/373 1097/1097/373 1124/1124/373\nf 1123/1123/373 1095/1095/373 1097/1097/373\nf 1124/1124/373 1099/1099/373 1125/1125/373\nf 1124/1124/373 1097/1097/373 1099/1099/373\nf 1125/1125/373 1101/1101/373 1126/1126/373\nf 1125/1125/373 1099/1099/373 1101/1101/373\nf 1126/1126/373 1103/1103/373 1127/1127/373\nf 1126/1126/373 1101/1101/373 1103/1103/373\nf 1127/1127/373 1105/1105/373 1128/1128/373\nf 1127/1127/373 1103/1103/373 1105/1105/373\nf 1128/1128/373 1107/1107/373 1129/1129/373\nf 1128/1128/373 1105/1105/373 1107/1107/373\nf 1129/1129/373 1109/1109/373 1130/1130/373\nf 1129/1129/373 1107/1107/373 1109/1109/373\nf 1130/1130/373 1111/1111/373 1131/1131/373\nf 1130/1130/373 1109/1109/373 1111/1111/373\nf 1131/1131/373 1113/1113/373 1132/1132/373\nf 1131/1131/373 1111/1111/373 1113/1113/373\nf 1132/1132/373 1115/1115/373 1133/1133/373\nf 1132/1132/373 1113/1113/373 1115/1115/373\nf 1133/1133/373 1117/1117/373 1134/1134/373\nf 1133/1133/373 1115/1115/373 1117/1117/373\nf 1134/1134/373 1088/1088/373 1119/1119/373\nf 1134/1134/373 1117/1117/373 1088/1088/373\nf 1134/1134/591 1135/1135/591 1133/1133/591\nf 1134/1134/592 1136/1136/592 1135/1135/592\nf 1137/1137/373 1139/1139/373 1138/1138/373\nf 1139/1139/373 1141/1141/373 1140/1140/373\nf 1141/1141/373 1135/1135/373 1136/1136/373\nf 1135/1135/373 1143/1143/373 1142/1142/373\nf 1143/1143/373 1145/1145/373 1144/1144/373\nf 1145/1145/373 1147/1147/373 1146/1146/373\nf 1145/1145/373 1148/1148/373 1147/1147/373\nf 1137/1137/373 1141/1141/373 1139/1139/373\nf 1149/1149/373 1141/1141/373 1137/1137/373\nf 1143/1143/373 1148/1148/373 1145/1145/373\nf 1143/1143/373 1150/1150/373 1148/1148/373\nf 1151/1151/373 1141/1141/373 1149/1149/373\nf 1152/1152/373 1141/1141/373 1151/1151/373\nf 1135/1135/373 1150/1150/373 1143/1143/373\nf 1135/1135/373 1153/1153/373 1150/1150/373\nf 1152/1152/373 1135/1135/373 1141/1141/373\nf 1135/1135/373 1152/1152/373 1153/1153/373\nf 1154/1154/373 1145/1145/373 1146/1146/373\nf 1145/1145/373 1156/1156/373 1155/1155/373\nf 1156/1156/373 1158/1158/373 1157/1157/373\nf 1158/1158/373 1160/1160/373 1159/1159/373\nf 1160/1160/373 1139/1139/373 1161/1161/373\nf 1139/1139/373 1162/1162/373 1138/1138/373\nf 1139/1139/373 1163/1163/373 1162/1162/373\nf 1154/1154/373 1156/1156/373 1145/1145/373\nf 1164/1164/373 1156/1156/373 1154/1154/373\nf 1160/1160/373 1163/1163/373 1139/1139/373\nf 1160/1160/373 1165/1165/373 1163/1163/373\nf 1166/1166/373 1156/1156/373 1164/1164/373\nf 1167/1167/373 1156/1156/373 1166/1166/373\nf 1158/1158/373 1165/1165/373 1160/1160/373\nf 1158/1158/373 1168/1168/373 1165/1165/373\nf 1167/1167/373 1158/1158/373 1156/1156/373\nf 1158/1158/373 1167/1167/373 1168/1168/373\nf 1127/1127/640 1157/1157/640 1126/1126/640\nf 1127/1127/576 1156/1156/576 1157/1157/576\nf 1120/1120/641 1141/1141/641 1119/1119/641\nf 1120/1120/578 1140/1140/578 1141/1141/578\nf 1119/1119/573 1136/1136/573 1134/1134/573\nf 1119/1119/510 1141/1141/510 1136/1136/510\nf 1128/1128/642 1156/1156/642 1127/1127/642\nf 1128/1128/575 1155/1155/575 1156/1156/575\nf 1121/1121/581 1140/1140/581 1120/1120/581\nf 1121/1121/581 1139/1139/581 1140/1140/581\nf 1129/1129/580 1155/1155/580 1128/1128/580\nf 1129/1129/580 1145/1145/580 1155/1155/580\nf 1122/1122/584 1139/1139/584 1121/1121/584\nf 1122/1122/584 1161/1161/584 1139/1139/584\nf 1130/1130/582 1145/1145/582 1129/1129/582\nf 1130/1130/583 1144/1144/583 1145/1145/583\nf 1123/1123/511 1161/1161/511 1122/1122/511\nf 1123/1123/643 1160/1160/643 1161/1161/643\nf 1131/1131/515 1144/1144/515 1130/1130/515\nf 1131/1131/644 1143/1143/644 1144/1144/644\nf 1124/1124/557 1160/1160/557 1123/1123/557\nf 1124/1124/588 1159/1159/588 1160/1160/588\nf 1132/1132/587 1143/1143/587 1131/1131/587\nf 1132/1132/587 1142/1142/587 1143/1143/587\nf 1125/1125/590 1159/1159/590 1124/1124/590\nf 1125/1125/590 1158/1158/590 1159/1159/590\nf 1133/1133/589 1142/1142/589 1132/1132/589\nf 1133/1133/589 1135/1135/589 1142/1142/589\nf 1126/1126/645 1158/1158/645 1125/1125/645\nf 1126/1126/645 1157/1157/645 1158/1158/645\nf 1169/1169/368 1087/1087/368 1118/1118/368\nf 1087/1087/368 1092/1092/368 1090/1090/368\nf 1092/1092/368 1096/1096/368 1094/1094/368\nf 1096/1096/368 1100/1100/368 1098/1098/368\nf 1100/1100/368 1170/1170/368 1102/1102/368\nf 1100/1100/368 1171/1171/368 1170/1170/368\nf 1172/1172/368 1087/1087/368 1169/1169/368\nf 1173/1173/368 1087/1087/368 1172/1172/368\nf 1100/1100/368 1174/1174/368 1171/1171/368\nf 1100/1100/368 1175/1175/368 1174/1174/368\nf 1173/1173/368 1092/1092/368 1087/1087/368\nf 1176/1176/368 1092/1092/368 1173/1173/368\nf 1096/1096/368 1175/1175/368 1100/1100/368\nf 1096/1096/368 1177/1177/368 1175/1175/368\nf 1178/1178/368 1092/1092/368 1176/1176/368\nf 1096/1096/368 1178/1178/368 1177/1177/368\nf 1092/1092/368 1178/1178/368 1096/1096/368\nf 1179/1179/368 1102/1102/368 1170/1170/368\nf 1102/1102/368 1106/1106/368 1104/1104/368\nf 1106/1106/368 1110/1110/368 1108/1108/368\nf 1110/1110/368 1114/1114/368 1112/1112/368\nf 1114/1114/368 1118/1118/368 1116/1116/368\nf 1118/1118/368 1180/1180/368 1169/1169/368\nf 1118/1118/368 1181/1181/368 1180/1180/368\nf 1179/1179/368 1106/1106/368 1102/1102/368\nf 1182/1182/368 1106/1106/368 1179/1179/368\nf 1114/1114/368 1181/1181/368 1118/1118/368\nf 1114/1114/368 1183/1183/368 1181/1181/368\nf 1184/1184/368 1106/1106/368 1182/1182/368\nf 1185/1185/368 1106/1106/368 1184/1184/368\nf 1110/1110/368 1183/1183/368 1114/1114/368\nf 1110/1110/368 1186/1186/368 1183/1183/368\nf 1185/1185/368 1110/1110/368 1106/1106/368\nf 1110/1110/368 1185/1185/368 1186/1186/368\nf 1174/1174/474 1167/1167/474 1171/1171/474\nf 1174/1174/474 1168/1168/474 1167/1167/474\nf 1179/1179/472 1167/1167/472 1166/1166/472\nf 1167/1167/646 1170/1170/646 1171/1171/646\nf 1167/1167/647 1179/1179/647 1170/1170/647\nf 1166/1166/469 1182/1182/469 1179/1179/469\nf 1166/1166/599 1164/1164/599 1182/1182/599\nf 1182/1182/468 1154/1154/468 1184/1184/468\nf 1182/1182/468 1164/1164/468 1154/1154/468\nf 1154/1154/492 1185/1185/492 1184/1184/492\nf 1185/1185/648 1146/1146/648 1147/1147/648\nf 1185/1185/649 1154/1154/649 1146/1146/649\nf 1186/1186/490 1147/1147/490 1148/1148/490\nf 1186/1186/650 1185/1185/650 1147/1147/650\nf 1183/1183/489 1148/1148/489 1150/1150/489\nf 1183/1183/628 1186/1186/628 1148/1148/628\nf 1181/1181/487 1150/1150/487 1153/1153/487\nf 1181/1181/487 1183/1183/487 1150/1150/487\nf 1180/1180/486 1153/1153/486 1152/1152/486\nf 1180/1180/486 1181/1181/486 1153/1153/486\nf 1151/1151/484 1180/1180/484 1152/1152/484\nf 1169/1169/594 1151/1151/594 1172/1172/594\nf 1180/1180/635 1151/1151/635 1169/1169/635\nf 1173/1173/483 1151/1151/483 1149/1149/483\nf 1173/1173/595 1172/1172/595 1151/1151/595\nf 1176/1176/482 1149/1149/482 1137/1137/482\nf 1176/1176/482 1173/1173/482 1149/1149/482\nf 1176/1176/481 1162/1162/481 1178/1178/481\nf 1138/1138/481 1176/1176/481 1137/1137/481\nf 1162/1162/651 1176/1176/651 1138/1138/651\nf 1163/1163/652 1178/1178/652 1162/1162/652\nf 1163/1163/418 1177/1177/418 1178/1178/418\nf 1163/1163/542 1175/1175/542 1177/1177/542\nf 1163/1163/542 1165/1165/542 1175/1175/542\nf 1175/1175/475 1168/1168/475 1174/1174/475\nf 1175/1175/475 1165/1165/475 1168/1168/475\nf 1187/1187/365 1188/1188/365 1189/1189/365\nf 1189/1189/359 1190/1190/359 1191/1191/359\nf 1189/1189/359 1191/1191/359 1187/1187/359\nf 1192/1192/358 1193/1193/358 1194/1194/358\nf 1194/1194/653 1195/1195/653 1196/1196/653\nf 1194/1194/362 1196/1196/362 1192/1192/362\nf 1193/1193/654 1192/1192/654 1187/1187/654\nf 1193/1193/654 1187/1187/654 1191/1191/654\nf 1197/1197/365 1198/1198/365 1191/1191/365\nf 1191/1191/359 1190/1190/359 1199/1199/359\nf 1191/1191/364 1199/1199/364 1197/1197/364\nf 1200/1200/655 1201/1201/655 1194/1194/655\nf 1194/1194/358 1193/1193/358 1202/1202/358\nf 1194/1194/362 1202/1202/362 1200/1200/362\nf 1190/1190/370 1194/1194/370 1201/1201/370\nf 1190/1190/656 1201/1201/656 1199/1199/656\nf 1199/1199/368 1201/1201/368 1200/1200/368\nf 1199/1199/368 1200/1200/368 1197/1197/368\nf 1202/1202/657 1198/1198/657 1197/1197/657\nf 1202/1202/657 1197/1197/657 1200/1200/657\nf 1193/1193/367 1191/1191/367 1198/1198/367\nf 1193/1193/367 1198/1198/367 1202/1202/367\nf 1187/1187/658 1192/1192/658 1196/1196/658\nf 1187/1187/658 1196/1196/658 1188/1188/658\nf 1195/1195/373 1189/1189/373 1188/1188/373\nf 1195/1195/373 1188/1188/373 1196/1196/373\nf 1203/1203/375 1204/1204/375 1205/1205/375\nf 1205/1205/375 1206/1206/375 1207/1207/375\nf 1205/1205/375 1207/1207/375 1203/1203/375\nf 1208/1208/374 1209/1209/374 1210/1210/374\nf 1210/1210/452 1211/1211/452 1212/1212/452\nf 1210/1210/374 1212/1212/374 1208/1208/374\nf 1209/1209/382 1208/1208/382 1203/1203/382\nf 1209/1209/382 1203/1203/382 1207/1207/382\nf 1213/1213/659 1214/1214/659 1207/1207/659\nf 1207/1207/375 1206/1206/375 1215/1215/375\nf 1207/1207/660 1215/1215/660 1213/1213/660\nf 1216/1216/661 1217/1217/661 1210/1210/661\nf 1210/1210/374 1209/1209/374 1218/1218/374\nf 1210/1210/452 1218/1218/452 1216/1216/452\nf 1206/1206/377 1210/1210/377 1217/1217/377\nf 1206/1206/377 1217/1217/377 1215/1215/377\nf 1215/1215/368 1217/1217/368 1216/1216/368\nf 1215/1215/368 1216/1216/368 1213/1213/368\nf 1218/1218/662 1214/1214/662 1213/1213/662\nf 1218/1218/662 1213/1213/662 1216/1216/662\nf 1209/1209/382 1207/1207/382 1214/1214/382\nf 1209/1209/382 1214/1214/382 1218/1218/382\nf 1203/1203/663 1208/1208/663 1212/1212/663\nf 1203/1203/664 1212/1212/664 1204/1204/664\nf 1211/1211/373 1205/1205/373 1204/1204/373\nf 1211/1211/373 1204/1204/373 1212/1212/373\nf 1219/1219/392 1220/1220/392 1221/1221/392\nf 1221/1221/392 1222/1222/392 1223/1223/392\nf 1221/1221/392 1223/1223/392 1219/1219/392\nf 1224/1224/391 1225/1225/391 1226/1226/391\nf 1224/1224/391 1226/1226/391 1227/1227/391\nf 1228/1228/390 1229/1229/390 1230/1230/390\nf 1228/1228/390 1230/1230/390 1231/1231/390\nf 1232/1232/373 1233/1233/373 1234/1234/373\nf 1232/1232/373 1234/1234/373 1221/1221/373\nf 1235/1235/373 1236/1236/373 1237/1237/373\nf 1235/1235/373 1237/1237/373 1238/1238/373\nf 1239/1239/373 1240/1240/373 1241/1241/373\nf 1239/1239/373 1241/1241/373 1242/1242/373\nf 1243/1243/389 1244/1244/389 1245/1245/389\nf 1243/1243/389 1245/1245/389 1246/1246/389\nf 1247/1247/396 1248/1248/396 1249/1249/396\nf 1247/1247/396 1249/1249/396 1250/1250/396\nf 1250/1250/395 1249/1249/395 1251/1251/395\nf 1250/1250/395 1251/1251/395 1252/1252/395\nf 1252/1252/390 1251/1251/390 1229/1229/390\nf 1252/1252/390 1229/1229/390 1228/1228/390\nf 1253/1253/393 1254/1254/393 1255/1255/393\nf 1253/1253/394 1255/1255/394 1256/1256/394\nf 1257/1257/390 1258/1258/390 1248/1248/390\nf 1257/1257/390 1248/1248/390 1247/1247/390\nf 1259/1259/391 1260/1260/391 1254/1254/391\nf 1259/1259/391 1254/1254/391 1253/1253/391\nf 1261/1261/394 1262/1262/394 1260/1260/394\nf 1261/1261/394 1260/1260/394 1259/1259/394\nf 1263/1263/393 1264/1264/393 1262/1262/393\nf 1263/1263/394 1262/1262/394 1261/1261/394\nf 1227/1227/391 1226/1226/391 1264/1264/391\nf 1227/1227/391 1264/1264/391 1263/1263/391\nf 1265/1265/373 1235/1235/373 1238/1238/373\nf 1265/1265/373 1238/1238/373 1266/1266/373\nf 1266/1266/373 1238/1238/373 1239/1239/373\nf 1266/1266/373 1239/1239/373 1267/1267/373\nf 1267/1267/373 1239/1239/373 1242/1242/373\nf 1267/1267/373 1242/1242/373 1268/1268/373\nf 1268/1268/373 1242/1242/373 1232/1232/373\nf 1268/1268/373 1232/1232/373 1269/1269/373\nf 1234/1234/392 1270/1270/392 1271/1271/392\nf 1271/1271/665 1272/1272/665 1273/1273/665\nf 1271/1271/520 1273/1273/520 1234/1234/520\nf 1241/1241/373 1274/1274/373 1275/1275/373\nf 1241/1241/373 1275/1275/373 1233/1233/373\nf 1240/1240/373 1276/1276/373 1274/1274/373\nf 1240/1240/373 1274/1274/373 1241/1241/373\nf 1237/1237/373 1277/1277/373 1276/1276/373\nf 1237/1237/373 1276/1276/373 1240/1240/373\nf 1236/1236/373 1278/1278/373 1277/1277/373\nf 1236/1236/373 1277/1277/373 1237/1237/373\nf 1279/1279/396 1280/1280/396 1281/1281/396\nf 1279/1279/396 1281/1281/396 1282/1282/396\nf 1283/1283/393 1284/1284/393 1223/1223/393\nf 1283/1283/393 1223/1223/393 1285/1285/393\nf 1286/1286/368 1273/1273/368 1272/1272/368\nf 1286/1286/368 1272/1272/368 1287/1287/368\nf 1285/1285/368 1223/1223/368 1222/1222/368\nf 1285/1285/368 1222/1222/368 1288/1288/368\nf 1288/1288/368 1222/1222/368 1273/1273/368\nf 1288/1288/368 1273/1273/368 1286/1286/368\nf 1289/1289/368 1290/1290/368 1291/1291/368\nf 1289/1289/368 1291/1291/368 1292/1292/368\nf 1293/1293/368 1294/1294/368 1295/1295/368\nf 1293/1293/368 1295/1295/368 1296/1296/368\nf 1297/1297/368 1298/1298/368 1289/1289/368\nf 1289/1289/368 1299/1299/368 1300/1300/368\nf 1289/1289/368 1300/1300/368 1297/1297/368\nf 1298/1298/368 1301/1301/368 1290/1290/368\nf 1298/1298/368 1290/1290/368 1289/1289/368\nf 1301/1301/368 1302/1302/368 1293/1293/368\nf 1301/1301/368 1293/1293/368 1290/1290/368\nf 1302/1302/368 1303/1303/368 1294/1294/368\nf 1302/1302/368 1294/1294/368 1293/1293/368\nf 1303/1303/368 1285/1285/368 1288/1288/368\nf 1303/1303/368 1288/1288/368 1294/1294/368\nf 1304/1304/368 1292/1292/368 1280/1280/368\nf 1280/1280/368 1279/1279/368 1305/1305/368\nf 1280/1280/368 1305/1305/368 1304/1304/368\nf 1292/1292/368 1291/1291/368 1306/1306/368\nf 1292/1292/368 1306/1306/368 1280/1280/368\nf 1291/1291/368 1296/1296/368 1307/1307/368\nf 1291/1291/368 1307/1307/368 1306/1306/368\nf 1296/1296/368 1295/1295/368 1308/1308/368\nf 1296/1296/368 1308/1308/368 1307/1307/368\nf 1295/1295/368 1286/1286/368 1287/1287/368\nf 1295/1295/368 1287/1287/368 1308/1308/368\nf 1309/1309/394 1298/1298/394 1297/1297/394\nf 1309/1309/666 1297/1297/666 1310/1310/666\nf 1309/1309/393 1311/1311/393 1301/1301/393\nf 1309/1309/393 1301/1301/393 1298/1298/393\nf 1311/1311/391 1312/1312/391 1302/1302/391\nf 1311/1311/391 1302/1302/391 1301/1301/391\nf 1312/1312/391 1313/1313/391 1303/1303/391\nf 1312/1312/391 1303/1303/391 1302/1302/391\nf 1313/1313/394 1283/1283/394 1285/1285/394\nf 1313/1313/394 1285/1285/394 1303/1303/394\nf 1314/1314/395 1315/1315/395 1287/1287/395\nf 1314/1314/395 1287/1287/395 1272/1272/395\nf 1315/1315/396 1316/1316/396 1308/1308/396\nf 1315/1315/396 1308/1308/396 1287/1287/396\nf 1316/1316/390 1317/1317/390 1307/1307/390\nf 1316/1316/390 1307/1307/390 1308/1308/390\nf 1317/1317/390 1318/1318/390 1306/1306/390\nf 1317/1317/390 1306/1306/390 1307/1307/390\nf 1318/1318/395 1281/1281/395 1280/1280/395\nf 1318/1318/395 1280/1280/395 1306/1306/395\nf 1224/1224/368 1227/1227/368 1315/1315/368\nf 1224/1224/368 1315/1315/368 1314/1314/368\nf 1233/1233/373 1275/1275/373 1270/1270/373\nf 1233/1233/373 1270/1270/373 1234/1234/373\nf 1269/1269/373 1232/1232/373 1221/1221/373\nf 1269/1269/373 1221/1221/373 1220/1220/373\nf 1319/1319/373 1320/1320/373 1235/1235/373\nf 1235/1235/373 1265/1265/373 1321/1321/373\nf 1235/1235/373 1321/1321/373 1319/1319/373\nf 1245/1245/395 1244/1244/395 1258/1258/395\nf 1245/1245/395 1258/1258/395 1257/1257/395\nf 1246/1246/368 1245/1245/368 1257/1257/368\nf 1257/1257/368 1309/1309/368 1310/1310/368\nf 1257/1257/368 1310/1310/368 1246/1246/368\nf 1322/1322/373 1323/1323/373 1278/1278/373\nf 1278/1278/373 1236/1236/373 1324/1324/373\nf 1278/1278/373 1324/1324/373 1322/1322/373\nf 1325/1325/389 1256/1256/389 1255/1255/389\nf 1325/1325/389 1255/1255/389 1326/1326/389\nf 1231/1231/392 1230/1230/392 1219/1219/392\nf 1219/1219/392 1223/1223/392 1284/1284/392\nf 1219/1219/392 1284/1284/392 1231/1231/392\nf 1221/1221/392 1234/1234/392 1273/1273/392\nf 1221/1221/392 1273/1273/392 1222/1222/392\nf 1282/1282/368 1281/1281/368 1253/1253/368\nf 1253/1253/368 1256/1256/368 1325/1325/368\nf 1253/1253/368 1325/1325/368 1282/1282/368\nf 1259/1259/368 1253/1253/368 1281/1281/368\nf 1259/1259/368 1281/1281/368 1318/1318/368\nf 1261/1261/368 1259/1259/368 1318/1318/368\nf 1261/1261/368 1318/1318/368 1317/1317/368\nf 1263/1263/368 1261/1261/368 1317/1317/368\nf 1263/1263/368 1317/1317/368 1316/1316/368\nf 1227/1227/368 1263/1263/368 1316/1316/368\nf 1227/1227/368 1316/1316/368 1315/1315/368\nf 1228/1228/368 1231/1231/368 1284/1284/368\nf 1228/1228/368 1284/1284/368 1283/1283/368\nf 1252/1252/368 1228/1228/368 1283/1283/368\nf 1252/1252/368 1283/1283/368 1313/1313/368\nf 1250/1250/368 1252/1252/368 1313/1313/368\nf 1250/1250/368 1313/1313/368 1312/1312/368\nf 1247/1247/368 1250/1250/368 1312/1312/368\nf 1247/1247/368 1312/1312/368 1311/1311/368\nf 1257/1257/368 1247/1247/368 1311/1311/368\nf 1257/1257/368 1311/1311/368 1309/1309/368\nf 1299/1299/667 1289/1289/667 1235/1235/667\nf 1299/1299/667 1235/1235/667 1320/1320/667\nf 1239/1239/391 1238/1238/391 1290/1290/391\nf 1239/1239/391 1290/1290/391 1293/1293/391\nf 1232/1232/393 1242/1242/393 1294/1294/393\nf 1232/1232/402 1294/1294/402 1288/1288/402\nf 1324/1324/668 1236/1236/668 1292/1292/668\nf 1324/1324/668 1292/1292/668 1304/1304/668\nf 1237/1237/390 1240/1240/390 1296/1296/390\nf 1237/1237/390 1296/1296/390 1291/1291/390\nf 1241/1241/396 1233/1233/396 1286/1286/396\nf 1241/1241/395 1286/1286/395 1295/1295/395\nf 1236/1236/389 1235/1235/389 1289/1289/389\nf 1236/1236/389 1289/1289/389 1292/1292/389\nf 1238/1238/392 1237/1237/392 1291/1291/392\nf 1238/1238/392 1291/1291/392 1290/1290/392\nf 1240/1240/389 1239/1239/389 1293/1293/389\nf 1240/1240/389 1293/1293/389 1296/1296/389\nf 1242/1242/392 1241/1241/392 1295/1295/392\nf 1242/1242/392 1295/1295/392 1294/1294/392\nf 1233/1233/389 1232/1232/389 1288/1288/389\nf 1233/1233/389 1288/1288/389 1286/1286/389\nf 1270/1270/392 1225/1225/392 1271/1271/392\nf 1255/1255/389 1327/1327/389 1326/1326/389\nf 1230/1230/392 1220/1220/392 1219/1219/392\nf 1328/1328/389 1244/1244/389 1243/1243/389\nf 1323/1323/411 1327/1327/411 1255/1255/411\nf 1255/1255/405 1254/1254/405 1278/1278/405\nf 1255/1255/414 1278/1278/414 1323/1323/414\nf 1269/1269/408 1220/1220/408 1230/1230/408\nf 1269/1269/407 1230/1230/407 1229/1229/407\nf 1270/1270/405 1275/1275/405 1226/1226/405\nf 1270/1270/405 1226/1226/405 1225/1225/405\nf 1275/1275/669 1274/1274/669 1264/1264/669\nf 1275/1275/406 1264/1264/406 1226/1226/406\nf 1274/1274/414 1276/1276/414 1262/1262/414\nf 1274/1274/670 1262/1262/670 1264/1264/670\nf 1276/1276/411 1277/1277/411 1260/1260/411\nf 1276/1276/406 1260/1260/406 1262/1262/406\nf 1277/1277/406 1278/1278/406 1254/1254/406\nf 1277/1277/406 1254/1254/406 1260/1260/406\nf 1328/1328/403 1321/1321/403 1265/1265/403\nf 1265/1265/671 1258/1258/671 1244/1244/671\nf 1265/1265/672 1244/1244/672 1328/1328/672\nf 1265/1265/673 1266/1266/673 1248/1248/673\nf 1265/1265/407 1248/1248/407 1258/1258/407\nf 1266/1266/403 1267/1267/403 1249/1249/403\nf 1266/1266/674 1249/1249/674 1248/1248/674\nf 1267/1267/404 1268/1268/404 1251/1251/404\nf 1267/1267/404 1251/1251/404 1249/1249/404\nf 1268/1268/674 1269/1269/674 1229/1229/674\nf 1268/1268/404 1229/1229/404 1251/1251/404\nf 1271/1271/392 1225/1225/392 1224/1224/392\nf 1224/1224/392 1314/1314/392 1272/1272/392\nf 1224/1224/392 1272/1272/392 1271/1271/392\nf 1246/1246/675 1310/1310/675 1297/1297/675\nf 1297/1297/676 1300/1300/676 1319/1319/676\nf 1319/1319/676 1321/1321/676 1328/1328/676\nf 1243/1243/675 1246/1246/675 1297/1297/675\nf 1319/1319/491 1328/1328/491 1243/1243/491\nf 1297/1297/677 1319/1319/677 1243/1243/677\nf 1320/1320/492 1319/1319/492 1300/1300/492\nf 1320/1320/678 1300/1300/678 1299/1299/678\nf 1304/1304/468 1305/1305/468 1322/1322/468\nf 1304/1304/679 1322/1322/679 1324/1324/679\nf 1322/1322/680 1305/1305/680 1279/1279/680\nf 1279/1279/681 1282/1282/681 1325/1325/681\nf 1326/1326/469 1327/1327/469 1323/1323/469\nf 1279/1279/680 1325/1325/680 1326/1326/680\nf 1323/1323/682 1322/1322/682 1279/1279/682\nf 1279/1279/683 1326/1326/683 1323/1323/683\nf 1329/1329/438 1330/1330/438 1331/1331/438\nf 1329/1329/439 1331/1331/439 1332/1332/439\nf 1332/1332/440 1331/1331/440 1333/1333/440\nf 1332/1332/455 1333/1333/455 1334/1334/455\nf 1334/1334/441 1333/1333/441 1335/1335/441\nf 1334/1334/441 1335/1335/441 1336/1336/441\nf 1336/1336/442 1335/1335/442 1337/1337/442\nf 1336/1336/442 1337/1337/442 1338/1338/442\nf 1338/1338/443 1337/1337/443 1339/1339/443\nf 1338/1338/444 1339/1339/444 1340/1340/444\nf 1340/1340/445 1339/1339/445 1341/1341/445\nf 1340/1340/445 1341/1341/445 1342/1342/445\nf 1342/1342/447 1341/1341/447 1343/1343/447\nf 1342/1342/447 1343/1343/447 1344/1344/447\nf 1344/1344/659 1343/1343/659 1345/1345/659\nf 1344/1344/659 1345/1345/659 1346/1346/659\nf 1346/1346/428 1345/1345/428 1347/1347/428\nf 1346/1346/428 1347/1347/428 1348/1348/428\nf 1348/1348/429 1347/1347/429 1349/1349/429\nf 1348/1348/429 1349/1349/429 1350/1350/429\nf 1350/1350/430 1349/1349/430 1351/1351/430\nf 1350/1350/430 1351/1351/430 1352/1352/430\nf 1352/1352/431 1351/1351/431 1353/1353/431\nf 1352/1352/431 1353/1353/431 1354/1354/431\nf 1354/1354/432 1353/1353/432 1355/1355/432\nf 1354/1354/433 1355/1355/433 1356/1356/433\nf 1356/1356/435 1355/1355/435 1357/1357/435\nf 1356/1356/435 1357/1357/435 1358/1358/435\nf 1358/1358/436 1357/1357/436 1359/1359/436\nf 1358/1358/684 1359/1359/684 1360/1360/684\nf 1360/1360/374 1359/1359/374 1330/1330/374\nf 1360/1360/437 1330/1330/437 1329/1329/437\nf 1361/1361/373 1362/1362/373 1331/1331/373\nf 1361/1361/373 1331/1331/373 1330/1330/373\nf 1362/1362/373 1363/1363/373 1333/1333/373\nf 1362/1362/373 1333/1333/373 1331/1331/373\nf 1363/1363/373 1364/1364/373 1335/1335/373\nf 1363/1363/373 1335/1335/373 1333/1333/373\nf 1364/1364/373 1365/1365/373 1337/1337/373\nf 1364/1364/373 1337/1337/373 1335/1335/373\nf 1365/1365/373 1366/1366/373 1339/1339/373\nf 1365/1365/373 1339/1339/373 1337/1337/373\nf 1366/1366/373 1367/1367/373 1341/1341/373\nf 1366/1366/373 1341/1341/373 1339/1339/373\nf 1367/1367/373 1368/1368/373 1343/1343/373\nf 1367/1367/373 1343/1343/373 1341/1341/373\nf 1368/1368/373 1369/1369/373 1345/1345/373\nf 1368/1368/373 1345/1345/373 1343/1343/373\nf 1369/1369/373 1370/1370/373 1347/1347/373\nf 1369/1369/373 1347/1347/373 1345/1345/373\nf 1370/1370/373 1371/1371/373 1349/1349/373\nf 1370/1370/373 1349/1349/373 1347/1347/373\nf 1371/1371/373 1372/1372/373 1351/1351/373\nf 1371/1371/373 1351/1351/373 1349/1349/373\nf 1372/1372/373 1373/1373/373 1353/1353/373\nf 1372/1372/373 1353/1353/373 1351/1351/373\nf 1373/1373/373 1374/1374/373 1355/1355/373\nf 1373/1373/373 1355/1355/373 1353/1353/373\nf 1374/1374/373 1375/1375/373 1357/1357/373\nf 1374/1374/373 1357/1357/373 1355/1355/373\nf 1375/1375/373 1376/1376/373 1359/1359/373\nf 1375/1375/373 1359/1359/373 1357/1357/373\nf 1376/1376/373 1361/1361/373 1330/1330/373\nf 1376/1376/373 1330/1330/373 1359/1359/373\nf 1376/1376/685 1375/1375/685 1377/1377/685\nf 1376/1376/446 1377/1377/446 1378/1378/446\nf 1379/1379/373 1380/1380/373 1381/1381/373\nf 1381/1381/373 1382/1382/373 1383/1383/373\nf 1383/1383/373 1378/1378/373 1377/1377/373\nf 1377/1377/373 1384/1384/373 1385/1385/373\nf 1385/1385/373 1386/1386/373 1387/1387/373\nf 1387/1387/373 1388/1388/373 1389/1389/373\nf 1387/1387/373 1389/1389/373 1390/1390/373\nf 1379/1379/373 1381/1381/373 1383/1383/373\nf 1391/1391/373 1379/1379/373 1383/1383/373\nf 1385/1385/373 1387/1387/373 1390/1390/373\nf 1385/1385/373 1390/1390/373 1392/1392/373\nf 1393/1393/373 1391/1391/373 1383/1383/373\nf 1394/1394/373 1393/1393/373 1383/1383/373\nf 1377/1377/373 1385/1385/373 1392/1392/373\nf 1377/1377/373 1392/1392/373 1395/1395/373\nf 1394/1394/373 1383/1383/373 1377/1377/373\nf 1377/1377/373 1395/1395/373 1394/1394/373\nf 1396/1396/373 1388/1388/373 1387/1387/373\nf 1387/1387/373 1397/1397/373 1398/1398/373\nf 1398/1398/373 1399/1399/373 1400/1400/373\nf 1400/1400/373 1401/1401/373 1402/1402/373\nf 1402/1402/373 1403/1403/373 1381/1381/373\nf 1381/1381/373 1380/1380/373 1404/1404/373\nf 1381/1381/373 1404/1404/373 1405/1405/373\nf 1396/1396/373 1387/1387/373 1398/1398/373\nf 1406/1406/373 1396/1396/373 1398/1398/373\nf 1402/1402/373 1381/1381/373 1405/1405/373\nf 1402/1402/373 1405/1405/373 1407/1407/373\nf 1408/1408/373 1406/1406/373 1398/1398/373\nf 1409/1409/373 1408/1408/373 1398/1398/373\nf 1400/1400/373 1402/1402/373 1407/1407/373\nf 1400/1400/373 1407/1407/373 1410/1410/373\nf 1409/1409/373 1398/1398/373 1400/1400/373\nf 1400/1400/373 1410/1410/373 1409/1409/373\nf 1369/1369/686 1368/1368/686 1399/1399/686\nf 1369/1369/452 1399/1399/452 1398/1398/452\nf 1362/1362/687 1361/1361/687 1383/1383/687\nf 1362/1362/454 1383/1383/454 1382/1382/454\nf 1361/1361/450 1376/1376/450 1378/1378/450\nf 1361/1361/381 1378/1378/381 1383/1383/381\nf 1370/1370/451 1369/1369/451 1398/1398/451\nf 1370/1370/439 1398/1398/439 1397/1397/439\nf 1363/1363/456 1362/1362/456 1382/1382/456\nf 1363/1363/456 1382/1382/456 1381/1381/456\nf 1371/1371/455 1370/1370/455 1397/1397/455\nf 1371/1371/455 1397/1397/455 1387/1387/455\nf 1364/1364/459 1363/1363/459 1381/1381/459\nf 1364/1364/459 1381/1381/459 1403/1403/459\nf 1372/1372/457 1371/1371/457 1387/1387/457\nf 1372/1372/688 1387/1387/688 1386/1386/688\nf 1365/1365/377 1364/1364/377 1403/1403/377\nf 1365/1365/377 1403/1403/377 1402/1402/377\nf 1373/1373/382 1372/1372/382 1386/1386/382\nf 1373/1373/382 1386/1386/382 1385/1385/382\nf 1366/1366/465 1365/1365/465 1402/1402/465\nf 1366/1366/465 1402/1402/465 1401/1401/465\nf 1374/1374/463 1373/1373/463 1385/1385/463\nf 1374/1374/443 1385/1385/443 1384/1384/443\nf 1367/1367/689 1366/1366/689 1401/1401/689\nf 1367/1367/467 1401/1401/467 1400/1400/467\nf 1375/1375/466 1374/1374/466 1384/1384/466\nf 1375/1375/466 1384/1384/466 1377/1377/466\nf 1368/1368/448 1367/1367/448 1400/1400/448\nf 1368/1368/684 1400/1400/684 1399/1399/684\nf 1411/1411/368 1360/1360/368 1329/1329/368\nf 1329/1329/368 1332/1332/368 1334/1334/368\nf 1334/1334/368 1336/1336/368 1338/1338/368\nf 1338/1338/368 1340/1340/368 1342/1342/368\nf 1342/1342/368 1344/1344/368 1412/1412/368\nf 1342/1342/368 1412/1412/368 1413/1413/368\nf 1414/1414/368 1411/1411/368 1329/1329/368\nf 1415/1415/368 1414/1414/368 1329/1329/368\nf 1342/1342/368 1413/1413/368 1416/1416/368\nf 1342/1342/368 1416/1416/368 1417/1417/368\nf 1415/1415/368 1329/1329/368 1334/1334/368\nf 1418/1418/368 1415/1415/368 1334/1334/368\nf 1338/1338/368 1342/1342/368 1417/1417/368\nf 1338/1338/368 1417/1417/368 1419/1419/368\nf 1420/1420/368 1418/1418/368 1334/1334/368\nf 1338/1338/368 1419/1419/368 1420/1420/368\nf 1334/1334/368 1338/1338/368 1420/1420/368\nf 1421/1421/368 1412/1412/368 1344/1344/368\nf 1344/1344/368 1346/1346/368 1348/1348/368\nf 1348/1348/368 1350/1350/368 1352/1352/368\nf 1352/1352/368 1354/1354/368 1356/1356/368\nf 1356/1356/368 1358/1358/368 1360/1360/368\nf 1360/1360/368 1411/1411/368 1422/1422/368\nf 1360/1360/368 1422/1422/368 1423/1423/368\nf 1421/1421/368 1344/1344/368 1348/1348/368\nf 1424/1424/368 1421/1421/368 1348/1348/368\nf 1356/1356/368 1360/1360/368 1423/1423/368\nf 1356/1356/368 1423/1423/368 1425/1425/368\nf 1426/1426/368 1424/1424/368 1348/1348/368\nf 1427/1427/368 1426/1426/368 1348/1348/368\nf 1352/1352/368 1356/1356/368 1425/1425/368\nf 1352/1352/368 1425/1425/368 1428/1428/368\nf 1427/1427/368 1348/1348/368 1352/1352/368\nf 1352/1352/368 1428/1428/368 1427/1427/368\nf 1416/1416/482 1413/1413/482 1409/1409/482\nf 1416/1416/482 1409/1409/482 1410/1410/482\nf 1421/1421/483 1408/1408/483 1409/1409/483\nf 1409/1409/690 1413/1413/690 1412/1412/690\nf 1409/1409/424 1412/1412/424 1421/1421/424\nf 1408/1408/484 1421/1421/484 1424/1424/484\nf 1408/1408/485 1424/1424/485 1406/1406/485\nf 1424/1424/486 1426/1426/486 1396/1396/486\nf 1424/1424/486 1396/1396/486 1406/1406/486\nf 1396/1396/487 1426/1426/487 1427/1427/487\nf 1427/1427/691 1389/1389/691 1388/1388/691\nf 1427/1427/692 1388/1388/692 1396/1396/692\nf 1428/1428/489 1390/1390/489 1389/1389/489\nf 1428/1428/628 1389/1389/628 1427/1427/628\nf 1425/1425/491 1392/1392/491 1390/1390/491\nf 1425/1425/491 1390/1390/491 1428/1428/491\nf 1423/1423/492 1395/1395/492 1392/1392/492\nf 1423/1423/492 1392/1392/492 1425/1425/492\nf 1422/1422/468 1394/1394/468 1395/1395/468\nf 1422/1422/468 1395/1395/468 1423/1423/468\nf 1393/1393/469 1394/1394/469 1422/1422/469\nf 1411/1411/680 1414/1414/680 1393/1393/680\nf 1422/1422/683 1411/1411/683 1393/1393/683\nf 1415/1415/472 1391/1391/472 1393/1393/472\nf 1415/1415/473 1393/1393/473 1414/1414/473\nf 1418/1418/474 1379/1379/474 1391/1391/474\nf 1418/1418/474 1391/1391/474 1415/1415/474\nf 1418/1418/475 1420/1420/475 1404/1404/475\nf 1380/1380/475 1379/1379/475 1418/1418/475\nf 1404/1404/693 1380/1380/693 1418/1418/693\nf 1405/1405/542 1404/1404/542 1420/1420/542\nf 1405/1405/542 1420/1420/542 1419/1419/542\nf 1405/1405/418 1419/1419/418 1417/1417/418\nf 1405/1405/652 1417/1417/652 1407/1407/652\nf 1417/1417/481 1416/1416/481 1410/1410/481\nf 1417/1417/481 1410/1410/481 1407/1407/481\ng cf_metal\nusemtl metal\nf 1430/1432/417 1431/1435/417 1429/1429/417\nf 1432/1437/596 1433/1439/596 1431/1435/596\nf 1434/1441/423 1435/1443/423 1433/1439/423\nf 1436/1445/424 1437/1447/424 1435/1443/424\nf 1438/1449/594 1439/1451/594 1437/1447/594\nf 1440/1453/694 1441/1455/694 1439/1451/694\nf 1442/1457/691 1443/1459/691 1441/1455/691\nf 1444/1461/626 1445/1463/626 1443/1459/626\nf 1446/1465/676 1447/1467/676 1445/1463/676\nf 1448/1469/648 1449/1471/648 1447/1467/648\nf 1450/1473/695 1451/1475/695 1449/1471/695\nf 1452/1477/680 1453/1479/680 1451/1475/680\nf 1454/1481/548 1455/1483/548 1453/1479/548\nf 1456/1485/696 1457/1487/696 1455/1483/696\nf 1450/1474/373 1442/1458/373 1434/1442/373\nf 1458/1490/697 1459/1491/697 1457/1487/697\nf 1460/1494/541 1429/1430/541 1459/1491/541\nf 1443/1460/368 1451/1476/368 1459/1492/368\nf 1463/1501/541 1462/1498/541 1461/1495/541\nf 1465/1505/476 1464/1503/476 1463/1501/476\nf 1467/1509/698 1466/1507/698 1465/1505/698\nf 1469/1513/548 1468/1511/548 1467/1509/548\nf 1471/1517/680 1470/1515/680 1469/1513/680\nf 1473/1521/699 1472/1519/699 1471/1517/699\nf 1475/1525/648 1474/1523/648 1473/1521/648\nf 1477/1529/676 1476/1527/676 1475/1525/676\nf 1479/1533/626 1478/1531/626 1477/1529/626\nf 1481/1537/691 1480/1535/691 1479/1533/691\nf 1483/1541/694 1482/1539/694 1481/1537/694\nf 1485/1545/594 1484/1543/594 1483/1541/594\nf 1487/1549/424 1486/1547/424 1485/1545/424\nf 1489/1553/700 1488/1551/700 1487/1549/700\nf 1478/1532/373 1486/1548/373 1462/1499/373\nf 1491/1557/596 1490/1556/596 1489/1553/596\nf 1461/1496/417 1492/1560/417 1491/1557/417\nf 1479/1534/368 1471/1518/368 1463/1502/368\nf 1495/1567/626 1494/1564/626 1493/1561/626\nf 1497/1571/691 1496/1569/691 1495/1567/691\nf 1499/1575/694 1498/1573/694 1497/1571/694\nf 1501/1579/594 1500/1577/594 1499/1575/594\nf 1503/1583/424 1502/1581/424 1501/1579/424\nf 1505/1587/423 1504/1585/423 1503/1583/423\nf 1507/1591/596 1506/1589/596 1505/1587/596\nf 1509/1595/417 1508/1593/417 1507/1591/417\nf 1511/1599/541 1510/1597/541 1509/1595/541\nf 1513/1603/476 1512/1601/476 1511/1599/476\nf 1515/1607/701 1514/1605/701 1513/1603/701\nf 1517/1611/548 1516/1609/548 1515/1607/548\nf 1519/1615/680 1518/1613/680 1517/1611/680\nf 1521/1619/695 1520/1617/695 1519/1615/695\nf 1510/1598/373 1518/1614/373 1494/1565/373\nf 1523/1623/648 1522/1622/648 1521/1619/648\nf 1493/1562/676 1524/1626/676 1523/1623/676\nf 1511/1600/368 1503/1584/368 1495/1568/368\nf 1526/1630/676 1527/1633/676 1525/1627/676\nf 1528/1635/648 1529/1637/648 1527/1633/648\nf 1530/1639/699 1531/1641/699 1529/1637/699\nf 1532/1643/680 1533/1645/680 1531/1641/680\nf 1534/1647/548 1535/1649/548 1533/1645/548\nf 1536/1651/698 1537/1653/698 1535/1649/698\nf 1538/1655/476 1539/1657/476 1537/1653/476\nf 1540/1659/541 1541/1661/541 1539/1657/541\nf 1542/1663/417 1543/1665/417 1541/1661/417\nf 1544/1667/596 1545/1669/596 1543/1665/596\nf 1546/1671/423 1547/1673/423 1545/1669/423\nf 1548/1675/424 1549/1677/424 1547/1673/424\nf 1550/1679/594 1551/1681/594 1549/1677/594\nf 1552/1683/702 1553/1685/702 1551/1681/702\nf 1546/1672/373 1538/1656/373 1530/1640/373\nf 1554/1688/691 1555/1689/691 1553/1685/691\nf 1556/1692/626 1525/1628/626 1555/1689/626\nf 1539/1658/368 1547/1674/368 1555/1690/368\nf 1430/1432/417 1432/1437/417 1431/1435/417\nf 1432/1437/481 1434/1441/481 1433/1439/481\nf 1434/1441/423 1436/1445/423 1435/1443/423\nf 1436/1445/424 1438/1449/424 1437/1447/424\nf 1438/1449/594 1440/1453/594 1439/1451/594\nf 1440/1453/694 1442/1457/694 1441/1455/694\nf 1442/1457/691 1444/1461/691 1443/1459/691\nf 1444/1461/626 1446/1465/626 1445/1463/626\nf 1446/1465/676 1448/1469/676 1447/1467/676\nf 1448/1469/648 1450/1473/648 1449/1471/648\nf 1450/1473/703 1452/1477/703 1451/1475/703\nf 1452/1477/680 1454/1481/680 1453/1479/680\nf 1454/1481/548 1456/1485/548 1455/1483/548\nf 1456/1485/698 1458/1490/698 1457/1487/698\nf 1434/1442/373 1432/1438/373 1430/1433/373\nf 1430/1433/373 1460/1493/373 1458/1489/373\nf 1458/1489/373 1456/1486/373 1454/1482/373\nf 1454/1482/373 1452/1478/373 1450/1474/373\nf 1450/1474/373 1448/1470/373 1446/1466/373\nf 1446/1466/373 1444/1462/373 1442/1458/373\nf 1442/1458/373 1440/1454/373 1438/1450/373\nf 1438/1450/373 1436/1446/373 1434/1442/373\nf 1434/1442/373 1430/1433/373 1458/1489/373\nf 1458/1489/373 1454/1482/373 1450/1474/373\nf 1450/1474/373 1446/1466/373 1442/1458/373\nf 1442/1458/373 1438/1450/373 1434/1442/373\nf 1434/1442/373 1458/1489/373 1450/1474/373\nf 1458/1490/475 1460/1494/475 1459/1491/475\nf 1460/1494/541 1430/1434/541 1429/1430/541\nf 1459/1492/368 1429/1431/368 1431/1436/368\nf 1431/1436/368 1433/1440/368 1435/1444/368\nf 1435/1444/368 1437/1448/368 1439/1452/368\nf 1439/1452/368 1441/1456/368 1443/1460/368\nf 1443/1460/368 1445/1464/368 1447/1468/368\nf 1447/1468/368 1449/1472/368 1451/1476/368\nf 1451/1476/368 1453/1480/368 1455/1484/368\nf 1455/1484/368 1457/1488/368 1459/1492/368\nf 1459/1492/368 1431/1436/368 1435/1444/368\nf 1435/1444/368 1439/1452/368 1443/1460/368\nf 1443/1460/368 1447/1468/368 1451/1476/368\nf 1451/1476/368 1455/1484/368 1459/1492/368\nf 1459/1492/368 1435/1444/368 1443/1460/368\nf 1463/1501/541 1464/1503/541 1462/1498/541\nf 1465/1505/475 1466/1507/475 1464/1503/475\nf 1467/1509/698 1468/1511/698 1466/1507/698\nf 1469/1513/548 1470/1515/548 1468/1511/548\nf 1471/1517/680 1472/1519/680 1470/1515/680\nf 1473/1521/699 1474/1523/699 1472/1519/699\nf 1475/1525/648 1476/1527/648 1474/1523/648\nf 1477/1529/676 1478/1531/676 1476/1527/676\nf 1479/1533/626 1480/1535/626 1478/1531/626\nf 1481/1537/691 1482/1539/691 1480/1535/691\nf 1483/1541/704 1484/1543/704 1482/1539/704\nf 1485/1545/594 1486/1547/594 1484/1543/594\nf 1487/1549/424 1488/1551/424 1486/1547/424\nf 1489/1553/423 1490/1556/423 1488/1551/423\nf 1462/1499/373 1464/1504/373 1466/1508/373\nf 1466/1508/373 1468/1512/373 1470/1516/373\nf 1470/1516/373 1472/1520/373 1474/1524/373\nf 1474/1524/373 1476/1528/373 1478/1532/373\nf 1478/1532/373 1480/1536/373 1482/1540/373\nf 1482/1540/373 1484/1544/373 1486/1548/373\nf 1486/1548/373 1488/1552/373 1490/1555/373\nf 1490/1555/373 1492/1559/373 1462/1499/373\nf 1462/1499/373 1466/1508/373 1470/1516/373\nf 1470/1516/373 1474/1524/373 1478/1532/373\nf 1478/1532/373 1482/1540/373 1486/1548/373\nf 1486/1548/373 1490/1555/373 1462/1499/373\nf 1462/1499/373 1470/1516/373 1478/1532/373\nf 1491/1557/596 1492/1560/596 1490/1556/596\nf 1461/1496/417 1462/1500/417 1492/1560/417\nf 1463/1502/368 1461/1497/368 1491/1558/368\nf 1491/1558/368 1489/1554/368 1487/1550/368\nf 1487/1550/368 1485/1546/368 1483/1542/368\nf 1483/1542/368 1481/1538/368 1479/1534/368\nf 1479/1534/368 1477/1530/368 1475/1526/368\nf 1475/1526/368 1473/1522/368 1471/1518/368\nf 1471/1518/368 1469/1514/368 1467/1510/368\nf 1467/1510/368 1465/1506/368 1463/1502/368\nf 1463/1502/368 1491/1558/368 1487/1550/368\nf 1487/1550/368 1483/1542/368 1479/1534/368\nf 1479/1534/368 1475/1526/368 1471/1518/368\nf 1471/1518/368 1467/1510/368 1463/1502/368\nf 1463/1502/368 1487/1550/368 1479/1534/368\nf 1495/1567/626 1496/1569/626 1494/1564/626\nf 1497/1571/691 1498/1573/691 1496/1569/691\nf 1499/1575/694 1500/1577/694 1498/1573/694\nf 1501/1579/594 1502/1581/594 1500/1577/594\nf 1503/1583/424 1504/1585/424 1502/1581/424\nf 1505/1587/423 1506/1589/423 1504/1585/423\nf 1507/1591/596 1508/1593/596 1506/1589/596\nf 1509/1595/417 1510/1597/417 1508/1593/417\nf 1511/1599/541 1512/1601/541 1510/1597/541\nf 1513/1603/476 1514/1605/476 1512/1601/476\nf 1515/1607/705 1516/1609/705 1514/1605/705\nf 1517/1611/548 1518/1613/548 1516/1609/548\nf 1519/1615/680 1520/1617/680 1518/1613/680\nf 1521/1619/703 1522/1622/703 1520/1617/703\nf 1494/1565/373 1496/1570/373 1498/1574/373\nf 1498/1574/373 1500/1578/373 1502/1582/373\nf 1502/1582/373 1504/1586/373 1506/1590/373\nf 1506/1590/373 1508/1594/373 1510/1598/373\nf 1510/1598/373 1512/1602/373 1514/1606/373\nf 1514/1606/373 1516/1610/373 1518/1614/373\nf 1518/1614/373 1520/1618/373 1522/1621/373\nf 1522/1621/373 1524/1625/373 1494/1565/373\nf 1494/1565/373 1498/1574/373 1502/1582/373\nf 1502/1582/373 1506/1590/373 1510/1598/373\nf 1510/1598/373 1514/1606/373 1518/1614/373\nf 1518/1614/373 1522/1621/373 1494/1565/373\nf 1494/1565/373 1502/1582/373 1510/1598/373\nf 1523/1623/648 1524/1626/648 1522/1622/648\nf 1493/1562/676 1494/1566/676 1524/1626/676\nf 1495/1568/368 1493/1563/368 1523/1624/368\nf 1523/1624/368 1521/1620/368 1519/1616/368\nf 1519/1616/368 1517/1612/368 1515/1608/368\nf 1515/1608/368 1513/1604/368 1511/1600/368\nf 1511/1600/368 1509/1596/368 1507/1592/368\nf 1507/1592/368 1505/1588/368 1503/1584/368\nf 1503/1584/368 1501/1580/368 1499/1576/368\nf 1499/1576/368 1497/1572/368 1495/1568/368\nf 1495/1568/368 1523/1624/368 1519/1616/368\nf 1519/1616/368 1515/1608/368 1511/1600/368\nf 1511/1600/368 1507/1592/368 1503/1584/368\nf 1503/1584/368 1499/1576/368 1495/1568/368\nf 1495/1568/368 1519/1616/368 1511/1600/368\nf 1526/1630/676 1528/1635/676 1527/1633/676\nf 1528/1635/648 1530/1639/648 1529/1637/648\nf 1530/1639/699 1532/1643/699 1531/1641/699\nf 1532/1643/680 1534/1647/680 1533/1645/680\nf 1534/1647/548 1536/1651/548 1535/1649/548\nf 1536/1651/698 1538/1655/698 1537/1653/698\nf 1538/1655/476 1540/1659/476 1539/1657/476\nf 1540/1659/541 1542/1663/541 1541/1661/541\nf 1542/1663/417 1544/1667/417 1543/1665/417\nf 1544/1667/596 1546/1671/596 1545/1669/596\nf 1546/1671/706 1548/1675/706 1547/1673/706\nf 1548/1675/424 1550/1679/424 1549/1677/424\nf 1550/1679/594 1552/1683/594 1551/1681/594\nf 1552/1683/694 1554/1688/694 1553/1685/694\nf 1530/1640/373 1528/1636/373 1526/1631/373\nf 1526/1631/373 1556/1691/373 1554/1687/373\nf 1554/1687/373 1552/1684/373 1550/1680/373\nf 1550/1680/373 1548/1676/373 1546/1672/373\nf 1546/1672/373 1544/1668/373 1542/1664/373\nf 1542/1664/373 1540/1660/373 1538/1656/373\nf 1538/1656/373 1536/1652/373 1534/1648/373\nf 1534/1648/373 1532/1644/373 1530/1640/373\nf 1530/1640/373 1526/1631/373 1554/1687/373\nf 1554/1687/373 1550/1680/373 1546/1672/373\nf 1546/1672/373 1542/1664/373 1538/1656/373\nf 1538/1656/373 1534/1648/373 1530/1640/373\nf 1530/1640/373 1554/1687/373 1546/1672/373\nf 1554/1688/691 1556/1692/691 1555/1689/691\nf 1556/1692/626 1526/1632/626 1525/1628/626\nf 1555/1690/368 1525/1629/368 1527/1634/368\nf 1527/1634/368 1529/1638/368 1531/1642/368\nf 1531/1642/368 1533/1646/368 1535/1650/368\nf 1535/1650/368 1537/1654/368 1539/1658/368\nf 1539/1658/368 1541/1662/368 1543/1666/368\nf 1543/1666/368 1545/1670/368 1547/1674/368\nf 1547/1674/368 1549/1678/368 1551/1682/368\nf 1551/1682/368 1553/1686/368 1555/1690/368\nf 1555/1690/368 1527/1634/368 1531/1642/368\nf 1531/1642/368 1535/1650/368 1539/1658/368\nf 1539/1658/368 1543/1666/368 1547/1674/368\nf 1547/1674/368 1551/1682/368 1555/1690/368\nf 1555/1690/368 1531/1642/368 1539/1658/368\nf 1751/1887/373 1752/1888/373 1753/1889/373\nf 1751/1887/373 1753/1889/373 1754/1890/373\nf 1755/1891/743 1754/1890/743 1753/1889/743\nf 1755/1891/743 1753/1889/743 1756/1892/743\nf 1756/1892/745 1753/1889/745 1752/1888/745\nf 1756/1892/745 1752/1888/745 1757/1893/745\nf 1757/1893/368 1758/1894/368 1755/1891/368\nf 1757/1893/368 1755/1891/368 1756/1892/368\nf 1758/1894/742 1751/1887/742 1754/1890/742\nf 1758/1894/742 1754/1890/742 1755/1891/742\nf 1757/1893/747 1752/1888/747 1751/1887/747\nf 1757/1893/747 1751/1887/747 1758/1894/747\nf 1759/1895/373 1760/1896/373 1761/1897/373\nf 1759/1895/373 1761/1897/373 1762/1898/373\nf 1763/1899/743 1762/1898/743 1761/1897/743\nf 1763/1899/743 1761/1897/743 1764/1900/743\nf 1764/1900/745 1761/1897/745 1760/1896/745\nf 1764/1900/745 1760/1896/745 1765/1901/745\nf 1765/1901/368 1766/1902/368 1763/1899/368\nf 1765/1901/368 1763/1899/368 1764/1900/368\nf 1766/1902/742 1759/1895/742 1762/1898/742\nf 1766/1902/742 1762/1898/742 1763/1899/742\nf 1765/1901/747 1760/1896/747 1759/1895/747\nf 1765/1901/747 1759/1895/747 1766/1902/747\nf 1767/1903/373 1768/1904/373 1769/1905/373\nf 1767/1903/373 1769/1905/373 1770/1906/373\nf 1771/1907/743 1770/1906/743 1769/1905/743\nf 1771/1907/743 1769/1905/743 1772/1908/743\nf 1772/1908/745 1769/1905/745 1768/1904/745\nf 1772/1908/745 1768/1904/745 1773/1909/745\nf 1773/1909/368 1774/1910/368 1771/1907/368\nf 1773/1909/368 1771/1907/368 1772/1908/368\nf 1774/1910/742 1767/1903/742 1770/1906/742\nf 1774/1910/742 1770/1906/742 1771/1907/742\nf 1773/1909/747 1768/1904/747 1767/1903/747\nf 1773/1909/747 1767/1903/747 1774/1910/747\nf 1775/1911/373 1776/1912/373 1777/1913/373\nf 1775/1911/373 1777/1913/373 1778/1914/373\nf 1779/1915/743 1778/1914/743 1777/1913/743\nf 1779/1915/743 1777/1913/743 1780/1916/743\nf 1780/1916/745 1777/1913/745 1776/1912/745\nf 1780/1916/745 1776/1912/745 1781/1917/745\nf 1781/1917/368 1782/1918/368 1779/1915/368\nf 1781/1917/368 1779/1915/368 1780/1916/368\nf 1782/1918/742 1775/1911/742 1778/1914/742\nf 1782/1918/742 1778/1914/742 1779/1915/742\nf 1781/1917/747 1776/1912/747 1775/1911/747\nf 1781/1917/747 1775/1911/747 1782/1918/747\nf 1783/1919/373 1784/1920/373 1785/1921/373\nf 1783/1919/373 1785/1921/373 1786/1922/373\nf 1787/1923/743 1786/1922/743 1785/1921/743\nf 1787/1923/743 1785/1921/743 1788/1924/743\nf 1788/1924/745 1785/1921/745 1784/1920/745\nf 1788/1924/745 1784/1920/745 1789/1925/745\nf 1789/1925/368 1790/1926/368 1787/1923/368\nf 1789/1925/368 1787/1923/368 1788/1924/368\nf 1790/1926/742 1783/1919/742 1786/1922/742\nf 1790/1926/742 1786/1922/742 1787/1923/742\nf 1789/1925/747 1784/1920/747 1783/1919/747\nf 1789/1925/747 1783/1919/747 1790/1926/747\nf 1791/1927/373 1792/1928/373 1793/1929/373\nf 1791/1927/373 1793/1929/373 1794/1930/373\nf 1795/1931/743 1794/1930/743 1793/1929/743\nf 1795/1931/743 1793/1929/743 1796/1932/743\nf 1796/1932/745 1793/1929/745 1792/1928/745\nf 1796/1932/745 1792/1928/745 1797/1933/745\nf 1797/1933/368 1798/1934/368 1795/1931/368\nf 1797/1933/368 1795/1931/368 1796/1932/368\nf 1798/1934/742 1791/1927/742 1794/1930/742\nf 1798/1934/742 1794/1930/742 1795/1931/742\nf 1797/1933/747 1792/1928/747 1791/1927/747\nf 1797/1933/747 1791/1927/747 1798/1934/747\nf 1799/1935/373 1800/1936/373 1801/1937/373\nf 1799/1935/373 1801/1937/373 1802/1938/373\nf 1803/1939/743 1802/1938/743 1801/1937/743\nf 1803/1939/743 1801/1937/743 1804/1940/743\nf 1804/1940/745 1801/1937/745 1800/1936/745\nf 1804/1940/745 1800/1936/745 1805/1941/745\nf 1805/1941/368 1806/1942/368 1803/1939/368\nf 1805/1941/368 1803/1939/368 1804/1940/368\nf 1806/1942/742 1799/1935/742 1802/1938/742\nf 1806/1942/742 1802/1938/742 1803/1939/742\nf 1805/1941/747 1800/1936/747 1799/1935/747\nf 1805/1941/747 1799/1935/747 1806/1942/747\nf 1807/1943/373 1808/1944/373 1809/1945/373\nf 1807/1943/373 1809/1945/373 1810/1946/373\nf 1811/1947/743 1810/1946/743 1809/1945/743\nf 1811/1947/743 1809/1945/743 1812/1948/743\nf 1812/1948/745 1809/1945/745 1808/1944/745\nf 1812/1948/745 1808/1944/745 1813/1949/745\nf 1813/1949/368 1814/1950/368 1811/1947/368\nf 1813/1949/368 1811/1947/368 1812/1948/368\nf 1814/1950/742 1807/1943/742 1810/1946/742\nf 1814/1950/742 1810/1946/742 1811/1947/742\nf 1813/1949/747 1808/1944/747 1807/1943/747\nf 1813/1949/747 1807/1943/747 1814/1950/747\nf 1815/1951/373 1816/1952/373 1817/1953/373\nf 1815/1951/373 1817/1953/373 1818/1954/373\nf 1819/1955/743 1818/1954/743 1817/1953/743\nf 1819/1955/743 1817/1953/743 1820/1956/743\nf 1820/1956/745 1817/1953/745 1816/1952/745\nf 1820/1956/745 1816/1952/745 1821/1957/745\nf 1821/1957/368 1822/1958/368 1819/1955/368\nf 1821/1957/368 1819/1955/368 1820/1956/368\nf 1822/1958/742 1815/1951/742 1818/1954/742\nf 1822/1958/742 1818/1954/742 1819/1955/742\nf 1821/1957/747 1816/1952/747 1815/1951/747\nf 1821/1957/747 1815/1951/747 1822/1958/747\nf 1823/1959/373 1824/1960/373 1825/1961/373\nf 1823/1959/373 1825/1961/373 1826/1962/373\nf 1827/1963/743 1826/1962/743 1825/1961/743\nf 1827/1963/743 1825/1961/743 1828/1964/743\nf 1828/1964/745 1825/1961/745 1824/1960/745\nf 1828/1964/745 1824/1960/745 1829/1965/745\nf 1829/1965/368 1830/1966/368 1827/1963/368\nf 1829/1965/368 1827/1963/368 1828/1964/368\nf 1830/1966/742 1823/1959/742 1826/1962/742\nf 1830/1966/742 1826/1962/742 1827/1963/742\nf 1829/1965/747 1824/1960/747 1823/1959/747\nf 1829/1965/747 1823/1959/747 1830/1966/747\nf 1831/1967/745 1832/1968/745 1833/1969/745\nf 1831/1967/745 1833/1969/745 1834/1970/745\nf 1834/1970/747 1833/1969/747 1835/1971/747\nf 1834/1970/747 1835/1971/747 1836/1972/747\nf 1836/1972/742 1835/1971/742 1837/1973/742\nf 1836/1972/742 1837/1973/742 1838/1974/742\nf 1838/1974/743 1837/1973/743 1832/1968/743\nf 1838/1974/743 1832/1968/743 1831/1967/743\nf 1834/1970/368 1836/1972/368 1838/1974/368\nf 1834/1970/368 1838/1974/368 1831/1967/368\nf 1835/1971/373 1833/1969/373 1832/1968/373\nf 1835/1971/373 1832/1968/373 1837/1973/373\nf 1839/1975/373 1841/1977/373 1840/1976/373\nf 1839/1975/373 1842/1978/373 1841/1977/373\nf 1843/1979/747 1841/1977/747 1842/1978/747\nf 1843/1979/747 1844/1980/747 1841/1977/747\nf 1844/1980/745 1840/1976/745 1841/1977/745\nf 1844/1980/745 1845/1981/745 1840/1976/745\nf 1845/1981/368 1843/1979/368 1846/1982/368\nf 1845/1981/368 1844/1980/368 1843/1979/368\nf 1846/1982/742 1842/1978/742 1839/1975/742\nf 1846/1982/742 1843/1979/742 1842/1978/742\nf 1845/1981/743 1839/1975/743 1840/1976/743\nf 1845/1981/743 1846/1982/743 1839/1975/743\nf 1847/1983/373 1849/1985/373 1848/1984/373\nf 1847/1983/373 1850/1986/373 1849/1985/373\nf 1851/1987/747 1849/1985/747 1850/1986/747\nf 1851/1987/747 1852/1988/747 1849/1985/747\nf 1852/1988/745 1848/1984/745 1849/1985/745\nf 1852/1988/745 1853/1989/745 1848/1984/745\nf 1853/1989/368 1851/1987/368 1854/1990/368\nf 1853/1989/368 1852/1988/368 1851/1987/368\nf 1854/1990/742 1850/1986/742 1847/1983/742\nf 1854/1990/742 1851/1987/742 1850/1986/742\nf 1853/1989/743 1847/1983/743 1848/1984/743\nf 1853/1989/743 1854/1990/743 1847/1983/743\nf 1855/1991/373 1857/1993/373 1856/1992/373\nf 1855/1991/373 1858/1994/373 1857/1993/373\nf 1859/1995/747 1857/1993/747 1858/1994/747\nf 1859/1995/747 1860/1996/747 1857/1993/747\nf 1860/1996/745 1856/1992/745 1857/1993/745\nf 1860/1996/745 1861/1997/745 1856/1992/745\nf 1861/1997/368 1859/1995/368 1862/1998/368\nf 1861/1997/368 1860/1996/368 1859/1995/368\nf 1862/1998/742 1858/1994/742 1855/1991/742\nf 1862/1998/742 1859/1995/742 1858/1994/742\nf 1861/1997/743 1855/1991/743 1856/1992/743\nf 1861/1997/743 1862/1998/743 1855/1991/743\nf 1863/1999/373 1865/2001/373 1864/2000/373\nf 1863/1999/373 1866/2002/373 1865/2001/373\nf 1867/2003/747 1865/2001/747 1866/2002/747\nf 1867/2003/747 1868/2004/747 1865/2001/747\nf 1868/2004/745 1864/2000/745 1865/2001/745\nf 1868/2004/745 1869/2005/745 1864/2000/745\nf 1869/2005/368 1867/2003/368 1870/2006/368\nf 1869/2005/368 1868/2004/368 1867/2003/368\nf 1870/2006/742 1866/2002/742 1863/1999/742\nf 1870/2006/742 1867/2003/742 1866/2002/742\nf 1869/2005/743 1863/1999/743 1864/2000/743\nf 1869/2005/743 1870/2006/743 1863/1999/743\nf 1871/2007/373 1873/2009/373 1872/2008/373\nf 1871/2007/373 1874/2010/373 1873/2009/373\nf 1875/2011/747 1873/2009/747 1874/2010/747\nf 1875/2011/747 1876/2012/747 1873/2009/747\nf 1876/2012/745 1872/2008/745 1873/2009/745\nf 1876/2012/745 1877/2013/745 1872/2008/745\nf 1877/2013/368 1875/2011/368 1878/2014/368\nf 1877/2013/368 1876/2012/368 1875/2011/368\nf 1878/2014/742 1874/2010/742 1871/2007/742\nf 1878/2014/742 1875/2011/742 1874/2010/742\nf 1877/2013/743 1871/2007/743 1872/2008/743\nf 1877/2013/743 1878/2014/743 1871/2007/743\nf 1879/2015/373 1881/2017/373 1880/2016/373\nf 1879/2015/373 1882/2018/373 1881/2017/373\nf 1883/2019/747 1881/2017/747 1882/2018/747\nf 1883/2019/747 1884/2020/747 1881/2017/747\nf 1884/2020/745 1880/2016/745 1881/2017/745\nf 1884/2020/745 1885/2021/745 1880/2016/745\nf 1885/2021/368 1883/2019/368 1886/2022/368\nf 1885/2021/368 1884/2020/368 1883/2019/368\nf 1886/2022/742 1882/2018/742 1879/2015/742\nf 1886/2022/742 1883/2019/742 1882/2018/742\nf 1885/2021/743 1879/2015/743 1880/2016/743\nf 1885/2021/743 1886/2022/743 1879/2015/743\nf 1887/2023/373 1889/2025/373 1888/2024/373\nf 1887/2023/373 1890/2026/373 1889/2025/373\nf 1891/2027/747 1889/2025/747 1890/2026/747\nf 1891/2027/747 1892/2028/747 1889/2025/747\nf 1892/2028/745 1888/2024/745 1889/2025/745\nf 1892/2028/745 1893/2029/745 1888/2024/745\nf 1893/2029/368 1891/2027/368 1894/2030/368\nf 1893/2029/368 1892/2028/368 1891/2027/368\nf 1894/2030/742 1890/2026/742 1887/2023/742\nf 1894/2030/742 1891/2027/742 1890/2026/742\nf 1893/2029/743 1887/2023/743 1888/2024/743\nf 1893/2029/743 1894/2030/743 1887/2023/743\nf 1895/2031/373 1897/2033/373 1896/2032/373\nf 1895/2031/373 1898/2034/373 1897/2033/373\nf 1899/2035/747 1897/2033/747 1898/2034/747\nf 1899/2035/747 1900/2036/747 1897/2033/747\nf 1900/2036/745 1896/2032/745 1897/2033/745\nf 1900/2036/745 1901/2037/745 1896/2032/745\nf 1901/2037/368 1899/2035/368 1902/2038/368\nf 1901/2037/368 1900/2036/368 1899/2035/368\nf 1902/2038/742 1898/2034/742 1895/2031/742\nf 1902/2038/742 1899/2035/742 1898/2034/742\nf 1901/2037/743 1895/2031/743 1896/2032/743\nf 1901/2037/743 1902/2038/743 1895/2031/743\nf 1903/2039/373 1905/2041/373 1904/2040/373\nf 1903/2039/373 1906/2042/373 1905/2041/373\nf 1907/2043/747 1905/2041/747 1906/2042/747\nf 1907/2043/747 1908/2044/747 1905/2041/747\nf 1908/2044/745 1904/2040/745 1905/2041/745\nf 1908/2044/745 1909/2045/745 1904/2040/745\nf 1909/2045/368 1907/2043/368 1910/2046/368\nf 1909/2045/368 1908/2044/368 1907/2043/368\nf 1910/2046/742 1906/2042/742 1903/2039/742\nf 1910/2046/742 1907/2043/742 1906/2042/742\nf 1909/2045/743 1903/2039/743 1904/2040/743\nf 1909/2045/743 1910/2046/743 1903/2039/743\nf 1911/2047/373 1913/2049/373 1912/2048/373\nf 1911/2047/373 1914/2050/373 1913/2049/373\nf 1915/2051/747 1913/2049/747 1914/2050/747\nf 1915/2051/747 1916/2052/747 1913/2049/747\nf 1916/2052/745 1912/2048/745 1913/2049/745\nf 1916/2052/745 1917/2053/745 1912/2048/745\nf 1917/2053/368 1915/2051/368 1918/2054/368\nf 1917/2053/368 1916/2052/368 1915/2051/368\nf 1918/2054/742 1914/2050/742 1911/2047/742\nf 1918/2054/742 1915/2051/742 1914/2050/742\nf 1917/2053/743 1911/2047/743 1912/2048/743\nf 1917/2053/743 1918/2054/743 1911/2047/743\nf 1919/2055/745 1921/2057/745 1920/2056/745\nf 1919/2055/745 1922/2058/745 1921/2057/745\nf 1922/2058/743 1923/2059/743 1921/2057/743\nf 1922/2058/743 1924/2060/743 1923/2059/743\nf 1924/2060/742 1925/2061/742 1923/2059/742\nf 1924/2060/742 1926/2062/742 1925/2061/742\nf 1926/2062/747 1920/2056/747 1925/2061/747\nf 1926/2062/747 1919/2055/747 1920/2056/747\nf 1922/2058/368 1926/2062/368 1924/2060/368\nf 1922/2058/368 1919/2055/368 1926/2062/368\nf 1923/2059/373 1920/2056/373 1921/2057/373\nf 1923/2059/373 1925/2061/373 1920/2056/373\ng cf_Material.001\nusemtl Material.001\nf 1727/1863/743 1728/1864/743 1729/1865/743\nf 1727/1863/743 1729/1865/743 1730/1866/743\nf 1731/1867/742 1732/1868/742 1733/1869/742\nf 1731/1867/742 1733/1869/742 1734/1870/742\nf 1735/1871/373 1736/1872/373 1737/1873/373\nf 1735/1871/373 1737/1873/373 1738/1874/373\nf 1739/1875/745 1740/1876/745 1741/1877/745\nf 1739/1875/745 1741/1877/745 1742/1878/745\nf 1743/1879/747 1744/1880/747 1745/1881/747\nf 1743/1879/747 1745/1881/747 1746/1882/747\nf 1747/1883/753 1730/1866/753 1739/1875/753\nf 1729/1865/754 1737/1873/754 1740/1876/754\nf 1748/1884/755 1742/1878/755 1743/1879/755\nf 1736/1872/756 1744/1880/756 1741/1877/756\nf 1749/1885/757 1734/1870/757 1727/1863/757\nf 1738/1874/758 1728/1864/758 1733/1869/758\nf 1750/1886/759 1746/1882/759 1731/1867/759\nf 1735/1871/760 1732/1868/760 1745/1881/760\nf 1748/1884/761 1747/1883/761 1739/1875/761\nf 1748/1884/761 1739/1875/761 1742/1878/761\nf 1730/1866/762 1729/1865/762 1740/1876/762\nf 1730/1866/762 1740/1876/762 1739/1875/762\nf 1737/1873/763 1736/1872/763 1741/1877/763\nf 1737/1873/763 1741/1877/763 1740/1876/763\nf 1744/1880/764 1743/1879/764 1742/1878/764\nf 1744/1880/764 1742/1878/764 1741/1877/764\nf 1750/1886/765 1748/1884/765 1743/1879/765\nf 1750/1886/765 1743/1879/765 1746/1882/765\nf 1736/1872/766 1735/1871/766 1745/1881/766\nf 1736/1872/766 1745/1881/766 1744/1880/766\nf 1732/1868/767 1731/1867/767 1746/1882/767\nf 1732/1868/767 1746/1882/767 1745/1881/767\nf 1749/1885/768 1750/1886/768 1731/1867/768\nf 1749/1885/768 1731/1867/768 1734/1870/768\nf 1735/1871/769 1738/1874/769 1733/1869/769\nf 1735/1871/769 1733/1869/769 1732/1868/769\nf 1728/1864/770 1727/1863/770 1734/1870/770\nf 1728/1864/770 1734/1870/770 1733/1869/770\nf 1747/1883/771 1749/1885/771 1727/1863/771\nf 1747/1883/771 1727/1863/771 1730/1866/771\nf 1738/1874/772 1737/1873/772 1729/1865/772\nf 1738/1874/772 1729/1865/772 1728/1864/772\nf 1748/1884/368 1750/1886/368 1749/1885/368\nf 1748/1884/368 1749/1885/368 1747/1883/368\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/pdf.py",
    "content": "from __future__ import annotations\n\nimport copy\n\nfrom matplotlib.backends.backend_pdf import PdfPages\nimport matplotlib.pyplot as plt\nimport numpy as np\nfrom rclpy.node import Node\nimport rowan\n\nfrom ..sim_data_types import Action, State\n\n\nclass Visualization:\n    \"\"\"Plots current and desired states into a PDF.\"\"\"\n\n    def __init__(self, node: Node, params: dict, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.ts = []\n        self.all_states = []\n        self.all_states_desired = []\n        self.all_actions = []\n        self.filename = params['output_file']\n\n    def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]):\n        self.ts.append(t)\n        self.all_states.append(copy.deepcopy(states))\n        self.all_states_desired.append(copy.deepcopy(states_desired))\n        self.all_actions.append(copy.deepcopy(actions))\n\n    def shutdown(self):\n        with PdfPages(self.filename) as pdf:\n\n            for k, name in enumerate(self.names):\n\n                cf_states = np.array([s[k]._state for s in self.all_states])\n                cf_states_desired = np.array([s[k]._state for s in self.all_states_desired])\n                cf_actions = np.array([s[k]._action for s in self.all_actions])\n\n                # position\n                fig, axs = plt.subplots(3, 1, sharex=True)\n                fig.suptitle(name + ' position')\n                axs[0].set_ylabel('px [m]')\n                axs[1].set_ylabel('py [m]')\n                axs[2].set_ylabel('pz [m]')\n                axs[-1].set_xlabel('Time [s]')\n\n                for d in range(3):\n                    axs[d].plot(self.ts, cf_states[:, d], label='state')\n                    axs[d].plot(self.ts, cf_states_desired[:, d], label='desired')\n                axs[0].legend()\n                pdf.savefig(fig)\n                plt.close()\n\n                # velocity\n                fig, axs = plt.subplots(3, 1, sharex=True)\n                fig.suptitle(name + ' velocity')\n                axs[0].set_ylabel('vx [m/s]')\n                axs[1].set_ylabel('vy [m/s]')\n                axs[2].set_ylabel('vz [m/s]')\n                axs[-1].set_xlabel('Time [s]')\n\n                for d in range(3):\n                    axs[d].plot(self.ts, cf_states[:, 3+d], label='state')\n                    axs[d].plot(self.ts, cf_states_desired[:, 3+d], label='desired')\n                axs[0].legend()\n                pdf.savefig(fig)\n                plt.close()\n\n                # orientation\n                fig, axs = plt.subplots(3, 1, sharex=True)\n                fig.suptitle(name + ' orientation')\n                axs[0].set_ylabel('roll [deg]')\n                axs[1].set_ylabel('pitch [deg]')\n                axs[2].set_ylabel('yaw [deg]')\n                axs[-1].set_xlabel('Time [s]')\n\n                rpy = np.degrees(rowan.to_euler(cf_states[:, 6:10], convention='xyz'))\n                rpy_desired = np.degrees(\n                    rowan.to_euler(cf_states_desired[:, 6:10], convention='xyz'))\n\n                for d in range(3):\n                    axs[d].plot(self.ts, rpy[:, d], label='state')\n                    axs[d].plot(self.ts, rpy_desired[:, d], label='desired')\n                axs[0].legend()\n                pdf.savefig(fig)\n                plt.close()\n\n                # omega\n                fig, axs = plt.subplots(3, 1, sharex=True)\n                fig.suptitle(name + ' angular velocity')\n                axs[0].set_ylabel('wx [deg/s]')\n                axs[1].set_ylabel('wy [deg/s]')\n                axs[2].set_ylabel('wz [deg/s]')\n                axs[-1].set_xlabel('Time [s]')\n\n                for d in range(3):\n                    axs[d].plot(self.ts, np.degrees(cf_states[:, 10+d]), label='state')\n                    axs[d].plot(self.ts, np.degrees(cf_states_desired[:, 10+d]), label='desired')\n                axs[0].legend()\n                pdf.savefig(fig)\n                plt.close()\n\n                # actions\n                fig, axs = plt.subplots(2, 2, sharex=True, sharey=True)\n                fig.suptitle(name + ' motor actions')\n                axs[0, 0].set_ylabel('rpm')\n                axs[1, 0].set_ylabel('rpm')\n                axs[1, 0].set_xlabel('Time [s]')\n                axs[1, 1].set_xlabel('Time [s]')\n\n                axs[0, 0].plot(self.ts, cf_actions[:, 3], label='M4')\n                axs[0, 0].set_title('M4')\n                axs[0, 1].plot(self.ts, cf_actions[:, 0], label='M1')\n                axs[0, 1].set_title('M1')\n                axs[1, 1].plot(self.ts, cf_actions[:, 1], label='M2')\n                axs[1, 1].set_title('M2')\n                axs[1, 0].plot(self.ts, cf_actions[:, 2], label='M3')\n                axs[1, 0].set_title('M3')\n\n                pdf.savefig(fig)\n                plt.close()\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/record_states.py",
    "content": "from __future__ import annotations\n\nimport datetime\nimport os\n\nimport numpy as np\nfrom rclpy.node import Node\n\nfrom ..sim_data_types import Action, State\n\n\nclass Visualization:\n    \"\"\"Records states in given format file.\"\"\"\n\n    def __init__(self, node: Node, params: dict, names: list[str], states: list[State]):\n        self.node = node\n        self.names = names\n        self.outdir = params['output_dir'] if 'output_dir' in params else 'state_info'\n        self.outdir = self.outdir + '/' + datetime.datetime.now().strftime('%Y-%m-%d_%H%M%S')\n        os.makedirs(self.outdir, exist_ok=True)\n        self.names_idx_map = {}\n        # how many seconds to leave between logs\n        self.logging_time = params['logging_time'] if 'logging_time' in params else 0.3\n        # timestamp of last log, initialized to -self.logging_time so log occurs at t=0\n        self.last_log = -self.logging_time\n        self.supported_formats = {\n            'csv': {\n                'log': self.__log_csv\n            },\n            'np': {\n                'log': self.__log_np,\n                'shutdown': self.__shutdown_np\n            }\n        }\n        self.active_formats = params['file_formats']\n        for idx, name in enumerate(names):\n            self.names_idx_map[name] = idx\n        self.n = len(names)\n        if 'csv' in self.active_formats:\n            for idx, name in enumerate(names):\n                os.makedirs(f'{self.outdir}/csv', exist_ok=True)\n                csf = f'{self.outdir}/csv/{name}.csv'\n                # initialize <robot_name>.csv\n                with open(csf, 'w') as file:\n                    file.write('timestamp,x,y,z,qw,qx,qy,qz\\n')\n        self.ts = []  # list of timestamps\n        if 'np' in self.active_formats:\n            os.makedirs(f'{self.outdir}/np', exist_ok=True)\n            self.Ps = []  # list of positions matrices (self.n x 3)\n            self.Qs = []  # list of quaternion matrices (self.n x 4)\n\n    def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]):\n        if t - self.last_log >= self.logging_time:\n            self.last_log = t\n            self.ts.append(t)\n            P = np.zeros((self.n, 3))\n            Q = np.zeros((self.n, 4))\n            for name, state in zip(self.names, states):\n                idx = self.names_idx_map[name]\n                P[idx] = np.array(state.pos)\n                Q[idx] = np.array(state.quat)\n                for fmt in self.active_formats:\n                    self.supported_formats[fmt]['log'](t, idx, P, Q)\n\n    def __log_csv(self, t, idx: int, P: np.ndarray, Q: np.ndarray):\n        \"\"\"Record states in csv file.\"\"\"\n        with open(f'{self.outdir}/csv/{self.names[idx]}.csv', 'a') as file:\n            file.write(f'{t},{P[idx,0]},{P[idx,1]},{P[idx,2]},{Q[idx,0]},{Q[idx,1]},{Q[idx,2]},{Q[idx,3]}\\n')  # noqa E501\n\n    def __log_np(self, t, idx: int, P: np.ndarray, Q: np.ndarray):\n        self.Ps.append(P)\n        self.Qs.append(Q)\n\n    def __shutdown_np(self):\n        P = np.array(self.Ps)\n        Q = np.array(self.Qs)\n        for idx, name in enumerate(self.names):\n            np.savez_compressed(\n                f'{self.outdir}/np/{name}.npz',\n                t=self.ts,\n                pos=P[idx::self.n, idx, :],\n                quat=Q[idx::self.n, idx, :])\n\n    def shutdown(self):\n        for fmt in self.active_formats:\n            if 'shutdown' in self.supported_formats[fmt]:\n                self.supported_formats[fmt]['shutdown']()\n"
  },
  {
    "path": "crazyflie_sim/crazyflie_sim/visualization/rviz.py",
    "content": "from __future__ import annotations\n\nimport math\n\nfrom geometry_msgs.msg import TransformStamped\nfrom rclpy.node import Node\nfrom tf2_ros import TransformBroadcaster\n\nfrom ..sim_data_types import Action, State\n\n\nclass Visualization:\n    \"\"\"Publishes ROS 2 transforms of the states, so that they can be visualized in RVIZ.\"\"\"\n\n    def __init__(\n        self,\n        node: Node,\n        params: dict,\n        names: list[str],\n        states: list[State],\n        reference_frames: list[str],\n    ):\n        self.node = node\n        self.names = names\n        self.reference_frames = reference_frames\n        self.tfbr = TransformBroadcaster(self.node)\n\n    def step(self, t, states: list[State], states_desired: list[State], actions: list[Action]):\n        # publish transformation to visualize in rviz\n        msgs = []\n        for name, state, reference_frame in zip(self.names, states, self.reference_frames):\n            msg = TransformStamped()\n            msg.header.stamp.sec = math.floor(t)\n            msg.header.stamp.nanosec = int((t - msg.header.stamp.sec) * 1e9)\n            msg.header.frame_id = reference_frame\n            msg.child_frame_id = name\n            msg.transform.translation.x = state.pos[0]\n            msg.transform.translation.y = state.pos[1]\n            msg.transform.translation.z = state.pos[2]\n            msg.transform.rotation.x = state.quat[1]\n            msg.transform.rotation.y = state.quat[2]\n            msg.transform.rotation.z = state.quat[3]\n            msg.transform.rotation.w = state.quat[0]\n            msgs.append(msg)\n        self.tfbr.sendTransform(msgs)\n\n    def shutdown(self):\n        pass\n"
  },
  {
    "path": "crazyflie_sim/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<?xml-model href=\"http://download.ros.org/schema/package_format3.xsd\" schematypens=\"http://www.w3.org/2001/XMLSchema\"?>\n<package format=\"3\">\n  <name>crazyflie_sim</name>\n  <version>1.0.3</version>\n  <description>Simulator for the Crazyswarm2 ROS stack</description>\n  <maintainer email=\"hoenig@tu-berlin.de\">Wolfgang Hönig</maintainer>\n  <maintainer email=\"kimberleymcguire@gmail.com\">Kimberly N. McGuire</maintainer>\n  <license>MIT</license>\n\n  <buildtool_depend>ament_cmake</buildtool_depend>\n  <buildtool_depend>ament_cmake_python</buildtool_depend>\n\n  <depend>rclpy</depend>\n  <depend>crazyflie_interfaces</depend>\n\n  <test_depend>ament_copyright</test_depend>\n  <test_depend>ament_flake8</test_depend>\n  <test_depend>ament_pep257</test_depend>\n  <test_depend>python3-pytest</test_depend>\n  <test_depend>ament_cmake_pytest</test_depend>\n\n  <export>\n    <build_type>ament_cmake</build_type>\n  </export>\n</package>\n"
  },
  {
    "path": "crazyflie_sim/resource/crazyflie_sim",
    "content": ""
  },
  {
    "path": "crazyflie_sim/setup.cfg",
    "content": "[options.entry_points]\nconsole_scripts =\n    crazyflie_server = crazyflie_sim.crazyflie_server:main"
  },
  {
    "path": "crazyflie_sim/test/test_flake8.py",
    "content": "# Copyright 2017 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_flake8.main import main_with_errors\nimport pytest\n\n\n@pytest.mark.flake8\n@pytest.mark.linter\ndef test_flake8():\n    rc, errors = main_with_errors(argv=[])\n    assert rc == 0, \\\n        'Found %d code style errors / warnings:\\n' % len(errors) + \\\n        '\\n'.join(errors)\n"
  },
  {
    "path": "crazyflie_sim/test/test_pep257.py",
    "content": "# Copyright 2015 Open Source Robotics Foundation, Inc.\n#\n# Licensed under the Apache License, Version 2.0 (the \"License\");\n# you may not use this file except in compliance with the License.\n# You may obtain a copy of the License at\n#\n#     http://www.apache.org/licenses/LICENSE-2.0\n#\n# Unless required by applicable law or agreed to in writing, software\n# distributed under the License is distributed on an \"AS IS\" BASIS,\n# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n# See the License for the specific language governing permissions and\n# limitations under the License.\n\nfrom ament_pep257.main import main\nimport pytest\n\n\n@pytest.mark.linter\n@pytest.mark.pep257\ndef test_pep257():\n    rc = main(argv=['.', 'test'])\n    assert rc == 0, 'Found code style errors / warnings'\n"
  },
  {
    "path": "docs/.gitignore",
    "content": "_build\nhtml\n"
  },
  {
    "path": "docs/Makefile",
    "content": "# Makefile for Sphinx documentation\n#\n\n# You can set these variables from the command line.\nSPHINXOPTS    = -W\nSPHINXBUILD   = sphinx-build\nPAPER         =\nBUILDDIR      = _build\n\n# Internal variables.\nPAPEROPT_a4     = -D latex_paper_size=a4\nPAPEROPT_letter = -D latex_paper_size=letter\nALLSPHINXOPTS   = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n# the i18n builder cannot share the environment and doctrees with the others\nI18NSPHINXOPTS  = $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n\n.PHONY: help\nhelp:\n\t@echo \"Please use \\`make <target>' where <target> is one of\"\n\t@echo \"  html       to make standalone HTML files\"\n\t@echo \"  dirhtml    to make HTML files named index.html in directories\"\n\t@echo \"  singlehtml to make a single large HTML file\"\n\t@echo \"  pickle     to make pickle files\"\n\t@echo \"  json       to make JSON files\"\n\t@echo \"  htmlhelp   to make HTML files and a HTML help project\"\n\t@echo \"  qthelp     to make HTML files and a qthelp project\"\n\t@echo \"  applehelp  to make an Apple Help Book\"\n\t@echo \"  devhelp    to make HTML files and a Devhelp project\"\n\t@echo \"  epub       to make an epub\"\n\t@echo \"  epub3      to make an epub3\"\n\t@echo \"  latex      to make LaTeX files, you can set PAPER=a4 or PAPER=letter\"\n\t@echo \"  latexpdf   to make LaTeX files and run them through pdflatex\"\n\t@echo \"  latexpdfja to make LaTeX files and run them through platex/dvipdfmx\"\n\t@echo \"  text       to make text files\"\n\t@echo \"  man        to make manual pages\"\n\t@echo \"  texinfo    to make Texinfo files\"\n\t@echo \"  info       to make Texinfo files and run them through makeinfo\"\n\t@echo \"  gettext    to make PO message catalogs\"\n\t@echo \"  changes    to make an overview of all changed/added/deprecated items\"\n\t@echo \"  xml        to make Docutils-native XML files\"\n\t@echo \"  pseudoxml  to make pseudoxml-XML files for display purposes\"\n\t@echo \"  linkcheck  to check all external links for integrity\"\n\t@echo \"  doctest    to run all doctests embedded in the documentation (if enabled)\"\n\t@echo \"  coverage   to run coverage check of the documentation (if enabled)\"\n\t@echo \"  dummy      to check syntax errors of document sources\"\n\n.PHONY: clean\nclean:\n\trm -rf $(BUILDDIR)/*\n\n.PHONY: html\nhtml:\n\t$(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/html.\"\n\n.PHONY: dirhtml\ndirhtml:\n\t$(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/dirhtml.\"\n\n.PHONY: singlehtml\nsinglehtml:\n\t$(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml\n\t@echo\n\t@echo \"Build finished. The HTML page is in $(BUILDDIR)/singlehtml.\"\n\n.PHONY: pickle\npickle:\n\t$(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle\n\t@echo\n\t@echo \"Build finished; now you can process the pickle files.\"\n\n.PHONY: json\njson:\n\t$(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json\n\t@echo\n\t@echo \"Build finished; now you can process the JSON files.\"\n\n.PHONY: htmlhelp\nhtmlhelp:\n\t$(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp\n\t@echo\n\t@echo \"Build finished; now you can run HTML Help Workshop with the\" \\\n\t      \".hhp project file in $(BUILDDIR)/htmlhelp.\"\n\n.PHONY: qthelp\nqthelp:\n\t$(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp\n\t@echo\n\t@echo \"Build finished; now you can run \"qcollectiongenerator\" with the\" \\\n\t      \".qhcp project file in $(BUILDDIR)/qthelp, like this:\"\n\t@echo \"# qcollectiongenerator $(BUILDDIR)/qthelp/Crazyswarm.qhcp\"\n\t@echo \"To view the help file:\"\n\t@echo \"# assistant -collectionFile $(BUILDDIR)/qthelp/Crazyswarm.qhc\"\n\n.PHONY: applehelp\napplehelp:\n\t$(SPHINXBUILD) -b applehelp $(ALLSPHINXOPTS) $(BUILDDIR)/applehelp\n\t@echo\n\t@echo \"Build finished. The help book is in $(BUILDDIR)/applehelp.\"\n\t@echo \"N.B. You won't be able to view it unless you put it in\" \\\n\t      \"~/Library/Documentation/Help or install it in your application\" \\\n\t      \"bundle.\"\n\n.PHONY: devhelp\ndevhelp:\n\t$(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp\n\t@echo\n\t@echo \"Build finished.\"\n\t@echo \"To view the help file:\"\n\t@echo \"# mkdir -p $$HOME/.local/share/devhelp/Crazyswarm\"\n\t@echo \"# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/Crazyswarm\"\n\t@echo \"# devhelp\"\n\n.PHONY: epub\nepub:\n\t$(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub\n\t@echo\n\t@echo \"Build finished. The epub file is in $(BUILDDIR)/epub.\"\n\n.PHONY: epub3\nepub3:\n\t$(SPHINXBUILD) -b epub3 $(ALLSPHINXOPTS) $(BUILDDIR)/epub3\n\t@echo\n\t@echo \"Build finished. The epub3 file is in $(BUILDDIR)/epub3.\"\n\n.PHONY: latex\nlatex:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo\n\t@echo \"Build finished; the LaTeX files are in $(BUILDDIR)/latex.\"\n\t@echo \"Run \\`make' in that directory to run these through (pdf)latex\" \\\n\t      \"(use \\`make latexpdf' here to do that automatically).\"\n\n.PHONY: latexpdf\nlatexpdf:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through pdflatex...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: latexpdfja\nlatexpdfja:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through platex and dvipdfmx...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf-ja\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: text\ntext:\n\t$(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text\n\t@echo\n\t@echo \"Build finished. The text files are in $(BUILDDIR)/text.\"\n\n.PHONY: man\nman:\n\t$(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man\n\t@echo\n\t@echo \"Build finished. The manual pages are in $(BUILDDIR)/man.\"\n\n.PHONY: texinfo\ntexinfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo\n\t@echo \"Build finished. The Texinfo files are in $(BUILDDIR)/texinfo.\"\n\t@echo \"Run \\`make' in that directory to run these through makeinfo\" \\\n\t      \"(use \\`make info' here to do that automatically).\"\n\n.PHONY: info\ninfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo \"Running Texinfo files through makeinfo...\"\n\tmake -C $(BUILDDIR)/texinfo info\n\t@echo \"makeinfo finished; the Info files are in $(BUILDDIR)/texinfo.\"\n\n.PHONY: gettext\ngettext:\n\t$(SPHINXBUILD) -b gettext $(I18NSPHINXOPTS) $(BUILDDIR)/locale\n\t@echo\n\t@echo \"Build finished. The message catalogs are in $(BUILDDIR)/locale.\"\n\n.PHONY: changes\nchanges:\n\t$(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes\n\t@echo\n\t@echo \"The overview file is in $(BUILDDIR)/changes.\"\n\n.PHONY: linkcheck\nlinkcheck:\n\t$(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck\n\t@echo\n\t@echo \"Link check complete; look for any errors in the above output \" \\\n\t      \"or in $(BUILDDIR)/linkcheck/output.txt.\"\n\n.PHONY: doctest\ndoctest:\n\t$(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest\n\t@echo \"Testing of doctests in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/doctest/output.txt.\"\n\n.PHONY: coverage\ncoverage:\n\t$(SPHINXBUILD) -b coverage $(ALLSPHINXOPTS) $(BUILDDIR)/coverage\n\t@echo \"Testing of coverage in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/coverage/python.txt.\"\n\n.PHONY: xml\nxml:\n\t$(SPHINXBUILD) -b xml $(ALLSPHINXOPTS) $(BUILDDIR)/xml\n\t@echo\n\t@echo \"Build finished. The XML files are in $(BUILDDIR)/xml.\"\n\n.PHONY: pseudoxml\npseudoxml:\n\t$(SPHINXBUILD) -b pseudoxml $(ALLSPHINXOPTS) $(BUILDDIR)/pseudoxml\n\t@echo\n\t@echo \"Build finished. The pseudo-XML files are in $(BUILDDIR)/pseudoxml.\"\n\n.PHONY: dummy\ndummy:\n\t$(SPHINXBUILD) -b dummy $(ALLSPHINXOPTS) $(BUILDDIR)/dummy\n\t@echo\n\t@echo \"Build finished. Dummy builder generates no files.\"\n"
  },
  {
    "path": "docs/api.rst",
    "content": ".. _api:\n\nPython API Reference\n====================\n\nThe module ``pycrazyswarm``, contained in ``/ros_ws/src/crazyswarm/scripts``,\nis the main high-level interface to the Crazyswarm platform.\n\nThe goal of the Crazyswarm project is to reach a state where many diverse\nmulti-quadrotor research projects can be implemented without going any \"deeper\"\nthan writing a ``pycrazyswarm`` script and modifying configuration files.\nNew projects should try this approach first. If it becomes necessary to\nmodify Crazyswarm or its submodules, we encourage users to contribute those\nchanges back via Github pull request.\n\nAll classes in ``pycrazyswarm.crazyflie`` are mirrored by an identically named\nclass in ``pycrazyswarm.crazyflieSim``. The ``Sim`` version allows testing\n``pycrazyswarm`` scripts in simulation with a 3D visualization before running\nanything on real hardware. Since the APIs are identical, the documentation\nonly refers to the non-``Sim`` versions.\n\n\n``Crazyflie`` class\n-------------------\n.. autoclass:: pycrazyswarm.crazyflie.Crazyflie\n   :members:\n\n``CrazyflieServer`` class\n-------------------------\n.. autoclass:: pycrazyswarm.crazyflie.CrazyflieServer\n   :members:\n\n``TimeHelper`` class\n--------------------\n.. autoclass:: pycrazyswarm.crazyflie.TimeHelper\n   :members:\n\n\nSwitching between simulation and real hardware\n----------------------------------------------\nCorrect ``pycrazyswarm`` scripts should be able to run in both simulation\nand on real hardware without modification. Enable simulation and control the\nsimulation parameters with the command-line flags listed below.\n\n.. argparse::\n   :module: pycrazyswarm.crazyswarm_py\n   :func: build_argparser\n   :prog: python2 <my_crazyswarm_script.py>\n\nNote: rendering video output with the ``--video`` option requires an\ninstallation of `ffmpeg <https://ffmpeg.org>`_ with the ``libx264`` encoder.\nThis is provided in the Anaconda environment, but must be installed manually\notherwise.\n"
  },
  {
    "path": "docs/changelog.rst",
    "content": "Changelog\n=========\n\nOctober 4th, 2019\n-----------------\n\n1. We switched to the official firmware. Our own EKF is not used anymore, instead we contributed a full pose update in the official EKF.\n\n  a. We now support single-marker tracking, where only the position and not the pose is tracked by an external system. Attitude is estimated on-board.\n  b. The EKF is pre-tuned to work with motion capture systems and the Mellinger controller.\n\n2. There can be now more than 255 parameters in the firmware. Parameters can be specified by Crazyflie (and not only per type as before). Parameters can be updated using broadcasts mid-flight (e.g., to switch the controller mid-flight).\n\n3. We now have full support for OptiTrack, including for using Motive 2.x. Both object tracking by Motive and custom object tracking are supported.\n\nApril 22nd, 2018\n----------------\n\n1. More features have been merged into the official firmware. The high-level execution (takeoff, landing, trajectory execution) is now part of the official firmware. Custom firmware changes still include:\n\n  a. Kalman filter that support full-pose update\n  b. Improved handling after crashes (particularly important for big quads)\n  c. Custom LED-ring effect\n\n2. The Crazyswarm now uses the latest official crazyflie_ros instead of its own fork. Crazyswarm specific code (e.g, crazyswarm_server) has been moved into ``ros_ws/src/crazyswarm/src``.\n\n3. Getting the code into the official code base unfortunately required some API changes:\n\n  a. Support for ellipsoids has been removed. If you need that feature please let us know via github issues.\n  b. Support for canned trajectories has been removed.\n  c. The new API allows to upload multiple trajectories and does not have a piece number limit (instead, it is limited by total memory size of all trajectories only).\n  d. ``Hover`` has been renamed to ``GoTo``\n\nMarch 2nd, 2018\n---------------\n\n#. Support for heterogeneous swarms, i.e., bigger quadrotors can be used with the CF as control board and the bigQuad deck. Types can be specified in ``ros_ws/src/crazyswarm/launch/crazyflieTypes.yaml``. The list of all CFs has now a type field in ``ros_ws/src/crazyswarm/launch/allCrazyflies.yaml`` (previously ``all49.yaml``). Each type can have its own marker configuration.\n\n#. Firmware now re-based from the latest official firmware. Some parts are already in the official firmware (e.g., controller). The firmware now supports the use of our Kalman filter (KalmanUSC) or the official Kalman filter, although both have different feature sets. The prebuilt firmware uses our Kalman filter and comes with bigQuad-deck support enabled, i.e., it can be used for both standard Crazyflies and custom ones.\n\n#. Removed support for avoid-target mode\n"
  },
  {
    "path": "docs/conf.py",
    "content": "#!/usr/bin/env python3\n# -*- coding: utf-8 -*-\n#\n# Crazyswarm documentation build configuration file, created by\n# sphinx-quickstart on Tue Apr 18 20:00:33 2017.\n#\n# This file is execfile()d with the current directory set to its\n# containing dir.\n#\n# Note that not all possible configuration values are present in this\n# autogenerated file.\n#\n# All configuration values have a default; values that are commented out\n# serve to show the default.\n\n# If extensions (or modules to document with autodoc) are in another directory,\n# add these directories to sys.path here. If the directory is relative to the\n# documentation root, use os.path.abspath to make it absolute, like shown here.\n#\nimport os\nimport sys\nsys.path.insert(0, os.path.abspath('..'))\nsys.path.insert(0, os.path.abspath('../ros_ws/src/crazyswarm/scripts'))\n\nimport sphinx_rtd_theme\n\n# -- General configuration ------------------------------------------------\n\n# If your documentation needs a minimal Sphinx version, state it here.\n#\nneeds_sphinx = '1.4'\n\n# Add any Sphinx extension module names here, as strings. They can be\n# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom\n# ones.\nextensions = [\n    'sphinx.ext.autodoc',\n    'sphinx.ext.imgmath',\n    'sphinx.ext.mathjax',\n    'sphinx.ext.napoleon',\n    'sphinxarg.ext',\n    'sphinx_tabs.tabs',\n    'sphinxcontrib.programoutput',\n]\n\n# Add any paths that contain templates here, relative to this directory.\ntemplates_path = ['_templates']\n\n# The suffix(es) of source filenames.\n# You can specify multiple suffix as a list of string:\n#\n# source_suffix = ['.rst', '.md']\nsource_suffix = '.rst'\n\n# The encoding of source files.\n#\n# source_encoding = 'utf-8-sig'\n\n# The master toctree document.\nmaster_doc = 'index'\n\n# General information about the project.\nproject = 'Crazyswarm'\ncopyright = '2018-2021, Wolfgang Hoenig, James A. Preiss, and contributors.'\nauthor = 'Wolfgang Hoenig, James A. Preiss'\n\n# The version info for the project you're documenting, acts as replacement for\n# |version| and |release|, also used in various other places throughout the\n# built documents.\n#\n# The short X.Y version.\nversion = '0.3'\n# The full version, including alpha/beta/rc tags.\nrelease = '0.3'\n\n# The language for content autogenerated by Sphinx. Refer to documentation\n# for a list of supported languages.\n#\n# This is also used if you do content translation via gettext catalogs.\n# Usually you set \"language\" from the command line for these cases.\nlanguage = None\n\n# There are two options for replacing |today|: either, you set today to some\n# non-false value, then it is used:\n#\n# today = ''\n#\n# Else, today_fmt is used as the format for a strftime call.\n#\n# today_fmt = '%B %d, %Y'\n\n# List of patterns, relative to source directory, that match files and\n# directories to ignore when looking for source files.\n# This patterns also effect to html_static_path and html_extra_path\nexclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']\n\n# The reST default role (used for this markup: `text`) to use for all\n# documents.\n#\n# default_role = None\n\n# If true, '()' will be appended to :func: etc. cross-reference text.\n#\n# add_function_parentheses = True\n\n# If true, the current module name will be prepended to all description\n# unit titles (such as .. function::).\n#\n# add_module_names = True\n\n# If true, sectionauthor and moduleauthor directives will be shown in the\n# output. They are ignored by default.\n#\n# show_authors = False\n\n# The name of the Pygments (syntax highlighting) style to use.\npygments_style = 'sphinx'\n\n# A list of ignored prefixes for module index sorting.\n# modindex_common_prefix = []\n\n# If true, keep warnings as \"system message\" paragraphs in the built documents.\n# keep_warnings = False\n\n# If true, `todo` and `todoList` produce output, else they produce nothing.\ntodo_include_todos = False\n\n\n# -- Options for HTML output ----------------------------------------------\n\n# The theme to use for HTML and HTML Help pages.  See the documentation for\n# a list of builtin themes.\n#\nhtml_theme = 'sphinx_rtd_theme'\n\n# Theme options are theme-specific and customize the look and feel of a theme\n# further.  For a list of options available for each theme, see the\n# documentation.\n#\n# html_theme_options = {}\n\n# Add any paths that contain custom themes here, relative to this directory.\n# html_theme_path = []\n\n# The name for this set of Sphinx documents.\n# \"<project> v<release> documentation\" by default.\n#\n# html_title = 'Crazyswarm v0.1'\n\n# A shorter title for the navigation bar.  Default is the same as html_title.\n#\n# html_short_title = None\n\n# The name of an image file (relative to this directory) to place at the top\n# of the sidebar.\n#\n# html_logo = None\n\n# The name of an image file (relative to this directory) to use as a favicon of\n# the docs.  This file should be a Windows icon file (.ico) being 16x16 or 32x32\n# pixels large.\n#\n# html_favicon = None\n\n# Add any paths that contain custom static files (such as style sheets) here,\n# relative to this directory. They are copied after the builtin static files,\n# so a file named \"default.css\" will overwrite the builtin \"default.css\".\n# html_static_path = ['_static']\n\n# Add any extra paths that contain custom files (such as robots.txt or\n# .htaccess) here, relative to this directory. These files are copied\n# directly to the root of the documentation.\n#\n# html_extra_path = []\n\n# If not None, a 'Last updated on:' timestamp is inserted at every page\n# bottom, using the given strftime format.\n# The empty string is equivalent to '%b %d, %Y'.\n#\n# html_last_updated_fmt = None\n\n# If true, SmartyPants will be used to convert quotes and dashes to\n# typographically correct entities.\n#\n# html_use_smartypants = True\n\n# Custom sidebar templates, maps document names to template names.\n#\n# html_sidebars = {}\n\n# Additional templates that should be rendered to pages, maps page names to\n# template names.\n#\n# html_additional_pages = {}\n\n# If false, no module index is generated.\n#\n# html_domain_indices = True\n\n# If false, no index is generated.\n#\n# html_use_index = True\n\n# If true, the index is split into individual pages for each letter.\n#\n# html_split_index = False\n\n# If true, links to the reST sources are added to the pages.\n#\n# html_show_sourcelink = True\n\n# If true, \"Created using Sphinx\" is shown in the HTML footer. Default is True.\n#\n# html_show_sphinx = True\n\n# If true, \"(C) Copyright ...\" is shown in the HTML footer. Default is True.\n#\n# html_show_copyright = True\n\n# If true, an OpenSearch description file will be output, and all pages will\n# contain a <link> tag referring to it.  The value of this option must be the\n# base URL from which the finished HTML is served.\n#\n# html_use_opensearch = ''\n\n# This is the file name suffix for HTML files (e.g. \".xhtml\").\n# html_file_suffix = None\n\n# Language to be used for generating the HTML full-text search index.\n# Sphinx supports the following languages:\n#   'da', 'de', 'en', 'es', 'fi', 'fr', 'h', 'it', 'ja'\n#   'nl', 'no', 'pt', 'ro', 'r', 'sv', 'tr', 'zh'\n#\n# html_search_language = 'en'\n\n# A dictionary with options for the search language support, empty by default.\n# 'ja' uses this config value.\n# 'zh' user can custom change `jieba` dictionary path.\n#\n# html_search_options = {'type': 'default'}\n\n# The name of a javascript file (relative to the configuration directory) that\n# implements a search results scorer. If empty, the default will be used.\n#\n# html_search_scorer = 'scorer.js'\n\n# Output file base name for HTML help builder.\nhtmlhelp_basename = 'Crazyswarmdoc'\n\n# -- Options for LaTeX output ---------------------------------------------\n\nlatex_elements = {\n     # The paper size ('letterpaper' or 'a4paper').\n     #\n     # 'papersize': 'letterpaper',\n\n     # The font size ('10pt', '11pt' or '12pt').\n     #\n     # 'pointsize': '10pt',\n\n     # Additional stuff for the LaTeX preamble.\n     #\n     # 'preamble': '',\n\n     # Latex figure (float) alignment\n     #\n     # 'figure_align': 'htbp',\n}\n\n# Grouping the document tree into LaTeX files. List of tuples\n# (source start file, target name, title,\n#  author, documentclass [howto, manual, or own class]).\nlatex_documents = [\n    (master_doc, 'Crazyswarm.tex', 'Crazyswarm Documentation',\n     'Wolfgang Hoenig, James A. Preiss', 'manual'),\n]\n\n# The name of an image file (relative to this directory) to place at the top of\n# the title page.\n#\n# latex_logo = None\n\n# For \"manual\" documents, if this is true, then toplevel headings are parts,\n# not chapters.\n#\n# latex_use_parts = False\n\n# If true, show page references after internal links.\n#\n# latex_show_pagerefs = False\n\n# If true, show URL addresses after external links.\n#\n# latex_show_urls = False\n\n# Documents to append as an appendix to all manuals.\n#\n# latex_appendices = []\n\n# It false, will not define \\strong, \\code, \titleref, \\crossref ... but only\n# \\sphinxstrong, ..., \\sphinxtitleref, ... To help avoid clash with user added\n# packages.\n#\n# latex_keep_old_macro_names = True\n\n# If false, no module index is generated.\n#\n# latex_domain_indices = True\n\n\n# -- Options for manual page output ---------------------------------------\n\n# One entry per manual page. List of tuples\n# (source start file, name, description, authors, manual section).\nman_pages = [\n    (master_doc, 'crazyswarm', 'Crazyswarm Documentation',\n     [author], 1)\n]\n\n# If true, show URL addresses after external links.\n#\n# man_show_urls = False\n\n\n# -- Options for Texinfo output -------------------------------------------\n\n# Grouping the document tree into Texinfo files. List of tuples\n# (source start file, target name, title, author,\n#  dir menu entry, description, category)\ntexinfo_documents = [\n    (master_doc, 'Crazyswarm', 'Crazyswarm Documentation',\n     author, 'Crazyswarm', 'One line description of project.',\n     'Miscellaneous'),\n]\n\n# Documents to append as an appendix to all manuals.\n#\n# texinfo_appendices = []\n\n# If false, no module index is generated.\n#\n# texinfo_domain_indices = True\n\n# How to display URL addresses: 'footnote', 'no', or 'inline'.\n#\n# texinfo_show_urls = 'footnote'\n\n# If true, do not generate a @detailmenu in the \"Top\" node's menu.\n#\n# texinfo_no_detailmenu = False\n\n# -- Options for Autodoc -------------------------------------------------\n\n# List class members in the order they appear in the file,\n# instead of alphabetically.\nautodoc_member_order = 'bysource'\n\n# Do not try to import ROS modules so we can build on more machines easily.\nautodoc_mock_imports = [\n    'crazyswarm',\n    'numpy',\n    'rospy',\n    'std_msgs',\n    'std_srvs',\n    'tf',\n    'tf_conversions',\n]\n"
  },
  {
    "path": "docs/configuration.rst",
    "content": ".. _configuration:\n\nConfiguration\n=============\n\nAfter completing :ref:`installation`,\na significant amount of configuration is needed before the Crazyswarm is ready to fly.\nFollow the steps below.\n\nSet up radio communication\n--------------------------\nSince the Crazyflies share radios and communication channels, they need to have a unique identifier/address.\nThe convention in the Crazyswarm is to use the following address::\n\n    0xE7E7E7E7<X>\n\nwhere ``<X>`` is the number of the Crazyflie in the hexadecimal system. For example cf1 will use address ``0xE7E7E7E701`` and cf10 uses address ``0xE7E7E7E70A``.\nThe easiest way to assign addresses is to use the official Crazyflie Python Client.\n\n1. Physically label your Crazyflies with numbers.\n2. Assign addresses using the Crazyflie Python Client (use a USB cable for easiest handling).\n3. Each radio can control about 15 Crazyflies. If you have more than 15 CFs you will need to assign different channels to the Crazyflies. For example, if you have 49 Crazyflies you'll need three unique channels. It is up to you which channels you assign to which CF, but a good way is to use the Crazyflie number modulo the number of channels. For example, cf1 is assigned to channel 80, cf2 is assigned to channel 90, cf3 is assigned to channel 100, cf4 is assigned to channel 80 and so on.\n\nNote: Crazyflies must be rebooted after any change of the channel/address for the changes to take effect.\n\nFinally, add the user permissions to use the USB Radio without being root.\n\n  - Option 1: follow the `official instructions <https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/installation/usb_permissions>`_.\n  - Option 2: Use the script: ``./pc_permissions.sh``\n\n\nUpdate firmware\n---------------\nCrazyswarm is tested with the official Bitcraze firmwares for the Crazyflie and Crazyradio.\nWe supply the binary image of the Crazyradio firmware in the ``/prebuilt`` directory.\n\n1. Upgrade the firmwares of your Crazyflies with the latest official release using `cfclient`. This will update STM32, NRF51, and attached decks (e.g., LightHouse deck). We tested version 2021.6.\n\n   .. note::\n      If you use a custom-built firmware, you can also use `chooser.py`, see below.\n      To flash on the command line, check out the official Bitcraze documentation: `STM32 <https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/building-and-flashing/build/>`_, `NRF51 <https://github.com/bitcraze/crazyflie2-nrf-firmware/blob/master/docs/build/build.md>`_.\n\n2. Upgrade the firmware of your Crazyradios with the latest `official firmware <https://github.com/bitcraze/crazyradio-firmware>`_. Note that this is even required for newly bought Crazyradios.\n\n    #. ``python crazyradio-firmware/usbtools/launchBootloader.py``\n    #. ``sudo python crazyradio-firmware/usbtools/nrfbootload.py flash prebuilt/cradio.bin``\n    #. Now unplug and re-plug the radio. You can check the version using ``rosrun crazyflie_tools scan -v``, which should report ``Found Crazyradio with version 99.55``.\n\n\n\nAdjust configuration files\n--------------------------\n\nSeveral configuration files may require editing. You can edit those files in place, or follow :ref:`tutorial_git_integration` if you want to use your custom package.\n\nConfigure external tracking system\n~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~\nThe first configuration file is the ROS launch file, ``ros_ws/src/crazyswarm/launch/hover_swarm.launch``.\nIt contains settings on which external tracking system to use, among others.\n\nSelect hardware make\n^^^^^^^^^^^^^^^^^^^^\n\nFirst, select your tracking system in the appropriate tab below.\n\n.. tabs::\n\n   .. tab:: Vicon\n\n      Vicon is fully supported and tested with Tracker 3.4.\n      Set the host name of the Vicon machine:\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          motion_capture_type: \"vicon\"\n          motion_capture_host_name: \"viconPC\" # hostname or IP address\n\n      If using ``libobjecttracker`` as ``object_tracking_type`` disable all objects.\n\n   .. tab:: OptiTrack\n\n      OptiTrack is fully supported and tested with Motive 2.3 and Motive 3.0.\n      Select the host name of the Optitrack machine:\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          motion_capture_type: \"optitrack\"\n          motion_capture_host_name: \"optitrackPC\" # hostname or IP address\n\n      Use the following settings for correct operation:\n\n        * Data Streaming Pane: ``Up axis: Z``\n\n      If using ``libobjecttracker`` as ``object_tracking_type`` disable all assets and make sure that labeled or unlabeled markers are being streamed.\n\n   .. tab:: Qualisys\n\n      Qualisys has been tested to work with QTM 2.16 both for rigid body and point cloud. It is expected to work with any later version of QTM.\n      Set the host name and port of the Qualisys machine:\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          motion_capture_type: \"qualisys\"\n          motion_capture_host_name: \"qualisysPC\" # hostname or IP address\n\n      If using ``motionCapture`` as ``object_tracking_type`` make sure to check the checkbox ``Calculate 6DOF`` in QTM ``Project options/Processing/Real time actions``.\n\n      If using ``libobjecttracker`` as ``object_tracking_type`` and you have setup 6DOF tracking for your Crazyflies in QTM, make sure to disable the ``Calculate 6DOF`` checkbox.\n\n\n   .. tab:: LPS/LightHouse/FlowDeck\n\n      The usage of a motion capture system can be disabled by selecting ``none``.\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          motion_capture_type: \"none\"\n\n      This is useful for on-board solutions such as the Ultra-Wideband localization system (UWB), LightHouse, or dead-reckoning using the flow-deck.\n\n      In this case, you can visualize the state estimate in rviz if the following settings are enabled.\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          enable_logging: True\n          enable_logging_pose: True\n\n      (This only works for debugging when connected to a few drones.)\n\nSelect object tracking mode (motion capture only)\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nThe most significant configuration choice is whether or not to use *unique arrangements*\nof motion capture markers for each Crazyflie in your fleet.\nSelect one of the tabs below for a description of each choice.\nLater steps in the documentation will change depending on your selection.\n\n.. tabs::\n\n   .. group-tab:: Unique Marker Arrangements\n\n      With a unique marker arrangement for each Crazyflie, you rely on the motion capture vendor to differentiate between objects.\n      This is generally preferred.\n      However, if you have lots of Crazyflies, it can be hard to design enough unique configurations -- there are not many places to put a marker on the Crazyflie.\n\n      If your arrangements are too similar, motion capture software may not fail gracefully.\n      For example, it may rapidly switch back and forth between recognizing two different objects at a single physical location.\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          object_tracking_type: \"motionCapture\"\n\n   .. group-tab:: Duplicated Marker Arrangements\n\n      If more than one Crazyflie has the same marker arrangement, standard motion capture software will refuse to track them.\n      Instead, Crazyswarm can use the raw point cloud from the motion capture system and track the CFs frame-by-frame.\n      Here we use Iterative Closest Point (ICP) to greedily match the known marker arrangements to the pointcloud. \n      There are two main consequences of this option:\n\n      - The initial positions of the Crazyflies must be known, to establish a mapping between radio IDs and physical locations.\n      - The tracking is done frame-by-frame, so if markers are occluded for a significant amount of time,\n        the algorithm may not be able to re-establish the ID-location mapping once they are visible again.\n\n      You can use more than one marker arrangement in this mode.\n      For example, you might have several standard Crazyflies with arrangement 1,\n      and several larger quadcopters with arrangement 2.\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          object_tracking_type: \"libobjecttracker\"\n\n      .. warning::\n         When using ``libobjecttracker`` it is important to disable tracking of Crazyflies in your motion capture system's control software.\n         Some motion capture systems remove markers from the point cloud when they are matched to an object.\n         Since ``libobjecttracker`` operates on the raw point cloud, it will not be able to track any Crazyflies that have already been \"taken\" by the motion capture system.\n\n   .. group-tab:: Single Marker\n\n      A special case of duplicated marker arrangements is the case where we only use a single marker per robot.\n      As before, the Crazyswarm will use the raw point cloud from the motion capture system and track the CFs frame-by-frame.\n      In this mode, we use optimal task assignment at every frame, which makes this mode more robust to motion capture outliers compared to the duplicate marker arrangements.\n      The main disadvantage is that the yaw angle cannot be observed without moving in the xy-plane.\n      Nevertheless, it is possible to hover for 30 seconds in place for a Crazyflie 2.1, without causing flight instabilities.\n      The stable hover time for Crazyflie 2.0 is shorter (about 15s), due to the noisier IMU.\n\n      Currently, it is not possible to mix duplicate marker arrangements and single marker tracking.\n\n      .. code-block:: yaml\n\n          # ros_ws/src/crazyswarm/launch/hover_swarm.launch\n          object_tracking_type: \"libobjecttracker\"\n\n      .. warning::\n         When using ``libobjecttracker`` it is important to disable tracking of Crazyflies in your motion capture system's control software.\n         Some motion capture systems remove markers from the point cloud when they are matched to an object.\n         Since ``libobjecttracker`` operates on the raw point cloud, it will not be able to track any Crazyflies that have already been \"taken\" by the motion capture system.\n\n\n.. _config_crazyflies_yaml:\n\nEnumerate Crazyflies\n~~~~~~~~~~~~~~~~~~~~\nSecond we have ``crazyflies.yaml``, a file that lists all active Crazyflies.\nThe Crazyswarm server reads this configuration file at startup.\nIf it cannot communicate with all the Crazyflies defined in ``crazyflies.yaml``, it will halt and report an error.\n\n.. code-block:: yaml\n\n    # ros_ws/src/crazyswarm/launch/crazyflies.yaml\n    crazyflies:\n      - id: 1\n        channel: 100\n        initialPosition: [1.5, 1.5, 0.0]\n        type: default\n      - id: 2\n        channel: 110\n        initialPosition: [1.5, 1.0, 0.0]\n        type: medium\n\nThe file assumes that the address of each CF is set as discussed earlier.\nThe channel can be freely configured.\nThe ``initialPosition`` field is required for the simulation and for some motion capture configurations, see below.\n\n.. tabs::\n\n   .. group-tab:: Unique Marker Arrangements\n\n      If you use unique marker arrangements, the ``initialPosition`` field of the ``crazyflies.yaml`` entries will be ignored,\n      but it should still be set because the parser will expect it.\n\n   .. group-tab:: Duplicated Marker Arrangements\n\n      If you use duplicated marker arrangements, ``initialPosition`` must be correct.\n      Positions are specified in meters, in the coordinate system of your motion capture device.\n      It is not required that the CFs start exactly at those positions -- a few centimeters variation is fine.\n\n   .. group-tab:: Single Marker\n\n      If you use single markers, ``initialPosition`` can be a rough estimate.\n      Positions are specified in meters, in the coordinate system of your motion capture device.\n\nIt is often useful to select a subset of all available Crazyflies.\nThe graphical \"Chooser\" and the additional configuration file ``allCrazyflies.yaml`` help make this easy.\nSee :ref:`config_chooser` for details.\n\n\n.. _config_types:\n\n\nDefine Crazyflie types\n~~~~~~~~~~~~~~~~~~~~~~\n\nThe third configuration file ``crazyflieTypes.yaml`` defines the possible *types*.\nEach type specifies the physical attributes of the quadrotor.\nThe ``type`` field in the ``crazyflies.yaml`` entries must refer to a type listed in this file.\n\n.. note::\n\n   Many users will not need to modify this file.\n\n.. code-block:: yaml\n\n    # ros_ws/src/crazyswarm/launch/crazyflieTypes.yaml\n    crazyflieTypes:\n      default:\n        bigQuad: False\n        batteryVoltageWarning: 3.8  # V\n        batteryVoltateCritical: 3.7 # V\n        markerConfiguration: 0\n        dynamicsConfiguration: 0\n        firmwareParams:\n          ...\n      medium:\n        bigQuad: True\n        batteryVoltageWarning: 7.6  # V\n        batteryVoltateCritical: 7.4 # V\n        markerConfiguration: 1\n        dynamicsConfiguration: 0\n        firmwareParams:\n          ...\n    numMarkerConfigurations: 2\n    markerConfigurations:\n      \"0\":  # for standard Crazyflie\n        numPoints: 4\n        offset: [0.0, -0.01, -0.04]\n        points:\n          \"0\": [0.0177184,0.0139654,0.0557585]\n          \"1\": [-0.0262914,0.0509139,0.0402475]\n          \"2\": [-0.0328889,-0.02757,0.0390601]\n          \"3\": [0.0431307,-0.0331216,0.0388839]\n      \"1\": # medium frame\n        numPoints: 4\n        offset: [0.0, 0.0, -0.03]\n        points:\n          \"0\": [-0.00896228,-0.000716753,0.0716129]\n          \"1\": [-0.0156318,0.0997402,0.0508162]\n          \"2\": [0.0461693,-0.0881012,0.0380672]\n          \"3\": [-0.0789959,-0.0269793,0.0461144]\n    numDynamicsConfigurations: 1\n    dynamicsConfigurations:\n      \"0\":\n        maxXVelocity: 2.0\n        maxYVelocity: 2.0\n        maxZVelocity: 3.0\n        maxPitchRate: 20.0\n        maxRollRate: 20.0\n        maxYawRate: 10.0\n        maxRoll: 1.4\n        maxPitch: 1.4\n        maxFitnessScore: 0.001\n\nThe dynamics and marker configurations are only relevant when using a motion capture system for tracking, see below for details.\n\n.. tabs::\n\n   .. group-tab:: Unique Marker Arrangements\n\n      The ``markerConfiguration`` fields are not needed with unique marker arrangements.\n      All marker setup should be done in your motion capture system.\n      Create one object in your motion capture software for each marker arrangement\n      and give them names like ``cf1``, ``cf2``, ``cf3``, etc., corresponding to the IDs listed in your ``crazyflies.yaml``.\n\n   .. group-tab:: Duplicated Marker Arrangements\n\n      For duplicated marker arrangements, each arrangement must be described by a ``markerConfigurations`` entry.\n      The ``points`` specify the physical arrangement of markers you use, in the motion capture coordinate system.\n      For example, the marker configuration ``\"0\"`` corresponds to an off-the-shelf Crazyflie with the marker configuration shown below:\n\n      .. figure:: images/markerConfigurationExample.jpg\n         :align: center\n         :scale: 70%\n\n      To get values for the ``points``, follow these steps:\n\n      #. Place one CF with the desired arrangement at the origin of your motion capture space. The front of the Crazyflie should point in the ``x`` direction of the motion capture coordinate system.\n      #. Find the coordinates of the used markers, for example by using ``roslaunch crazyswarm mocap_helper.launch``. (You may need to do ``source ros_ws/devel/setup.bash`` before ``roslaunch``)\n      #. Update ``crazyflieTypes.yaml``.\n\n   .. group-tab:: Single Marker\n\n      For single markers, the ``markerConfigurations`` entry simply contains a single ``points`` entry. This point should describe the offset of the marker with respect to the Crazyflie's center of mass. For example, the marker configuration ``\"3\"`` corresponds to the marker placement shown below:\n\n      .. figure:: images/CrazyflieWithSingleMarker.jpg\n         :align: center\n         :scale: 70%\n\n\n\n.. _config_chooser:\n\nManage fleet with the Chooser\n-----------------------------\n\nThe graphical *Chooser* tool is used to enable/disable subsets of the available Crazyflies\nand perform other practical tasks.\nChooser relies on the additional configuration file ``allCrazyflies.yaml``,\nwhich has the same format as ``crazyflies.yaml`` (see :ref:`config_crazyflies_yaml`).\nEdit this file to contain all the Crazyflies you have available.\nThen, start the Chooser::\n\n    cd ros_ws/src/crazyswarm/scripts\n    python chooser.py\n\nYou should see something like the screenshot below.\n\n.. image:: images/chooser.png\n\nEach checkbox corresponds to an entry in ``allCrazyflies.yaml``.\nThe checkbox positions should match the ``initialPosition`` fields in the file.\nYou can drag a box to select many checkboxes at once.\n\nWhenever the selection is changed,\nthe ``allCrazyflies.yaml`` entries for the selected boxes are **immediately** copied and written to ``crazyflies.yaml``.\n\n.. note::\n\n   If you are using the ``allCrazyflies.yaml`` and the Chooser,\n   you should never need to edit ``crazyflies.yaml`` manually.\n\nThe buttons perform various functions that can be tedious to do for many CFs:\n\n:Clear:   Deselects all CFs.\n:Fill:    Selects all CFs.\n:battery: Retrieves battery voltage for enabled CFs. Only works if ``crazyflie_server`` is not running at the same time. Can be used while the CF is in power-safe mode.\n:version: Retrieves STM32 firmware version of enabled CFs. Only works if ``crazyflie_server`` is not running at the same time. Can only be used if CF is fully powered on.\n:sysOff: Puts enabled CFs in power-safe mode (NRF51 powered, but STM32 turned off). Only works if ``crazyflie_server`` is not running at the same time.\n:reboot: Reboot enabled CFs (such that NRF51 and STM32 will be powered). Only works if ``crazyflie_server`` is not running at the same time.\n:flash (STM): Flashes STM32 firmware to enabled CFs. Only works if ``crazyflie_server`` is not running at the same time. Assumes that firmware is built in ``crazyflie-firmware/cf2.bin``. Use ``--stm32Fw`` to specify a custom path.\n:flash (NRF): Flashes NRF51 firmware to enabled CFs. Only works if ``crazyflie_server`` is not running at the same time. Assumes that firmware is built in ``crazyflie2-nrf-firmware/cf2_nrf.bin``. Use ``--nrf51Fw`` to specify a custom path.\n\n\nTesting configuration\n---------------------\n\nOnce you have finished configuration,\nmove on to the :ref:`tutorial_hover` tutorial for your first test flight!\n"
  },
  {
    "path": "docs/generate_install_deps_code.py",
    "content": "import sys\n\nimport yaml\n\n\ndef main():\n    workflow_path = sys.argv[1]\n    with open(workflow_path) as f:\n        workflow = yaml.load(f, Loader=yaml.CLoader)\n    steps = workflow[\"jobs\"][\"build\"][\"steps\"]\n    depsteps = [s for s in steps if s[\"name\"] == \"Install Dependencies\"]\n    assert len(depsteps) == 1\n    depstep = depsteps[0]\n    code = depstep[\"run\"]\n    code = code.replace(\n        \"${{ matrix.pyVer }}\", \"${CSW_PYTHON}\"\n    ).replace(\n        \"${{ matrix.ros }}\", \"[ROS version]\"\n    )\n    print(code.strip())\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "docs/generated/.gitignore",
    "content": "*.rst\n*.rstinclude\n"
  },
  {
    "path": "docs/gettingstarted.rst",
    "content": "Getting Started\n===============\n\n#. Read the Crazyswarm paper to understand the different components of the system. A preprint is available `here <http://usc-actlab.github.io/publications/Preiss_ICRA2017.pdf>`__.\n#. Learn more about the Crazyflie platform, e.g. by reading sections 1 and 2 of \"Flying Multiple UAVs Using ROS\", Springer Book on Robot Operating System (ROS), 2017. A preprint is available `here <http://usc-actlab.github.io/publications/Hoenig_Springer_ROS2017.pdf>`__ or by following the `official getting started guide <https://www.bitcraze.io/documentation/start/>`__.\n#. Learn about the Robot Operating System (ROS), e.g. by reading part 1 of \"Programming Robots with ROS. A Practical Introduction to the Robot Operating System\" by Morgan Quigley, Brian Gerkey, William D. Smart, O'Reilly, 2015.\n#. If you use a motion capture for external localization, read the respective user manual. Proper tuning of the system is essential to achieve good tracking performance."
  },
  {
    "path": "docs/glossary.rst",
    "content": "Glossary\n========\n\n.. glossary::\n\n  Piecewise Polynomial\n    A piecewise function is function of the form\n\n    .. math::\n\n      f(t) = \\begin{cases}\n        f_1(t) :& 0 \\leq t < t_1 \\\\\n        f_2(t) :& t_1 \\leq t < t_2 \\\\\n        \\hfill \\vdots \\hfill & \\hfill \\vdots \\hfill \\hfill \\\\\n        f_n(t) :& t_{n - 1} \\leq t \\leq t_n.\n      \\end{cases}\n\n    where :math:`0 < t_1 < \\cdots < t_n`. It is naturally possible to define\n    piecewise functions on unbounded domains too, but in typical applications\n    the domain is bounded.\n\n    A piecewise polynomial is a piecewise function where each of the\n    :math:`f_i(t)` is a polynomial, possibly vector-valued.\n    With suitable number of pieces and polynomial degree, piecewise polynomials\n    make a highly expressive function class that is still simple\n    and numerically stable.\n\n    .. figure:: images/piecewise_poly.png\n       :width: 80%\n       :align: center\n       \n       A piecewise polynomial with four pieces. At the point\n       :math:`\\alpha = 2`, this function is continuous but not\n       differentiable. Such a nonsmooth polynomial would not be used for\n       quadrotor trajectory planning.\n\n    In Crazyswarm, we use degree-7 polynomials with 4-dimensional \n    vector-valued output: (x, y, z) position and yaw angle. The quadrotor's\n    `differential flatness <https://en.wikipedia.org/wiki/Flatness_(systems_theory)>`_\n    property makes it possible to compute other states (attitude, acceleration,\n    angular velocity) from these four values.\n\n\n  Setpoint\n    A collection of desired values for some or all of the quadrotor's state that the feedback controller should try to achieve.\n    For example, a setpoint may specify position, velocity, and acceleration -- or just position.\n"
  },
  {
    "path": "docs/hardware.rst",
    "content": "Hardware\n========\n\nIf you are planning to built a Crazyswarm yourself, below is the list of components we use.\n\nComponents\n----------\n\nPrices and links as of summer 2017.\n\n.. csv-table:: Part List\n   :header: \"Name\",\"Price (USD)\",\"Notes\",\"Distributor\",\"Link\"\n\n\n   \"Bitcraze Crazyflie 2.0\",180,,\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/kits/products/crazyflie-2-0\"\n   \"Crazyradio PA\",30,\"1 suffices for 15 Crazyflies. Also available as kit with Crazyflie.\",\"Bitcraze/Seeed\",\"https://store.bitcraze.io/products/crazyradio-pa\"\n   \"LED-ring deck\",20,\"Optional for light effects\",\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/decks/products/led-ring-deck\"\n   \"Propeller pack\",5,\"Breaks most often; buy ~ 0.5 packs per CF\",\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/spare-parts-crazyflie-2-0/products/propeller-pack\"\n   \"Spare motor mounts\",5,\"Breaks second most often; buy ~0.5 packs per CF\",\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/spare-parts-crazyflie-2-0/products/crazyflie-2-0-4-x-spare-7-mm-motor-mounts\"\n   \"Turnigy nano-tech 260mAh 1S\",2.45,\"Buy 2 or 3 per CF\",\"Hobbyking\",\"https://hobbyking.com/en_us/turnigy-nano-tech-260mah-1s-35-70c-lipo-pack-qr-ladybird-genius-cp-mini-cp.html?___store=en_us\"\n   \"Turnigy Micro-6 Lipoly Battery Charger\",13.34,\"Buy 1 for 6 Cfs\",\"Hobbyking\",\"https://hobbyking.com/en_us/turnigy-micro-6-lipoly-battery-charger.html?___store=en_us\"\n   \"7.9mm reflective markers\",4,\"Buy 4 per CF (and a few spares)\",\"B&L Engineering\",\"http://www.bleng.com/7-9mm-reflective-markers-set-of-10.html\"\n   \"Double-sided foam tape (e.g. 3M VHB)\",10,\"Command Poster Strips work well, too\",,\n   \"Debug adapter\",30,\"1 suffices for swarm; only needed if firmware development is intended\",\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/accessories/products/debug-adapter\"\n   \"J-LINK EDU\",60,\"1 suffices for swarm; only needed if firmware development is intended\",\"Segger\",\"https://shop-us.segger.com/J_Link_EDU_p/8.08.90.htm\"\n\n\nMedium Quadrotor\n----------------\n\n.. image:: images/medium.jpg\n\nPrices and links as of March 2018.\n\n.. csv-table:: Part List\n   :header: \"Part\",\"Item\",\"Weight (g)\", \"Price (USD)\",\"Notes\",\"Distributor\",\"Link\"\n\n\n   \"Flight Controller\",\"Bitcraze Crazyflie 2.0\",,180,,\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/kits/products/crazyflie-2-0\"\n   \"Flight Controller\",\"Bitcraze BigQuad Deck\",4,7,,\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/decks/products/bigquad-deck\"\n   \"Frame + Prop Guards\",\"Crazypony KingKong Flyegg 130mm\",30,22.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B073LBNJCR/ref=oh_aui_detailpage_o06_s02?ie=UTF8&psc=1\"\n   \"Power + ESC combo\",\"DYS F18A 4-in-1 ESC\",8,35.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B077G26CTX/ref=oh_aui_detailpage_o06_s01?ie=UTF8&psc=1\"\n   \"Motors x4\", \"Crazypony 1104 7500KV x4\",26,52.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B06XNJ8XPP/ref=oh_aui_detailpage_o06_s01?ie=UTF8&psc=1\"\n   \"Propellers\",\"Crazypony 2840 3-blade x8\",5.5,7.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B071FN9V78/ref=oh_aui_detailpage_o06_s00?ie=UTF8&psc=1\"\n   \"Battery\",\"Crazypony 450mAh 2S x2\",29,18.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B07351J77T/ref=oh_aui_detailpage_o02_s00?ie=UTF8&psc=1\"\n\n\nLarge Quadrotor\n----------------\n\n.. image:: images/large.jpg\n\nPrices and links as of March 2018.\n\n.. csv-table:: Part List\n   :header: \"Part\",\"Item\",\"Weight (g)\", \"Price (USD)\",\"Notes\",\"Distributor\",\"Link\"\n\n\n   \"Flight Controller\",\"Bitcraze Crazyflie 2.0\",,180,,\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/kits/products/crazyflie-2-0\"\n   \"Flight Controller\",\"Bitcraze BigQuad Deck\",4,7,,\"Bitcraze/Seeed\",\"https://store.bitcraze.io/collections/decks/products/bigquad-deck\"\n   \"Frame\",\"iFlight RACER iX5 V2 210mm\",24.2,36.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B06XYRPQCD/ref=oh_aui_detailpage_o05_s01?ie=UTF8&psc=1\"\n   \"Power Distribution\",\"Thriverline Matek PDB & Dual BEC\",13,10,,\"Amazon\",\"https://www.amazon.com/gp/product/B06XB9K9S8/ref=oh_aui_detailpage_o05_s02?ie=UTF8&psc=1\"\n   \"ESCs x4\",\"Makerfire BLHeli 20A x4\",25,34.99,,\"Amazon\",\"https://www.amazon.com/Makerfire-BLHeli-Brushless-Controller-QAV250/dp/B07869QR66/ref=sr_1_1\"\n   \"Motors\",\"DLFPV 2205 2300KV x4\",115,39.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B01JM1C9GK/ref=od_aui_detailpages02?ie=UTF8&psc=1\"\n   \"Propellers\",\"RAYCORP 5040 3-Blade x8\",6.2,14.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B01N3R7RCI/ref=oh_aui_detailpage_o05_s02?ie=UTF8&psc=1\"\n   \"Battery\",\"Tattu 1800mAh 45C 3\",200,19.99,,\"Amazon\",\"https://www.amazon.com/gp/product/B013I9SAHO/ref=oh_aui_detailpage_o05_s00?ie=UTF8&psc=1\"\n   \"Propeller Guards\",\"5-inch Prop guard for 250mm Class\",18,4.5,\"Optional\",\"Hobbyking\",\"https://hobbyking.com/en_us/propeller-guards-for-the-250-class-racer-5inch-set-of-4.html\"\n   \"Alternative Prop Guards\",\"KingKong 5 Inch Propeller Guard\",,4.9,\"Optional\",\"Helipal\",\"http://www.helipal.com/kingkong-5-inch-propeller-guard-black.html\"\n   \"SD Card Camera\",\"EOVAS 1080P Small Cam\",40,25,\"Optional\",\"Amazon\",\"https://www.amazon.com/gp/product/B074QM3JDP/ref=oh_aui_detailpage_o04_s00?ie=UTF8&psc=1\"\n"
  },
  {
    "path": "docs/howto/git_integration.rstinclude",
    "content": ".. _tutorial_git_integration:\n\nCrazyswarm Integration with Git\n-------------------------------\n\nIn this tutorial we discuss ways to use the Crazyswarm in your own projects, while properly \nversion-controlling you custom launch files and scripts.\n\n\nOption 1: Fork\n^^^^^^^^^^^^^^\n\nThe most straight-forward approach is to fork the Crazyswarm repository. This fork can be\nincluded as a submodule in your own projects and your own launch files and scripts can\nbe in `ros_ws/src/crazyswarm` along with the provided examples.\n\nThe only downside of this approach is that it becomes rather difficult to update with the \nlatest version upstream, especially if you have changes in one of the submodules (like \nthe firmware).\n\nOption 2: Custom ROS Package\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\nIf you only have custom launch files, scripts, or firmware, you can simplify the process\nby creating a custom out-of-source ROS package: ::\n\n\n\tany/folder$ catkin_create_pkg my-crazyswarm-pkg\n\nIn particular, you can create this package in any folder, including another git repository.\n\nThen, add this package to your crazyswarm workspace by using a symbolic link: ::\n\n\tcrazyswarm/ros_ws/src/userPackages$ ln -s /path/to/my-crazyswarm-pkg .\n\nIn you package, you can have your own launch files, yaml configuration files, and scripts,\nsimilar to the folder structure in the crazyswarm package.\n\nTo run `chooser.py`, you can use its optional arguments::\n\n\tcrazyswarm/ros_ws/crazyswarm/scripts$ python chooser.py --configpath ../../userPackages/my-crazyswarm-pkg/launch/ --stm32Fw /path/to/cf2.bin\n\nTo run your own launch file, simply use: ::\n\n\t$ roslaunch my-crazyswarm-pkg my-custom-launch-file.launch\n\nTo run your own scripts, you need to adjust the Python package search path so that our\nhelper library is found: ::\n\n\tmy-crazyswarm-pkg/scripts$ export PYTHONPATH=$PYTHONPATH:/path/to/crazyswarm/ros_ws/src/crazyswarm/scripts\n\tmy-crazyswarm-pkg/scripts$ examplescript.py\n"
  },
  {
    "path": "docs/howto/howto.rst",
    "content": "How-To Guides\n=============\n\n.. include:: git_integration.rstinclude\n\n.. include:: streaming_setpoint.rstinclude\n"
  },
  {
    "path": "docs/howto/streaming_setpoint.rstinclude",
    "content": ".. _tutorial_streaming_setpoint:\n\nCreating a new streaming setpoint mode\n--------------------------------------\n\nIn this tutorial, we walk through the steps of implementing a new streaming\nsetpoint mode. This task is a good tutorial because it touches nearly all parts\nof the Crazyswarm system, including the onboard firmware.\n\n.. admonition:: High-level vs. streaming control modes\n\n\tIn a streaming setpoint mode, the PC sends :term:`Setpoint` values over the radio\n\tmany times per second to each robot individually.\n\tThe onboard feedback controller tries to achieve the states specified by the setpoint.\n\n\tIn comparison, in a high-level control mode, the PC sends instructions like\n\t:term:`Piecewise Polynomial` trajectory plans over the radio, and the onboard firmware\n\tuses the stored plan to compute a new control setpoint in every iteration of\n\tthe main loop.\n\n\tStreaming setpoint modes simplify the process of developing new high-level\n\tplanners, since the planner can run on the PC where it has access to more\n\tcomputational resources. However, they require more radio bandwidth, so they do\n\tnot scale as well to large numbers of robots. Currently, we have not validated\n\tanything larger than 7 robots on 3 radios.\n\n\tHigh-level control modes require implementing more planning logic\n\tonboard in the firmware code. This can be a challenge due to the limited computational\n\tresources and the difficulty of implementing numerical algorithms in C\n\tas compared to C++ or Python. However, the effort pays off in lower radio bandwidth\n\trequirements and increased robustness to hiccups in the radio communication.\n\nThe choice of a particular high-level planning algorithm suggests\na choice of which states to include in\nthe control setpoint. For example, piecewise polynomials (of sufficiently high\norder and smoothness) have continuous high-order derivatives, which makes it\npossible to compute setpoints for the entire state, including acceleration and\nangular velocity. On the other hand, a graph-based planner or RRT might only\ngive us a sequence of positions connected by straight lines, so it makes sense\nto only provide a position setpoint and let the onboard feedback controller\ndecide whatever velocity, acceleration, attitude, and angular velocity it needs\nto track the position setpoint most accurately.\n\nCRTP radio packet definition\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nFirst, we define our radio packet.\nRadio packets follow the CRTP (Crazyflie Real-Time Protocol)\ndefined by Bitcraze: `<https://www.bitcraze.io/docs/crazyflie-firmware/master/ctrp_index/>`_.\nOn that page we see the following diagram of the one-byte CRTP header: ::\n\n\t   7    6    5    4    3    2    1    0\n\t+----+----+----+----+----+----+----+----+\n\t|       Port        |  Link   |  Chan.  |\n\t+----+----+----+----+----+----+----+----+\n\nThe most important part is the 4-bit ``port`` value,\nwhich is used in the Crazyflie firmware to select between different subsystems\nfor further processing of the packet. Streaming control setpoints use port ``7``.\nWe define the radio protocol for our setpoint by defining C a struct in \n`crazyflie_cpp/include/crazyflie_cpp/crtp.h <https://github.com/whoenig/crazyflie_cpp/blob/master/include/crazyflie_cpp/crtp.h>`_:\n\n.. code-block:: c\n\n\tstruct crtpFullStateSetpointRequest\n\t{\n\t  crtpFullStateSetpointRequest(\n\t\tfloat x, float y, float z,\n\t\tfloat vx, float vy, float vz,\n\t\tfloat ax, float ay, float az,\n\t\tfloat qx, float qy, float qz, float qw,\n\t\tfloat rollRate, float pitchRate, float yawRate);\n\t  const crtp header;\n\t  uint8_t type;\n\t  int16_t x;\n\t  int16_t y;\n\t  int16_t z;\n\t  int16_t vx;\n\t  int16_t vy;\n\t  int16_t vz;\n\t  int16_t ax;\n\t  int16_t ay;\n\t  int16_t az;\n\t  int32_t quat; // compressed quaternion, xyzw\n\t  int16_t omegax;\n\t  int16_t omegay;\n\t  int16_t omegaz;\n\t} __attribute__((packed));\n\tCHECKSIZE(crtpFullStateSetpointRequest)\n\nAfter the CRTP header, we have another byte ``uint8_t type`` specifying the type of control setpoint.\nThe canonical source of these values is ``enum packet_type``\n`in the Crazyflie firmware <https://github.com/bitcraze/crazyflie-firmware/blob/f28ef7ad675146514caf5388749b466699ba23f3/src/modules/src/crtp_commander_generic.c#L65-L74>`_.\nIn the remainder of the struct we have 29 bytes left for the setpoint value.\n\n.. admonition:: How we implement the binary protocol\n\n\tTo send a packet, we cast the struct to a raw byte array ``uint8_t *``.\n\tThe reciever casts the packet bytes back to a struct.\n\tThis technique is not considered robust compared to parsing the byte stream;\n\tin fact, it only works at all due to the following facts:\n\n\t- The C and C++ languages both enforce that a ``struct``'s members are laid out in memory\n\t  in the same order in which they are declared in the source code.\n\t- The line ``__attribute((packed))`` is a\n\t  `GCC extension <https://gcc.gnu.org/onlinedocs/gcc/Common-Type-Attributes.html#Common-Type-Attributes>`_.\n\t  (This means it is not part of the ANSI C language specification, and C compilers\n\t  are not required to implement it.) \n\t  Its purpose is to disallow the compiler from performing\n\t  `struct padding <http://www.catb.org/esr/structure-packing/#_padding>`_.\n\t  This means there will be no empty space in the struct's memory layout.\n\t  In other words, its ``sizeof`` is exactly the sum of the ``sizeof`` s of its members.\n\t- The x86 and ARM architectures are both little-endian by default,\n\t  so types that are larger than 8 bits are decoded in the correct byte order.\n\t- We always use\n\t  `exact-width integer types <https://en.wikibooks.org/wiki/C_Programming/stdint.h>`_\n\t  provided by ``<stdint.h>`` instead of the more familiar types\n\t  ``int``, ``long``, ``char``, and so on.\n\t  The latter types\n\t  `can vary in size on different platforms <https://en.wikipedia.org/wiki/C_data_types#Main_types>`_.\n\t  For example, ``long`` is 4 bytes on 64-bit Windows systems\n\t  but 8 bytes on 64-bit Linux systems.\n\n\tFrom all this, one can show that the struct-casting method will produce\n\tcorrect results in our setup.\n\tThe macro ``CHECKSIZE`` on the final line uses a ``static_assert``\n\tto ensure at compile time that the struct is small enough to fit in a radio packet.\n\nNote that our example has used 16-bit fixed-point numbers and advanced\n`quaternion <https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation>`_ compression\nto fit a lot of values in one packet. Most setpoint types contain fewer values\nand fit in the packet without as much compression.\nAll CRTP structs in ``crtp.h`` should have a constructor that accepts uncompressed types,\nso the calling code does not need to know about compression tricks or the exact byte layout.\nIf there is nontrivial work to be done in the constructor, it can be placed in\n``crazyflie_cpp/src/crtp.cpp``, otherwise it should be defined inline in ``crtp.h``.\nOur new constructor looks like:\n\n.. code-block:: c++\n\n\tcrtpFullStateSetpointRequest::crtpFullStateSetpointRequest(\n\t  float x, float y, float z,\n\t  float vx, float vy, float vz,\n\t  float ax, float ay, float az,\n\t  float qx, float qy, float qz, float qw,\n\t  float rollRate, float pitchRate, float yawRate)\n\t  : header(0x07, 0), type(6)\n\t{\n\t\tfloat s = 1000.0;\n\t\tthis->x = s * x;\n\t\t...\n\t}\n\nFirst, we specify port ``7`` in the header byte (as discussed above) and the correct ``type`` value.\nIn the constructor body, we convert floating-point values in meters\nto integer values in millimeters. (Most of the repetitive code is snipped here.)\n\n``crazyflie_cpp`` wrapper\n^^^^^^^^^^^^^^^^^^^^^^^^^\nCalling code never constructs ``crtp.h`` packets directly;\ninstead, it interacts with the radio via the ``Crazyflie`` class defined in\n`crazyflie_cpp/include/crazyflie_cpp/Crazyflie.h <https://github.com/whoenig/crazyflie_cpp/blob/master/include/crazyflie_cpp/Crazyflie.h>`_.\nWe need to add a new method to the class ``Crazyflie``:\n\n.. code-block:: c++\n\n  void sendFullStateSetpoint(\n    float x, float y, float z,\n    float vx, float vy, float vz,\n    float ax, float ay, float az,\n    float qx, float qy, float qz, float qw,\n    float rollRate, float pitchRate, float yawRate);\n\nThe implementation should go in\n`crazyflie_cpp/src/Crazyflie.cpp <https://github.com/whoenig/crazyflie_cpp/blob/master/src/Crazyflie.cpp>`_\nand is very simple:\n\n.. code-block:: c++\n\n\tvoid Crazyflie::sendFullStateSetpoint(\n\t\tfloat x, float y, float z,\n\t\tfloat vx, float vy, float vz,\n\t\tfloat ax, float ay, float az,\n\t\tfloat qx, float qy, float qz, float qw,\n\t\tfloat rollRate, float pitchRate, float yawRate)\n\t{\n\t  crtpFullStateSetpointRequest request(\n\t\tx, y, z,\n\t\tvx, vy, vz,\n\t\tax, ay, az,\n\t\tqx, qy, qz, qw,\n\t\trollRate, pitchRate, yawRate);\n\t  sendPacket(request);\n\t}\n\n\nNote that we are using\n`the templated overload of Crazyflie::sendPacket <https://github.com/whoenig/crazyflie_cpp/blob/0017a1560b5c14970698ecae98f153701c4518db/include/crazyflie_cpp/Crazyflie.h#L373-L380>`_\nthat handles casting the struct pointer to ``uint8_t *`` automatically.\n\n\nROS service\n^^^^^^^^^^^\nAlthough ``crazyflie_cpp`` fully abstracts away the details of the binary\nprotocol and the radio hardware, there are still a few reasons why it's not\ndesirable to call ``crazyflie_cpp`` functions directly from higher-level code.\n\nFirst, the radio transmission functions block due the latency of the USB bus and of\nthe radio communication itself. This makes sense within ``crazyflie_cpp``,\nbecause there is no other work to do besides sending and recieving radio\npackets, and the radio can only be used by one thread at a time.\nHowever, in the higher-level code, there is no reason to block\nbecause control setpoints are a \"fire and forget\" data stream (like UDP) --\nthe high-level code should not care whether or not every single control setpoint packet is\ntransmitted successfully. There is other work to be done instead, such as\ncomputing the next setpoint. This implies that the radio functions should run,\nat minimum, in a separate thread.\n\nAdditionally, C++ is a good language for a radio protocol implementation,\nbut it is a more difficult language than Python. A Python wrapper makes\nCrazyswarm more accessible to novice programmers.\n\nFinally, if high-level code calls radio functions directly, it cannot run in a\nsimulator. There needs to be an abstraction layer *somewhere* in the system.\n\nIn Crazyswarm, we address these issues by using ROS (Robot Operating System)\nto run the ``crazyflie_cpp`` functionality in a separate process.\nDespite its name, ROS is not an operating system.\nIt is an application-level software framework focused on typed interprocess communication.\nAn introduction to ROS is out of this tutorial's scope;\nreaders should refer to `<https://wiki.ros.org>`_.\nWe assume the reader is familiar with ROS's concepts of \n*messages*, *nodes* and *topics*,\nwhich are designed specifically for streaming \"fire and forget\" data.\n\nComplex setpoint types may require defining a new ROS message type.\nIt is always preferable to use standard types if an appropriate type exists.\nFor the full quadrotor state, we define a new message\nin `crazyswarm/msg/FullState.msg <https://github.com/USC-ACTLab/crazyswarm/tree/master/ros_ws/src/crazyswarm/msg/FullState.msg>`_:\n\n.. code-block:: none\n\n\tHeader header\n\tgeometry_msgs/Pose pose\n\tgeometry_msgs/Twist twist\n\tgeometry_msgs/Vector3 acc\n\nNotice how we used the ``Pose`` and ``Twist`` standard compound types instead of raw\n``Vector3`` for everything. This helps Crazyswarm's compatibility with other\nrobotics packages available in ROS, such as planners.\n\nFor performance reasons, Crazyswarm is implemented as one monolithic ROS node\ninstead of several communicating nodes. This means we only need to modify one\nclass, ``CrazyflieROS``, to support our new setpoint.\nThere are three main changes: adding a method to handle setpoint messages,\nadding a ``ros::Subscriber`` object to subscribe to those messages,\nand setting up the subscriber in the ``run()`` method.\nWe show the basic idea here, abbreviating other methods and repetitive code\nwith ``...``:\n\n.. code-block:: c++\n\n\tclass CrazyflieROS\n\t{\n\tpublic:\n\t...\n\t\tvoid cmdFullStateSetpoint(\n\t\t\tconst crazyswarm::FullState::ConstPtr& msg)\n\t\t{\n\t\t\tif (!m_isEmergency) {\n\t\t\t\tfloat x = msg->pose.position.x;\n\t\t\t\t...\n\t\t\t\tfloat yawRate = msg->twist.angular.z;\n\n\t\t\t\tm_cf.sendFullStateSetpoint(x, ..., yawRate);\n\n\t\t\t\tm_sentSetpoint = true;\n\t\t\t}\n\t\t}\n\t...\n\t\tvoid run()\n\t\t{\n\t\t\tros::NodeHandle n;\n\t\t\t...\n\t\t\tm_subscribeCmdFullState = n.subscribe(\n\t\t\t\tm_tf_prefix + \"/cmd_full_state\",\n\t\t\t\t1,\n\t\t\t\t&CrazyflieROS::cmdFullStateSetpoint,\n\t\t\t\tthis);\n\t\t}\n\t\n\tprivate:\n\t...\n\t\tros::Subscriber m_subscribeCmdFullState;\n\t...\n\t}\n\nNote that our new method ``cmdFullStateSetpoint`` does little more than unpacking the ROS message\nand calling the appropriate method on ``m_cf``, which is an instance of\nthe ``crazyflie_cpp/Crazyflie`` class. We also check for emergency state.\nThe flag ``m_sentSetpoint = true`` helps decide whether it is necessary\nto send a \"heartbeat\" ping packet to the Crazyflie.\n\nIn the ``run()`` method, we have chosen a name for the setpoint's ROS topic,\nand we are initializing our ``ros::Subscriber`` object to connect that topic\nto the new method.\n\n\n``pycrazyswarm`` wrapper\n^^^^^^^^^^^^^^^^^^^^^^^^\nFinally, we implement the ability to publish the ``FullState`` message in\n``pycrazyswarm`` Python class. This is another thin wrapper, taking care of\nthe ROS publisher object and converting ``numpy`` types into ROS types:\n\n.. code-block:: python\n\n\tfrom crazyswarm.msg import ..., FullState\n\n\tclass Crazyflie:\n\n\t\tdef __init__(...):\n\t\t\t...\n\t\t\tself.cmdFullStatePublisher = rospy.Publisher(\n\t\t\t\tprefix + \"/cmd_full_state\", FullState, queue_size=1)\n\t\t\tself.cmdFullStateMsg = FullState()\n\t\t\tself.cmdFullStateMsg.header.seq = 0\n\t\t\tself.cmdFullStateMsg.header.frame_id = \"/world\"\n\t\t\t...\n\n\t\t...\n\n\t\tdef cmdFullState(self, pos, vel, acc, yaw, omega):\n\t\t\tself.cmdFullStateMsg.header.stamp = rospy.Time.now()\n\t\t\tself.cmdFullStateMsg.header.seq += 1\n\t\t\tself.cmdFullStateMsg.pose.position.x    = pos[0]\n\t\t\t...\n\t\t\tself.cmdFullStateMsg.twist.angular.z    = omega[2]\n\t\t\tself.cmdFullStatePublisher.publish(self.cmdFullStateMsg)\n\nThe Python class corresponding to the ``FullState`` message has been\nauto-generated by ROS's build system ``catkin_make``. We import it here.\n\nIn ``class Crazyflie``'s constructor,\nwe set up a ROS publisher object for our new topic.\nNote that we publish on the same topic that we subscribed to in the C++\n``CrazyflieROS`` node earlier.\nWe also construct one ``FullState`` object and store it as a data member.\nThis is an important performance optimization\nto avoid allocating and deallocating heap memory every time we publish a setpoint.\n\nThe new method ``cmdFullState(...)`` is the outer layer that ``pycrazyswarm`` scripts will use.\nWe update the timestamp and sequence number on the message object we constructed earlier;\ncopy the data from the arguments (either plain Python arrays or ``numpy`` arrays)\ninto the ROS message object, and finally publish it.\nNote that the ``publish(...)`` call will return immediately\nrather than waiting for the packet to actually be sent on the radio.\n\n.. admonition:: Note: Why so many layers?\n\n\tWe have modified three layers on the PC side of things to add our new\n\tsetpoint type: ``crazyflie_cpp``, ``crazyswarm``, and ``pycrazyswarm``.\n\tWe wrote a lot of boilerplate code to copy the same data from\n\tNumPy types, to ROS types, to C++ function arguments, and finally to\n\ta CRTP binary protocol struct. To understand what we gained with this\n\tlayered approach, it is helpful to think about the main role of each\n\tlayer:\n\n\t\t1. ``crazyflie_cpp`` is the only layer that needs to understand\n\t\t   the radio protocol and how to control the Crazyradio via USB.\n\n\t\t2. ``crazyswarm`` handles all the concurrency.\n\t\t   It performs the M:N multiplexing of multiple Crazyflies\n\t\t   onto multiple Crazyradios, deals with resending and ACKs\n\t\t   in reliable communiation modes (not discussed in this tutorial),\n\t\t   communicates with the motion capture system, and so on.\n\n\t\t3. ``pycrazyswarm`` implements the shared abstraction of the\n\t\t   real-hardware system and simulator. It is good to do this outside\n\t\t   the ROS layer, because ROS is finicky about Linux distributions\n\t\t   and versions. We can develop in the simulator on MacOS and other\n\t\t   Linuxes.\n\t\n\tIt is also worth mentioning that ``crazyflie_cpp`` is a standalone \n\tproject that can be used outside the Crazyswarm setting.\n\n\nFirmware CRTP parsing\n^^^^^^^^^^^^^^^^^^^^^\nWe are now finished with the PC part of our implementation.\nWe turn our attention to the onboard firmware.\nAs mentioned earlier, the first step is to define a packed struct\nfor \"parsing by casting\" of the incoming raw bytes.\nThis takes place entirely in ``crazyflie-firmware/src/modules/src/crtp_commander_generic.c``:\n\n.. code-block:: c\n\n\tstruct fullStatePacket_s {\n\t\tint16_t x;         // position - mm\n\t\tint16_t y;\n\t\tint16_t z;\n\t\tint16_t vx;        // velocity - mm / sec\n\t\tint16_t vy;\n\t\tint16_t vz;\n\t\tint16_t ax;        // acceleration - mm / sec^2\n\t\tint16_t ay;\n\t\tint16_t az;\n\t\tint32_t quat;      // compressed quaternion, see quatcompress.h\n\t\tint16_t rateRoll;  // angular velocity - milliradians / sec\n\t\tint16_t ratePitch; //  (NOTE: limits to about 5 full circles per sec.\n\t\tint16_t rateYaw;   //   may not be enough for extremely aggressive flight.)\n\t} __attribute__((packed));\n\nWe then write a decoder that unpacks the (possibly compressed)\nCRTP setpoint packet into the firmware's ``setpoint_t`` struct.\nCritically, the ``setpoint_t`` struct contains members for all data\nthat *any* setpoint mode might require, and \"mode\" tags that inform the\nfeedback controller on how it should behave:\n\n.. code-block:: c\n\n\tstatic void fullStateDecoder(setpoint_t *setpoint, uint8_t type, const void *data, size_t datalen)\n\t{\n\t\tconst struct fullStatePacket_s *values = data;\n\n\t\tASSERT(datalen == sizeof(struct fullStatePacket_s));\n\n\t\t#define UNPACK(x) \\\n\t\tsetpoint->mode.x = modeAbs; \\\n\t\tsetpoint->position.x = values->x / 1000.0f; \\\n\t\tsetpoint->velocity.x = (values->v ## x) / 1000.0f; \\\n\t\tsetpoint->acceleration.x = (values->a ## x) / 1000.0f; \\\n\n\t\tUNPACK(x)\n\t\tUNPACK(y)\n\t\tUNPACK(z)\n\t\t#undef UNPACK\n\n\t\tfloat const millirad2deg = 180.0f / ((float)M_PI * 1000.0f);\n\t\tsetpoint->attitudeRate.roll = millirad2deg * values->rateRoll;\n\t\tsetpoint->attitudeRate.pitch = millirad2deg * values->ratePitch;\n\t\tsetpoint->attitudeRate.yaw = millirad2deg * values->rateYaw;\n\n\t\tquatdecompress(values->quat, (float *)&setpoint->attitudeQuaternion.q0);\n\t\tsetpoint->mode.quat = modeAbs;\n\t\tsetpoint->mode.roll = modeDisable;\n\t\tsetpoint->mode.pitch = modeDisable;\n\t\tsetpoint->mode.yaw = modeDisable;\n\t}\n\nThe ``UNPACK`` macro is a questionable attempt to reduce the amount of boilerplate code.\nIt may be removed in the future.\n(This function would be much simpler if the packet were not compressed.)\nWithin ``UNPACK``, setting ``setpoint->mode->x`` to ``modeAbs`` informs the\ncontroller that it should track the absolute position, not just velocity.\nThe other modes\n(defined in ``crazyflie-firmware/src/modules/interface/stabilizer-types.h``)\nare ``modeVelocity``, for velocity tracking,\nand ``modeDisable``, meaning the controller should ignore that state completely.\n\nNext, we add our new setpoint to the ``packet_type`` enum\nand map this particular enum value to our decoder via an array of function pointers:\n\n.. code-block:: c\n\n\tenum packet_type {\n\t\t...\n\t\tfullStateType = 6,\n\t\t...\n\t};\n\n\t...\n\n\tconst static packetDecoder_t packetDecoders[] = {\n\t\t...\n\t\t[fullStateType]\t\t = fullStateDecoder,\n\t\t...\n\t};\n\nNote that the value ``6`` for this enum corresponds to the initialization\nof the ``uint8_t type`` member of ``crtpFullStateSetpointRequest`` in\nits constructor in\n``crazyflie_cpp/.../crtp.h``. It is the programmer's job to ensure these match.\n\nThe function ``crtpCommanderGenericDecodeSetpoint`` parses the ``type`` byte\nand dispatches to the correct decoder.\nBy construction, it does not need to be modified when we add a new setpoint type.\n\n\nOnboard control\n^^^^^^^^^^^^^^^\nThe needed changes in onboard feedback control may change depending on the\nsemantics of the new setpoint. In the case of the full-state setpoint,\nit is intended to be used with the \"Mellinger\" controller\n(`crazyflie-firmware/src/modules/src/controller_mellinger.c <https://github.com/bitcraze/crazyflie-firmware/blob/master/src/modules/src/controller_mellinger.c>`_,\nnamed after the paper by Daniel Mellinger and Vijay Kumar).\n\nA notable snippet of the controller code is the following:\n\n.. code-block:: c\n\n\tif (setpoint->mode.x == modeAbs) {\n\t\ttarget_thrust.x = g_vehicleMass * setpoint->acceleration.x                       + kp_xy * r_error.x + kd_xy * v_error.x + ki_xy * i_error_x;\n\t\ttarget_thrust.y = g_vehicleMass * setpoint->acceleration.y                       + kp_xy * r_error.y + kd_xy * v_error.y + ki_xy * i_error_y;\n\t\ttarget_thrust.z = g_vehicleMass * (setpoint->acceleration.z + GRAVITY_MAGNITUDE) + kp_z  * r_error.z + kd_z  * v_error.z + ki_z  * i_error_z;\n\t} else {\n\t\ttarget_thrust.x = -sinf(radians(setpoint->attitude.pitch));\n\t\ttarget_thrust.y = -sinf(radians(setpoint->attitude.roll));\n\t\t// In case of a timeout, the commander tries to level, ie. x/y are disabled, but z will use the previous setting\n\t\t// In that case we ignore the last feedforward term for acceleration\n\t\tif (setpoint->mode.z == modeAbs) {\n\t\t  target_thrust.z = g_vehicleMass * GRAVITY_MAGNITUDE + kp_z  * r_error.z + kd_z  * v_error.z + ki_z  * i_error_z;\n\t\t} else {\n\t\t  target_thrust.z = 1;\n\t\t}\n\t}\n\nThe ``if`` statement checks the ``mode`` values in the setpoint to see if the\nsetpoint has specified absolute position control or not.\nIf so (the first branch), we compute a target thrust vector using a PID  control law\nwith the desired position and velocity from the setpoint. We also use the\nacceleration value from the setpoint as a feedforward term.\nIf not, we construct a target thrust vector based on the roll and pitch setpoints.\n\nThis code does not seem to handle the case when ``setpoint->mode.x == modeVelocity``.\nPresumably, the second branch is only meant to handle ``setpoint->mode.x == modeDisable``.\nIn general, the \"compatibility matrix\" between setpoint types and controller types\n(other controllers include ``controller_pid.c`` and ``controller_indi.c``)\nis somewhat murky; this should be improved in future work.\n\n"
  },
  {
    "path": "docs/index.rst",
    "content": ".. _introduction:\n\nWelcome to Crazyswarm's documentation!\n======================================\n\nThe Crazyswarm platform allows you to fly a swarm of\n`Bitcraze Crazyflie 2.x <https://www.bitcraze.io/products/crazyflie-2-1/>`_ and `Bitcraze Crazyflie Bolt-based <https://store.bitcraze.io/products/crazyflie-bolt>`_ \nquadcopters in tight, synchronized formations.\nDifferent localization systems are supported: LightHouse, LPS, and motion capture. The Crazyswarm is particularly optimized for motion capture systems and supports VICON, OptiTrack, and Qualisys.\nWe successfully flew 49 Crazyflies using three Crazyradios.\nAn example video for what you can do is shown below:\n\n.. raw:: html\n\n    <div style=\"position: relative; padding-bottom: 56.25%; margin-bottom: 20pt; height: 0; overflow: hidden; max-width: 100%; height: auto;\">\n        <iframe src=\"https://www.youtube.com/embed/D0CrjoYDt9w\" frameborder=\"0\" allowfullscreen style=\"position: absolute; top: 0; left: 0; width: 100%; height: 100%;\"></iframe>\n    </div>\n\n\nHow is Crazyswarm different from Bitcraze's `Crazyflie Python API <https://github.com/bitcraze/crazyflie-lib-python>`_?\n-----------------------------------------------------------------------------------------------------------------------\n\nBoth can be used to control several Crazyflies from a Python script.\nHere are some differences:\n\n- **Motion capture integration.**\n  Crazyswarm contains drivers for common motion capture systems.\n  The Bitcraze API can *send* position measurements to the Crazyflie,\n  but does not know how to *get* position measurements from mocap hardware.\n- **Identical or single motion capture markers.**\n  Via `libobjecttracker <https://github.com/USC-ACTLab/libobjecttracker>`_,\n  Crazyswarm can track multiple quadrotors with identical motion capture marker arrangements,\n  or quadrotors with only one marker each.\n  Most motion capture devices do not support this natively.\n  To make it possible, the user must supply the quadrotors' initial positions in a configuration file\n  at startup to establish the mapping from radio addresses to positions.\n- **Broadcasts.**\n  Crazyswarm uses broadcast communication whenever possible to require fewer radios per Crazyflie. In contrast, the official SDK uses unicast communication instead.\n- **Simulation.**\n  Crazyswarm has a simulation mode with 3D graphics,\n  which makes it easy to validate complex scripts before running them on real hardware.\n- **Python firmware bindings.**\n  Crazyswarm's simulator is built upon automatically generated Python bindings\n  for certain modules in the Crazyflie firmware.\n  The binding system can be helpful when developing new firmware modules,\n  especially when they are mathematically complex and hard to debug.\n- **ROS foundation.**\n  The Crazyswarm server program is a ROS node.\n  The :ref:`api` is a thin wrapper around the ROS interface.\n  While we recommend the Python API for most applications,\n  the ROS interface is fully supported.\n\n\nCrazyswarm's academic origins\n-----------------------------\n\nThe Crazyswarm architecture, including some motivation for the design decisions, is described in\n`our paper <http://usc-actlab.github.io/publications/Preiss_ICRA2017.pdf>`_ [pdf].\n\nA talk at the `Aerial Swarms Workshop <https://lis2.epfl.ch/iros2019swarms/index.html>`_ at IROS 2019 includes a primer on how to use the Crazyswarm and a bibliography of papers using the Crazyswarm: `Slides <https://drive.google.com/file/d/15favAyrLLpC_O6nrAp-eIbZijFUMLgwV/view?usp=sharing>`_ [pdf].\n\n\nIf you use our work in academic research, please cite us:\n\n.. code-block:: none\n\n    @inproceedings{crazyswarm,\n      author    = {James A. Preiss* and\n                   Wolfgang  H\\\"onig* and\n                   Gaurav S. Sukhatme and\n                   Nora Ayanian},\n      title     = {Crazyswarm: {A} large nano-quadcopter swarm},\n      booktitle = {{IEEE} International Conference on Robotics and Automation ({ICRA})},\n      pages     = {3299--3304},\n      publisher = {{IEEE}},\n      year      = {2017},\n      url       = {https://doi.org/10.1109/ICRA.2017.7989376},\n      doi       = {10.1109/ICRA.2017.7989376},\n      note      = {Software available at \\url{https://github.com/USC-ACTLab/crazyswarm}},\n    }\n\n\nOur contributed code is licensed under the permissive MIT license, however some of the parts (such as the firmware) are licensed under their respective license.\n\n\nContents\n--------\n\n.. toctree::\n   changelog\n   gettingstarted\n   installation\n   configuration\n   tutorials/tutorials\n   howto/howto\n   api\n   internals\n   hardware\n   glossary\n   :maxdepth: 2\n\n\n\nIndices and tables\n------------------\n\n* :ref:`genindex`\n* :ref:`modindex`\n* :ref:`search`\n\n"
  },
  {
    "path": "docs/installation.rst",
    "content": ".. _installation:\n\nInstallation\n============\n\nCrazyswarm runs on **Ubuntu Linux** in one of the following configurations:\n\n====== ====== =======\nUbuntu Python ROS\n------ ------ -------\n20.04  3.7    Noetic\n18.04  2.7    Melodic\n====== ====== =======\n\nFor simulation-only operation, **Mac OS** is also supported.\nClick the appropriate tab(s) below to see the installation instructions for your desired configuration.\n\n.. note::\n   You must set the environment variable ``$CSW_PYTHON`` to the name of your Python interpreter\n   (e.g. ``python2`` or ``python3``)\n   before building.\n\n\n.. warning::\n   The `Windows Subsystem for Linux (WSL) <https://docs.microsoft.com/en-us/windows/wsl/about>`_ is not supported.\n   You must install Ubuntu either directly on the computer (recommended) or in a VM.\n\n\n.. tabs::\n\n   .. tab:: Simulation Only\n\n      You can write/debug ``pycrazyswarm`` scripts on a machine that does not have ROS installed.\n      On Mac OS, Crazyswarm must run within an Anaconda environment.\n      On Linux, using Anaconda is optional.\n      Select your platform from the tabs below:\n\n      .. tabs::\n\n         .. tab:: Linux or Mac OS with Anaconda\n\n            1. Set the ``$CSW_PYTHON`` environment variable::\n\n                $ export CSW_PYTHON=[python2 or python3]\n\n            2. Install `Anaconda Python 2.7 / 3.7 version <https://www.anaconda.com/distribution>`_ (We have tested on version ``2019.10``).\n\n            3. Clone the Crazyswarm git repository::\n\n                $ git clone https://github.com/USC-ACTLab/crazyswarm.git\n\n            4. Create the Anaconda environment with your desired Python version::\n\n                $ cd crazyswarm\n                $ conda create --name crazyswarm python=$CSW_PYTHON\n                $ conda env update -f conda_env.yaml\n\n            5. Activate the Anaconda environment::\n\n                $ conda activate crazyswarm\n\n            6. Run the build script::\n\n                $ ./buildSimOnly.sh\n\n            7. Verify the installation by running the unit tests::\n\n                $ cd ros_ws/src/crazyswarm/scripts\n                $ $CSW_PYTHON -m pytest\n\n         .. tab:: Linux without Anaconda\n\n            1. Set the ``$CSW_PYTHON`` environment variable::\n\n                $ export CSW_PYTHON=[python2 or python3]\n\n            2. Install the dependencies\n\n               .. program-output:: python3 generate_install_deps_code.py ../.github/workflows/ci-ros.yml | sed -e '/ros/d' -e '/usb/d'\n                  :shell:\n\n            3. Install the optional dependencies::\n\n                $ sudo apt install -y ffmpeg\n                $ ${CSW_PYTHON} -m pip install ffmpeg-python\n\n            4. Clone the Crazyswarm git repository::\n\n                $ git clone https://github.com/USC-ACTLab/crazyswarm.git\n\n            5. Run the build script::\n\n                $ cd crazyswarm\n                $ ./buildSimOnly.sh\n\n            6. Verify the installation by running the unit tests::\n\n                $ cd ros_ws/src/crazyswarm/scripts\n                $ $CSW_PYTHON -m pytest\n\n\n   .. tab:: Physical Robots and Simulation\n\n      For real hardware operation, ensure that your platform matches\n      one of the configurations in the table above.\n      **Avoid using a virtual machine** if possible:\n      they add additional latency and might cause issues with the visualization tools.\n\n      1. If needed, install ROS using the instructions at http://wiki.ros.org/ROS/Installation.\n\n      2. Set the ``$CSW_PYTHON`` environment variable::\n\n          $ export CSW_PYTHON=[python2 or python3]\n\n      3. Install the dependencies\n\n         .. program-output:: python3 generate_install_deps_code.py ../.github/workflows/ci-ros.yml\n            :shell:\n\n      4. Install the optional dependencies::\n\n          $ sudo apt install -y ffmpeg\n          $ ${CSW_PYTHON} -m pip install ffmpeg-python\n\n      5. Clone the Crazyswarm git repository::\n\n          $ git clone https://github.com/USC-ACTLab/crazyswarm.git\n\n      6. Run the build script::\n\n          $ cd crazyswarm\n          $ ./build.sh\n\n      7. Verify the installation by running the unit tests::\n\n          $ cd ros_ws/src/crazyswarm/scripts\n          $ source ../../../devel/setup.bash\n          $ $CSW_PYTHON -m pytest\n\n\nOnce you have completed installation,\nmove on to the :ref:`configuration` section and configure Crazyswarm for your hardware.\n"
  },
  {
    "path": "docs/internals.rst",
    "content": "Crazyswarm Internals\n====================\n\nThis page contains information for developers interested in modifying the Crazyswarm platform.\nDevelopers interested in using Crazyswarm as a library/framework should refer to :ref:`api` instead.\n\nThe tutorial :ref:`tutorial_streaming_setpoint` contains a significant amount of design motivation and internal details.\nIt is worth reading even if you are not working on streaming setpoints.\n\nFirmware bindings\n-----------------\nSelected modules from the Crazyflie firmware are exposed to ``pycrazyswarm`` scripts as a Python module via bindings.\nThe bindings are automatically generated from the C header files using \n`SWIG <http://www.swig.org/>`_.\nThey are used extensively in\n`crazyflieSim.py <https://github.com/USC-ACTLab/crazyswarm/blob/master/ros_ws/src/crazyswarm/scripts/pycrazyswarm/crazyflieSim.py>`_\nto mimic the behavior of a real Crazyflie in simulation mode.\n\nDebugging firmware modules via bindings\n~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~\n\n.. highlight:: none\n\nThe bindings are useful for testing and implementing new Crazyflie firmware modules.\nIf the core functionality of the module is written without any dependencies on ARM or FreeRTOS,\nit can be compiled for x86 and tested/debugged on a PC.\n\nLinux / GDB\n^^^^^^^^^^^\nOn Linux, bindings are compiled with GCC, so the preferred debugger is GDB.\nTo invoke a Python script with arguments, use the ``--args`` flag.\nIf your script is a unit test, GDB does not recognize the ``pytest`` command, so use::\n\n    gdb --args python -m pytest test_highLevel.py\n\nAfter GDB starts, you can place a breakpoint inside a firmware C file::\n\n    (gdb) b planner.c:plan_takeoff\n\nAlthough the symbol is not loaded yet, GDB is able to resolve the breakpoint later\nwhen the Python module is imported. Enter ``y`` at  the prompt::\n\n    No source file named planner.c.\n    Make breakpoint pending on future shared library load? (y or [n]) y\n    Breakpoint 1 (planner.c:plan_takeoff) pending.\n\nThen, when we type the ``run`` command, the Python interpreter runs for a while and hits our breakpoint::\n\n    (gdb) run\n    ...\n    Breakpoint 1, plan_takeoff (p=p@entry=0x555557522cd0, ...)\n    at ../../../../../../crazyflie-firmware/src/modules/src/planner.c:135\n\nThe first time you run GDB, it's useful to enter the command::\n\n    (gdb) set history save on\n\nThis will save your commands into a file ``.gdb_history`` in the working directory.\nNext time you run GDB, the commands from the previous run will still be available\nusing the \"up\" arrow key.\n\nMacOS / LLDB\n^^^^^^^^^^^^\nOn MacOS, bindings are compiled with Clang, so LLDB is the preferred debugger.\nLLDB is not a drop-in replacement for GDB; the commands are different.\n\nTo invoke a Python script with arguments, use ``--``::\n\n    lldb -- python -m pytest test_highLevel.py\n\nAfter LLDB starts, the equivalent syntax to place a breakpoint in a firmware C file is::\n\n    (lldb) br set -f planner.c -n plan_takeoff\n\nLLDB will automatically set up the pending breakpoint and resolve it upon library loading.\nUnlike GDB, it will not ask for your confirmation.\nWhen we type the ``run`` command, the Python interpreter runs for a while and hits our breakpoint::\n\n    (lldb) run\n    ...\n    * thread #1, queue = 'com.apple.main-thread', stop reason = breakpoint 1.1\n        frame #0: 0x000000010f554d10 _cffirmware.so`plan_takeoff(p=0x0000000100780bd0, ...)\n        at planner.c:136:15 [opt]\n\nLLDB automatically preserves command history between runs without any command.\n"
  },
  {
    "path": "docs/requirements.txt",
    "content": "numpy\npyyaml\nsphinx\nsphinx-argparse\nsphinx-rtd-theme\nsphinx-tabs\nsphinxcontrib-programoutput\n"
  },
  {
    "path": "docs/tutorials/hover.rstinclude",
    "content": ".. _tutorial_hover:\n\nHovering (hello, world)\n------------------------\n\nAfter completing :ref:`Installation` and :ref:`Configuration`,\nyou are ready to test your setup for the first time!\n\nFirst, run the test script in simulation mode to make sure your Python interpreter is set up correctly::\n\n    python hello_world.py --sim\n\nIn the 3D visualization, you should see a Crazyflie take off, hover for a few seconds, and then land.\n\nIf the script runs in simulation, you can move on to real hardware.\nFirst, start the ``crazyswarm_server``::\n\n    source ros_ws/devel/setup.bash\n    roslaunch crazyswarm hover_swarm.launch\n\nIt should only take a few seconds to connect to the CFs.\nIf you have the LED ring extension installed, you can see the connectivity by the color (green=good connectivity; red=bad connectivity).\nFurthermore, ``rviz`` will show the estimated pose of all CFs.\nIf there is an error, such as a faulty configuration or a turned-off Crazyflie, an error message will be shown and the application exits.\nIf there is a problem in the communication between the motion capture system and the Crazyswarm server, the application will not exit but the positions of the Crazyflies will not appear in rviz.\n\nIf ``crazyswarm_server`` is running correctly and you see CF pose(s) in ``rviz``,\nopen a new terminal (remember to ``source devel/setup.bash``) and run the test script::\n\n    python hello_world.py\n\nYou should see the same behavior in real life.\nIf you have more than one Crazyflie in your ``crazyflies.yaml``,\nthe script will select one arbitrarily.\n"
  },
  {
    "path": "docs/tutorials/tutorials.rst",
    "content": "Tutorials\n=========\n\n.. include:: hover.rstinclude\n"
  },
  {
    "path": "docs2/.gitignore",
    "content": "_build\n"
  },
  {
    "path": "docs2/Makefile",
    "content": "# Makefile for Sphinx documentation\n#\n\n# You can set these variables from the command line.\nSPHINXOPTS    = -W\nSPHINXBUILD   = sphinx-build\nPAPER         =\nBUILDDIR      = _build\n\n# Internal variables.\nPAPEROPT_a4     = -D latex_paper_size=a4\nPAPEROPT_letter = -D latex_paper_size=letter\nALLSPHINXOPTS   = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n# the i18n builder cannot share the environment and doctrees with the others\nI18NSPHINXOPTS  = $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n\n.PHONY: help\nhelp:\n\t@echo \"Please use \\`make <target>' where <target> is one of\"\n\t@echo \"  html       to make standalone HTML files\"\n\t@echo \"  dirhtml    to make HTML files named index.html in directories\"\n\t@echo \"  singlehtml to make a single large HTML file\"\n\t@echo \"  pickle     to make pickle files\"\n\t@echo \"  json       to make JSON files\"\n\t@echo \"  htmlhelp   to make HTML files and a HTML help project\"\n\t@echo \"  qthelp     to make HTML files and a qthelp project\"\n\t@echo \"  applehelp  to make an Apple Help Book\"\n\t@echo \"  devhelp    to make HTML files and a Devhelp project\"\n\t@echo \"  epub       to make an epub\"\n\t@echo \"  epub3      to make an epub3\"\n\t@echo \"  latex      to make LaTeX files, you can set PAPER=a4 or PAPER=letter\"\n\t@echo \"  latexpdf   to make LaTeX files and run them through pdflatex\"\n\t@echo \"  latexpdfja to make LaTeX files and run them through platex/dvipdfmx\"\n\t@echo \"  text       to make text files\"\n\t@echo \"  man        to make manual pages\"\n\t@echo \"  texinfo    to make Texinfo files\"\n\t@echo \"  info       to make Texinfo files and run them through makeinfo\"\n\t@echo \"  gettext    to make PO message catalogs\"\n\t@echo \"  changes    to make an overview of all changed/added/deprecated items\"\n\t@echo \"  xml        to make Docutils-native XML files\"\n\t@echo \"  pseudoxml  to make pseudoxml-XML files for display purposes\"\n\t@echo \"  linkcheck  to check all external links for integrity\"\n\t@echo \"  doctest    to run all doctests embedded in the documentation (if enabled)\"\n\t@echo \"  coverage   to run coverage check of the documentation (if enabled)\"\n\t@echo \"  dummy      to check syntax errors of document sources\"\n\n.PHONY: clean\nclean:\n\trm -rf $(BUILDDIR)/*\n\n.PHONY: html\nhtml:\n\t$(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/html.\"\n\n.PHONY: dirhtml\ndirhtml:\n\t$(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/dirhtml.\"\n\n.PHONY: singlehtml\nsinglehtml:\n\t$(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml\n\t@echo\n\t@echo \"Build finished. The HTML page is in $(BUILDDIR)/singlehtml.\"\n\n.PHONY: pickle\npickle:\n\t$(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle\n\t@echo\n\t@echo \"Build finished; now you can process the pickle files.\"\n\n.PHONY: json\njson:\n\t$(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json\n\t@echo\n\t@echo \"Build finished; now you can process the JSON files.\"\n\n.PHONY: htmlhelp\nhtmlhelp:\n\t$(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp\n\t@echo\n\t@echo \"Build finished; now you can run HTML Help Workshop with the\" \\\n\t      \".hhp project file in $(BUILDDIR)/htmlhelp.\"\n\n.PHONY: qthelp\nqthelp:\n\t$(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp\n\t@echo\n\t@echo \"Build finished; now you can run \"qcollectiongenerator\" with the\" \\\n\t      \".qhcp project file in $(BUILDDIR)/qthelp, like this:\"\n\t@echo \"# qcollectiongenerator $(BUILDDIR)/qthelp/Crazyswarm.qhcp\"\n\t@echo \"To view the help file:\"\n\t@echo \"# assistant -collectionFile $(BUILDDIR)/qthelp/Crazyswarm.qhc\"\n\n.PHONY: applehelp\napplehelp:\n\t$(SPHINXBUILD) -b applehelp $(ALLSPHINXOPTS) $(BUILDDIR)/applehelp\n\t@echo\n\t@echo \"Build finished. The help book is in $(BUILDDIR)/applehelp.\"\n\t@echo \"N.B. You won't be able to view it unless you put it in\" \\\n\t      \"~/Library/Documentation/Help or install it in your application\" \\\n\t      \"bundle.\"\n\n.PHONY: devhelp\ndevhelp:\n\t$(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp\n\t@echo\n\t@echo \"Build finished.\"\n\t@echo \"To view the help file:\"\n\t@echo \"# mkdir -p $$HOME/.local/share/devhelp/Crazyswarm\"\n\t@echo \"# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/Crazyswarm\"\n\t@echo \"# devhelp\"\n\n.PHONY: epub\nepub:\n\t$(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub\n\t@echo\n\t@echo \"Build finished. The epub file is in $(BUILDDIR)/epub.\"\n\n.PHONY: epub3\nepub3:\n\t$(SPHINXBUILD) -b epub3 $(ALLSPHINXOPTS) $(BUILDDIR)/epub3\n\t@echo\n\t@echo \"Build finished. The epub3 file is in $(BUILDDIR)/epub3.\"\n\n.PHONY: latex\nlatex:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo\n\t@echo \"Build finished; the LaTeX files are in $(BUILDDIR)/latex.\"\n\t@echo \"Run \\`make' in that directory to run these through (pdf)latex\" \\\n\t      \"(use \\`make latexpdf' here to do that automatically).\"\n\n.PHONY: latexpdf\nlatexpdf:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through pdflatex...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: latexpdfja\nlatexpdfja:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through platex and dvipdfmx...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf-ja\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: text\ntext:\n\t$(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text\n\t@echo\n\t@echo \"Build finished. The text files are in $(BUILDDIR)/text.\"\n\n.PHONY: man\nman:\n\t$(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man\n\t@echo\n\t@echo \"Build finished. The manual pages are in $(BUILDDIR)/man.\"\n\n.PHONY: texinfo\ntexinfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo\n\t@echo \"Build finished. The Texinfo files are in $(BUILDDIR)/texinfo.\"\n\t@echo \"Run \\`make' in that directory to run these through makeinfo\" \\\n\t      \"(use \\`make info' here to do that automatically).\"\n\n.PHONY: info\ninfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo \"Running Texinfo files through makeinfo...\"\n\tmake -C $(BUILDDIR)/texinfo info\n\t@echo \"makeinfo finished; the Info files are in $(BUILDDIR)/texinfo.\"\n\n.PHONY: gettext\ngettext:\n\t$(SPHINXBUILD) -b gettext $(I18NSPHINXOPTS) $(BUILDDIR)/locale\n\t@echo\n\t@echo \"Build finished. The message catalogs are in $(BUILDDIR)/locale.\"\n\n.PHONY: changes\nchanges:\n\t$(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes\n\t@echo\n\t@echo \"The overview file is in $(BUILDDIR)/changes.\"\n\n.PHONY: linkcheck\nlinkcheck:\n\t$(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck\n\t@echo\n\t@echo \"Link check complete; look for any errors in the above output \" \\\n\t      \"or in $(BUILDDIR)/linkcheck/output.txt.\"\n\n.PHONY: doctest\ndoctest:\n\t$(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest\n\t@echo \"Testing of doctests in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/doctest/output.txt.\"\n\n.PHONY: coverage\ncoverage:\n\t$(SPHINXBUILD) -b coverage $(ALLSPHINXOPTS) $(BUILDDIR)/coverage\n\t@echo \"Testing of coverage in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/coverage/python.txt.\"\n\n.PHONY: xml\nxml:\n\t$(SPHINXBUILD) -b xml $(ALLSPHINXOPTS) $(BUILDDIR)/xml\n\t@echo\n\t@echo \"Build finished. The XML files are in $(BUILDDIR)/xml.\"\n\n.PHONY: pseudoxml\npseudoxml:\n\t$(SPHINXBUILD) -b pseudoxml $(ALLSPHINXOPTS) $(BUILDDIR)/pseudoxml\n\t@echo\n\t@echo \"Build finished. The pseudo-XML files are in $(BUILDDIR)/pseudoxml.\"\n\n.PHONY: dummy\ndummy:\n\t$(SPHINXBUILD) -b dummy $(ALLSPHINXOPTS) $(BUILDDIR)/dummy\n\t@echo\n\t@echo \"Build finished. Dummy builder generates no files.\"\n"
  },
  {
    "path": "docs2/conf.py",
    "content": "#!/usr/bin/env python3\n# -*- coding: utf-8 -*-\n#\n# Crazyswarm documentation build configuration file, created by\n# sphinx-quickstart on Tue Apr 18 20:00:33 2017.\n#\n# This file is execfile()d with the current directory set to its\n# containing dir.\n#\n# Note that not all possible configuration values are present in this\n# autogenerated file.\n#\n# All configuration values have a default; values that are commented out\n# serve to show the default.\n\n# If extensions (or modules to document with autodoc) are in another directory,\n# add these directories to sys.path here. If the directory is relative to the\n# documentation root, use os.path.abspath to make it absolute, like shown here.\n#\n# import os\n# import sys\n# sys.path.insert(0, os.path.abspath('..'))\n# sys.path.insert(0, os.path.abspath('../ros_ws/src/crazyswarm/scripts'))\n\nimport sphinx_rtd_theme\n\n# -- General configuration ------------------------------------------------\n\n# If your documentation needs a minimal Sphinx version, state it here.\n#\nneeds_sphinx = '1.4'\n\n# Add any Sphinx extension module names here, as strings. They can be\n# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom\n# ones.\nextensions = [\n    'sphinx.ext.autodoc',\n    'sphinx.ext.imgmath',\n    'sphinx.ext.mathjax',\n    'sphinx.ext.napoleon',\n    'sphinxarg.ext',\n    'sphinx_design',\n    'sphinxcontrib.programoutput',\n    'sphinx_rtd_theme',\n]\n\n# Add any paths that contain templates here, relative to this directory.\ntemplates_path = ['_templates']\n\n# The suffix(es) of source filenames.\n# You can specify multiple suffix as a list of string:\n#\n# source_suffix = ['.rst', '.md']\nsource_suffix = '.rst'\n\n# The encoding of source files.\n#\n# source_encoding = 'utf-8-sig'\n\n# The master toctree document.\nmaster_doc = 'index'\n\n# General information about the project.\nproject = 'Crazyswarm2'\ncopyright = '2021-2025, Wolfgang Hönig (TU Berlin), Kimberly N. McGuire (Independent), and contributors'\nauthor = 'Wolfgang Hönig, Kimberly N. McGuire'\n\n# The version info for the project you're documenting, acts as replacement for\n# |version| and |release|, also used in various other places throughout the\n# built documents.\n#\n# The short X.Y version.\nversion = '1.0'\n# The full version, including alpha/beta/rc tags.\nrelease = '1.0a1'\n\n# The language for content autogenerated by Sphinx. Refer to documentation\n# for a list of supported languages.\n#\n# This is also used if you do content translation via gettext catalogs.\n# Usually you set \"language\" from the command line for these cases.\nlanguage = 'en'\n\n# There are two options for replacing |today|: either, you set today to some\n# non-false value, then it is used:\n#\n# today = ''\n#\n# Else, today_fmt is used as the format for a strftime call.\n#\n# today_fmt = '%B %d, %Y'\n\n# List of patterns, relative to source directory, that match files and\n# directories to ignore when looking for source files.\n# This patterns also effect to html_static_path and html_extra_path\nexclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']\n\n# The reST default role (used for this markup: `text`) to use for all\n# documents.\n#\n# default_role = None\n\n# If true, '()' will be appended to :func: etc. cross-reference text.\n#\n# add_function_parentheses = True\n\n# If true, the current module name will be prepended to all description\n# unit titles (such as .. function::).\n#\n# add_module_names = True\n\n# If true, sectionauthor and moduleauthor directives will be shown in the\n# output. They are ignored by default.\n#\n# show_authors = False\n\n# The name of the Pygments (syntax highlighting) style to use.\npygments_style = 'sphinx'\n\n# A list of ignored prefixes for module index sorting.\n# modindex_common_prefix = []\n\n# If true, keep warnings as \"system message\" paragraphs in the built documents.\n# keep_warnings = False\n\n# If true, `todo` and `todoList` produce output, else they produce nothing.\ntodo_include_todos = False\n\n\n# -- Options for HTML output ----------------------------------------------\n\n# The theme to use for HTML and HTML Help pages.  See the documentation for\n# a list of builtin themes.\n#\nhtml_theme = 'sphinx_rtd_theme'\n\n# Theme options are theme-specific and customize the look and feel of a theme\n# further.  For a list of options available for each theme, see the\n# documentation.\n#\n# html_theme_options = {}\n\n# Add any paths that contain custom themes here, relative to this directory.\n# html_theme_path = []\n\n# The name for this set of Sphinx documents.\n# \"<project> v<release> documentation\" by default.\n#\n# html_title = 'Crazyswarm v0.1'\n\n# A shorter title for the navigation bar.  Default is the same as html_title.\n#\n# html_short_title = None\n\n# The name of an image file (relative to this directory) to place at the top\n# of the sidebar.\n#\n# html_logo = None\n\n# The name of an image file (relative to this directory) to use as a favicon of\n# the docs.  This file should be a Windows icon file (.ico) being 16x16 or 32x32\n# pixels large.\n#\n# html_favicon = None\n\n# Add any paths that contain custom static files (such as style sheets) here,\n# relative to this directory. They are copied after the builtin static files,\n# so a file named \"default.css\" will overwrite the builtin \"default.css\".\n# html_static_path = ['_static']\n\n# Add any extra paths that contain custom files (such as robots.txt or\n# .htaccess) here, relative to this directory. These files are copied\n# directly to the root of the documentation.\n#\n# html_extra_path = []\n\n# If not None, a 'Last updated on:' timestamp is inserted at every page\n# bottom, using the given strftime format.\n# The empty string is equivalent to '%b %d, %Y'.\n#\n# html_last_updated_fmt = None\n\n# If true, SmartyPants will be used to convert quotes and dashes to\n# typographically correct entities.\n#\n# html_use_smartypants = True\n\n# Custom sidebar templates, maps document names to template names.\n#\n# html_sidebars = {}\n\n# Additional templates that should be rendered to pages, maps page names to\n# template names.\n#\n# html_additional_pages = {}\n\n# If false, no module index is generated.\n#\n# html_domain_indices = True\n\n# If false, no index is generated.\n#\n# html_use_index = True\n\n# If true, the index is split into individual pages for each letter.\n#\n# html_split_index = False\n\n# If true, links to the reST sources are added to the pages.\n#\n# html_show_sourcelink = True\n\n# If true, \"Created using Sphinx\" is shown in the HTML footer. Default is True.\n#\n# html_show_sphinx = True\n\n# If true, \"(C) Copyright ...\" is shown in the HTML footer. Default is True.\n#\n# html_show_copyright = True\n\n# If true, an OpenSearch description file will be output, and all pages will\n# contain a <link> tag referring to it.  The value of this option must be the\n# base URL from which the finished HTML is served.\n#\n# html_use_opensearch = ''\n\n# This is the file name suffix for HTML files (e.g. \".xhtml\").\n# html_file_suffix = None\n\n# Language to be used for generating the HTML full-text search index.\n# Sphinx supports the following languages:\n#   'da', 'de', 'en', 'es', 'fi', 'fr', 'h', 'it', 'ja'\n#   'nl', 'no', 'pt', 'ro', 'r', 'sv', 'tr', 'zh'\n#\n# html_search_language = 'en'\n\n# A dictionary with options for the search language support, empty by default.\n# 'ja' uses this config value.\n# 'zh' user can custom change `jieba` dictionary path.\n#\n# html_search_options = {'type': 'default'}\n\n# The name of a javascript file (relative to the configuration directory) that\n# implements a search results scorer. If empty, the default will be used.\n#\n# html_search_scorer = 'scorer.js'\n\n# Output file base name for HTML help builder.\nhtmlhelp_basename = 'Crazyswarmdoc'\n\n# -- Options for Autodoc -------------------------------------------------\n\n# List class members in the order they appear in the file,\n# instead of alphabetically.\nautodoc_member_order = 'bysource'\n\n# Do not try to import ROS modules so we can build on more machines easily.\nautodoc_mock_imports = [\n    'crazyswarm',\n    'numpy',\n    'rospy',\n    'std_msgs',\n    'std_srvs',\n    'tf',\n    'tf_conversions',\n]\n"
  },
  {
    "path": "docs2/faq.rst",
    "content": ".. _faq:\n\nFrequently Asked Questions\n==========================\n\nHow can I get help?\n-------------------\n\nPlease start a `discussion <https://github.com/IMRCLab/crazyswarm2/discussions>`_ for\n\n- Getting Crazyswarm2 to work with your hardware setup.\n- Advice on how to use it to achieve your goals.\n- Rough ideas for a new feature.\n\n\nHow can I report an issue?\n--------------------------\n\nIf you strongly believe that you found a bug that requires changes in the code, feel free to open an `issue <https://github.com/IMRCLab/crazyswarm2/issues>`_.\nProvide as much details as possible to reproduce the problem, your observation, as well as the desired outcome.\n\nIf you are not sure if a code change is required, please start a `discussion <https://github.com/IMRCLab/crazyswarm2/discussions>`_ first.\n\n\nHow do Crazyswarm2 and Crazyswarm differ?\n-----------------------------------------\n\nCrazyswarm2 was forked from Crazyswarm. However, there is also heavy re-design of core design choices.\n\n- **Motion capture integration.**\n  In Crazyswarm1, the motion capture integration is part of the crazyswarm_server, due to limitations in the ROS1 pub/sub system.\n  In contrast, Crazyswarm2 now follows a better ROS-style design, where our motion capture abstraction layer and custom\n  frame-by-frame tracking is available as a `separate ROS 2 package <https://github.com/IMRCLab/motion_capture_tracking>`_.\n  In addition, Crazyswarm2 is designed to support other localization methods (lighthouse, or on-board only localization) from the start.\n\n- **Communication backend.**\n  In Crazyswarm2, we rely on `crazyflie-link-cpp <https://github.com/bitcraze/crazyflie-link-cpp>`_ at the lowest layer, unlike a custom link implementation in Crazyswarm1.\n  This new link uses priority queues that allows new features like uploading trajectories during the flight. Moreover, the new link should improve the overall (communication) robustness.\n  There is also experimental support for a `crazyflie-lib-python <https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/>`_ backend as well. \n\n- **Support for Common UAV tasks.**\n  Crazyswarm1 was designed to operate a swarm and did not include common features for single-robot operation, such as teleoperation. Crazyswarm2 replaces both Crazyswarm1 and crazyflie_ros, thus supporting arbitrary URIs, teleoperation etc.\n\n- **Simulation.**\n  In Crazyswarm1, a simple visualization of the setpoints for high-level Python scripts is supported. There is no support for simulation of ROS code that does not use the high-level Python scripts and no support for physics-based simulation.\n  In contrast, Crazyswarm2 implements the simulation as an alternative backend. This will support multiple physics/visualization backends (optionally with physics and aerodynamic interaction).\n\n- **Support of Distributed Swarm Monitoring.**\n  In Crazyswarm1, a common swarm monitoring tool is the chooser.py (to enable/disable CFs, check the battery voltage etc.). However, this tool was not functioning while the swarm is operational.\n  In contrast, Crazyswarm2 allows common swarm monitoring tasks without restarting ROS nodes or launching additional tools.\n\n\nHow is Crazyswarm2 different from Bitcraze's cflib?\n---------------------------------------------------\n\nBoth can be used to control several Crazyflies from a Python script.\nHere are some differences:\n\n- **Motion capture integration.**\n  Crazyswarm2 supports common motion capture systems using the ROS 2 package `motion_capture_tracking <https://github.com/IMRCLab/motion_capture_tracking/tree/ROS 2>`_.\n  The Bitcraze API can *send* position measurements to the Crazyflie,\n  but does not know how to *get* position measurements from mocap hardware.\n  Moreover, the use of motion_capture_tracking allows to use identical or single motion capture markers.\n- **Broadcasts.**\n  Crazyswarm2 uses broadcast communication whenever possible to require fewer radios per Crazyflie. In contrast, the official SDK uses unicast communication instead.\n- **Simulation.**\n  Crazyswarm2 has a simulation mode with 3D graphics,\n  which makes it easy to validate complex scripts before running them on real hardware.\n- **Python firmware bindings.**\n  Crazyswarm2's simulator is built upon automatically generated Python bindings\n  for certain modules in the Crazyflie firmware.\n  The binding system can be helpful when developing new firmware modules,\n  especially when they are mathematically complex and hard to debug.\n- **ROS 2 foundation.**\n  The Crazyswarm2 server program is a ROS 2 node.\n  Our Python API is a thin wrapper around the ROS 2 interface."
  },
  {
    "path": "docs2/howto.rst",
    "content": ".. _howtos:\n\nHow To\n======\n\nThis page shows short how to's for the advanced usage.\n\n\nTracking Non-Robotic Objects\n----------------------------\n\nIn some cases it can be useful to provide the position or pose of rigid bodies in the motion capture space to the robots.\nFor example, consider a collision avoidance algorithms implemented on-board the firmware that requires to know\nthe position of an obstacle. In that case, a \"virtual\" robot can be defined in crazyflies.yaml\n\n.. code-block:: yaml\n\n    robots:\n        obstacle:\n            enabled: true\n            initial_position: [0, -0.5, 0]\n            type: marker  # see robot_types\n            id: 255\n\n    robot_types:\n        # Just a marker to track, not a robot to connect to\n        marker:\n            connection: none\n            motion_capture:\n                enabled: true\n                marker: default_single_marker\n                dynamics: default\n\n\nHere, the position of the obstacle will be tracked using the motion_capture_tracking ROS package. The resulting pose will be\navailable via TF (named \"obstacle\") and send to the firmware of the actual robots with id 255.\n\nDebugging\n---------\n\nIf there is a crash (e.g., segmentation fault) in the crazyflie_server (C++ backend), you can find the stacktrace by using gdb.\nFirst, compile your code in debug mode, then run the launch file with the debug flag, which will open an xterm window.\nIf you don't have xterm installed, you can do so using `sudo apt install xterm`.\n\n.. code-block:: bash\n\n    colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Debug\n    ros2 launch crazyflie launch.py debug:=True\n\nUsage from the command line\n---------------------------\n\nThe following shows a simple take off and land example\n\n.. code-block:: bash\n\n    [terminal1]$ ros2 run crazyflie reboot --uri radio://0/80/2M/E7E7E7E706 --mode sysoff\n    [terminal2]$ ros2 launch crazyflie launch.py\n    [terminal1]$ ros2 param set crazyflie_server cf1.params.commander.enHighLevel 1\n    [terminal1]$ ros2 param set crazyflie_server cf1.params.stabilizer.estimator 2\n    [terminal1]$ ros2 service call cf1/takeoff crazyflie_interfaces/srv/Takeoff \"{height: 0.5, duration: {sec: 2}}\"\n    [terminal1]$ ros2 service call cf1/land crazyflie_interfaces/srv/Land \"{height: 0.0, duration: {sec: 2}}\"\n\nEnabling Logblocks at runtime\n-----------------------------\n\n.. warning::\n    Runtime logblock enabling is currently only supported in the CFLIB backend of the server.\n\nIn the usage we explained how to enable log blocks at startup, but what if you would like to enable or disable logging blocks in runtime?\nThis section will show how to do that by using services\n\nIn one terminal run\n\n.. code-block:: bash\n\n    ros2 launch crazyflie launch.py backend:=cflib\n\nIn another terminal after sourcing the right setup.bash files, run:\n\n.. code-block:: bash\n\n    ros2 service call /cf2/add_logging crazyflie_interfaces/srv/AddLogging \"{topic_name: 'topic_test', frequency: 10, vars: ['stateEstimate.x','stateEstimate.y','stateEstimate.z']}\"\n    ros2 service call /cf2/add_logging crazyflie_interfaces/srv/AddLogging \"{topic_name: 'pose', frequency: 10}\"\n\nWith ROS 2's rqt you can look at the topics, or with 'ROS 2 topics echo /cf2/pose'\n\nTo close the logblocks again, run:\n\n.. code-block:: bash\n\n    ros2 service call /cf2/remove_logging crazyflie_interfaces/srv/RemoveLogging \"{topic_name: 'topic_test'}\"\n    ros2 service call /cf2/remove_logging crazyflie_interfaces/srv/RemoveLogging \"{topic_name: 'pose'}\"\n\nRun Tests Locally\n-----------------\n\nThis requires some updated pip packages for testing, see https://docs.ros.org/en/humble/Installation/Alternatives/Ubuntu-Development-Setup.html, otherwise the reported failures will be inconsistent with CI.\n\nThen execute:\n\n.. code-block:: bash\n\n    colcon test --event-handlers=console_cohesion+ --return-code-on-test-failure --packages-select crazyflie_py\n\n.. _Collision Avoidance:\n\nCollision Avoidance\n-------------------\n\nThe official firmware has support for collision avoidance using the Buffered Voronoi Cell algorithm.\nIt requires the use of a motion capture system (so that the positions of other drones are known) and can be enabled\nin the `crazyflies.yaml`:\n\n.. code-block:: yaml\n\n    all:\n        firmware_params:\n            colAv:\n                enable: 1\n\nor inside a Python script via:\n\n.. code-block:: python\n\n    swarm = Crazyswarm()\n    allcfs = swarm.allcfs\n    allcfs.setParam(\"colAv.enable\", 1)\n\nNote that the algorithm might require tuning of its hyperparameters. Documention can be found at https://github.com/bitcraze/crazyflie-firmware/blob/dbb9df1137f11d4e7e3771c56d25a7137b5b69cc/src/modules/src/collision_avoidance.c#L348-L428.\n\nGenerate Trajectories\n---------------------\n\nCrazyswarm2 supports polynomial trajectories (8th order). These can be generated from waypoints, waypoint/time pairs, or optimization. Useful tools are available at https://github.com/whoenig/uav_trajectories, including scripts to visualize the resulting trajectories.\n\nFor the multi-robot case, there is no easy to-use library, yet. One can use collision avoidance (see :ref:`Collision Avoidance`) or preplan trajectories using https://github.com/IMRCLab/db-CBS or https://github.com/mjdebord/smoothener/tree/cylinders. \n"
  },
  {
    "path": "docs2/index.rst",
    "content": ".. _introduction:\n\nCrazyswarm2: A ROS 2 testbed for Aerial Robot Teams\n===================================================\n\nCrazyswarm2 is a ROS 2 stack to use aerial robots that use flight computers from Bitcraze AB, including the Crazyflie 2.1(+), Crazyflie 2.1 Brushless, Flapper Nimble+, and custom drones built using Crazyflie Bolt.\n\nOn the technical side Crazyswarm2 is a port of the original `Crazyswarm <https://crazyswarm.readthedocs.io>`_ to ROS 2.\nIt is fully open-source (MIT) and available on `github <https://github.com/IMRCLab/crazyswarm2>`_.\n\nA good starting point is the `Aerial Swarm Tools and Applications Tutorial/Workshop <https://imrclab.github.io/workshop-aerial-swarms-rss2024/>`_. If you use our work in academic research, please cite the original paper (we are actively working on a dedicated publication for Crazyswarm2):\n\n.. code-block:: none\n\n    @inproceedings{crazyswarm,\n      author    = {James A. Preiss* and\n                   Wolfgang  H\\\"onig* and\n                   Gaurav S. Sukhatme and\n                   Nora Ayanian},\n      title     = {Crazyswarm: {A} large nano-quadcopter swarm},\n      booktitle = {{IEEE} International Conference on Robotics and Automation ({ICRA})},\n      pages     = {3299--3304},\n      publisher = {{IEEE}},\n      year      = {2017},\n      url       = {https://doi.org/10.1109/ICRA.2017.7989376},\n      doi       = {10.1109/ICRA.2017.7989376},\n      note      = {Software available at \\url{https://github.com/USC-ACTLab/crazyswarm}},\n    }\n\nRelated Packages:\n  - `Aerostack2 <https://aerostack2.github.io/>`_\n  - `CrazyChoir <https://github.com/OPT4SMART/crazychoir>`_\n  - `Skybrush <https://skybrush.io/>`_\n  - `Dynamic Swarms Crazyflies <https://dynamicswarms.github.io/ds-crazyflies/>`_\n\n.. warning::\n  Crazyswarm2 is being actively used and developed. There are currently the following major limitations:\n  \n  - Sometimes unicast packets get lost, which is a `known firmware bug <https://github.com/bitcraze/crazyflie-firmware/issues/703>`_.\n\n\nContents\n--------\n\n.. toctree::\n   installation\n   overview\n   usage\n   tutorials\n   howto\n   faq\n   :maxdepth: 1\n\n\n.. Indices and tables\n.. ------------------\n\n.. * :ref:`genindex`\n.. * :ref:`modindex`\n.. * :ref:`search`\n\n"
  },
  {
    "path": "docs2/installation.rst",
    "content": ".. _installation:\n\nInstallation\n============\n\nCrazyswarm2 runs on **Ubuntu Linux** in one of the following configurations:\n\n====== ======== ====== \nUbuntu Python   ROS 2\n------ -------- ------\n22.04  3.10     Humble\n------ -------- ------\n24.04  3.12     Jazzy\n====== ======== ======\n\n.. warning::\n   The `Windows Subsystem for Linux (WSL) <https://docs.microsoft.com/en-us/windows/wsl/about>`_ is experimentally supported but you'll have to use `usbipd-win <https://github.com/dorssel/usbipd-win/>`_.\n   This program will link the crazyradio directly with WS, but beware of bugs. Check out their `WSL connect guide <https://github.com/dorssel/usbipd-win/wiki/WSL-support/>`_.\n\n.. warning::\n   Avoid using a virtual machine if possible: they add additional latency and might cause issues with the visualization tools.\n\nFirst Installation\n------------------\n\n1. If needed, install ROS 2 using the instructions at https://docs.ros.org/en/jazzy/Installation.html.\n\n2. Install dependencies\n\n    .. tab-set::\n\n        .. tab-item:: Binary Installation\n            :sync: bin\n\n            .. code-block:: bash\n\n                pip3 install rowan nicegui==1.4.2\n\n        .. tab-item:: Source Installation\n            :sync: src\n\n            .. code-block:: bash\n\n                sudo apt install libboost-program-options-dev libusb-1.0-0-dev\n                pip3 install rowan nicegui==1.4.2\n\n   Then install the motion capture ROS 2 package (replace <DISTRO> with your version of ROS, namely humble or jazzy):\n\n    .. code-block:: bash\n\n        sudo apt-get install ros-<DISTRO>-motion-capture-tracking \n\n    If you are planning to use the CFlib backend, do:\n\n    .. code-block:: bash\n        \n        pip3 install cflib transforms3d\n        sudo apt-get install ros-<DISTRO>-tf-transformations\n\n3. Set up your ROS 2 workspace\n\n    .. tab-set::\n\n        .. tab-item:: Binary Installation\n            :sync: bin\n\n            Then install the crazyswarm2 stack (replace <DISTRO> with your version of ROS, namely humble or jazzy):\n\n            .. code-block:: bash\n\n                sudo apt-get install ros-<DISTRO>-crazyflie*\n\n            To prepare your workspace, see \"Custom ROS Package\" section below.\n\n        .. tab-item:: Source Installation\n            :sync: src\n\n            Clone the Crazyswarm2 repository\n\n            .. code-block:: bash\n\n                mkdir -p ros2_ws/src\n                cd ros2_ws/src\n                git clone https://github.com/IMRCLab/crazyswarm2 --recursive\n\n            Now build the ROS 2 workspace\n\n            .. code-block:: bash\n\n                cd ../\n                source /opt/ros/DISTRO/setup.bash\n                colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release\n         \n            .. note::\n                symlink-install allows you to edit Python and config files without running `colcon build` every time.\n         \n            .. note::\n                If you install it for the first time, you will see a lot of warnings at first. \n                As long as the build of the package finish, you can ignore this for now. \n       \n\n4. Set up Crazyradio\n\n   For the Crazyradio, you need to setup usb rules in order to communicate with the Crazyflie. Find the instructions for that here `in Bitcraze's USB permission guide for Linux <https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/installation/usb_permissions/>`_.\n\n   You will also need to update the Crazyradio firmware to the latest development branch to be able to use all features.\n   \n    - For Crazyradio PA (1), `follow these instructions <https://www.bitcraze.io/documentation/repository/crazyradio-firmware/master/building/building_flashing/>`_.\n    - For Crazyradio 2, follow `these instuctions to flash <https://www.bitcraze.io/documentation/repository/crazyradio2-firmware/main/building-and-flashing/flash//>`_ the `latest release <https://github.com/bitcraze/crazyradio2-firmware/releases>`_ (we tested version 5.1).\n\n5. Update the Crazyflies\n\n   If this is the first time handling Crazyflies it is always good to start with `Bitcraze's getting started guide  <https://www.bitcraze.io/documentation/tutorials/getting-started-with-crazyflie-2-x/>`_.\n\n   You can update each Crazyflie firmware to the latest release via `these instructions of the Bitcraze Crazyflie client <https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/userguides/userguide_client/#firmware-upgrade>`_ .\n\n   While you are at it, make sure that each Crazyflie have an unique radio address which you can change in `the client via these instructions <https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/userguides/userguide_client/#firmware-configuration>`_ .\n\n6. Set up software-in-the-loop simulation (optional)\n\n    This currently requires cloning the Crazyflie firmware of the latest tested release (2025.02) and building the Python bindings manually. In a separate folder (not part of your ROS 2 workspace!), \n\n    .. code-block:: bash\n\n        git clone --branch 2025.02 --single-branch --recursive https://github.com/bitcraze/crazyflie-firmware.git\n\n    First follow `the instructions to build the python bindings <https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/building-and-flashing/build/#build-python-bindings>`_ from the bitcraze website. Afterwards, make sure that the bindings can be found in the python path:\n\n    .. code-block:: bash\n\n        export PYTHONPATH=<replace-with-path-to>/crazyflie-firmware/build:$PYTHONPATH\n        \n    If you are working from an older version of the crazyflie-firmware (before tag 2023.02), then you will need to point to main folder of the repo by removing the '/build' part. \n\n\nUpdating\n--------\n\nYou can update your local copy using the following commands:\n\n    .. tab-set::\n\n        .. tab-item:: Binary Installation\n            :sync: bin\n\n            .. code-block:: bash\n\n                sudo apt update\n                sudo apt upgrade\n\n        .. tab-item:: Source Installation\n            :sync: src\n\n            .. code-block:: bash\n\n                cd ros2_ws/src/crazyswarm2\n                git pull\n                git submodule sync\n                git submodule update --init --recursive\n                cd ../../\n                source /opt/ros/DISTRO/setup.bash\n                colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release\n\n\nCustom ROS Package\n------------------\n\nIn order to use Crazyswarm, it is best practice to use a custom ROS package that contains all necessary config files as well as your user scripts / ROS nodes.\n\n1. Create a new package\n\n    .. code-block:: bash\n\n        mkdir -p ros2_ws/src\n        cd ros2_ws/src\n        ros2 pkg create --build-type ament_python --license MIT --node-name hello_world crazyflie_test\n\n2. Replace hello_world.py with https://github.com/IMRCLab/crazyswarm2/blob/main/crazyflie_examples/crazyflie_examples/hello_world.py\n\n3. Add `<depend>crazyflie_py</depend>` to package.xml\n\n4. Copy config files `crazyflies.yaml` and `motion_capture.yaml` from https://github.com/IMRCLab/crazyswarm2/tree/main/crazyflie/config into the config folder\n\n5. Add `launch/launch.py` with the following content\n\n    .. code-block:: python\n\n        import os\n\n        from ament_index_python.packages import get_package_share_directory\n        from launch import LaunchDescription\n        from launch.actions import IncludeLaunchDescription\n        from launch.launch_description_sources import PythonLaunchDescriptionSource\n\n        package_name = 'crazyflie_test'\n\n        def generate_launch_description():\n\n            crazyflies_yaml_path = os.path.join(\n                get_package_share_directory(package_name),\n                'config',\n                'crazyflies.yaml')\n            motion_capture_yaml_path = os.path.join(\n                get_package_share_directory(package_name),\n                'config',\n                'motion_capture.yaml')\n\n            return LaunchDescription(\n                [\n                    IncludeLaunchDescription(\n                        PythonLaunchDescriptionSource(\n                            [\n                                os.path.join(\n                                    get_package_share_directory('crazyflie'), 'launch'\n                                ),\n                                '/launch.py',\n                            ]\n                        ),\n                        launch_arguments={\n                            'crazyflies_yaml_file': crazyflies_yaml_path,\n                            'motion_capture_yaml_file': motion_capture_yaml_path,\n                        }.items(),\n                    ),\n                ]\n            )\n\n6. In `setup.py`, include the following lines as part of the `data_files` array:\n\n    .. code-block:: python\n\n        (os.path.join('share', package_name, 'launch'), glob('launch/*')),\n        (os.path.join('share', package_name, 'config'), glob('config/*'))\n\n\n"
  },
  {
    "path": "docs2/overview.rst",
    "content": ".. _overview:\n\nOverview\n========\n\nThis page will explain the overview of the crazyflie ROS 2 nodes:\n\n.. image:: images/architecture.png\n\n\nExplanation per package\n-----------------------\n\nIn the `source code of the Crazyswarm2 (Crazyflie ROS 2) project <https://github.com/IMRCLab/crazyswarm2>`_, there are several packages that we will explain here:\n\n\n- **crazyflie/**: The package that contains the crazyflie server nodes and the crazyflies.yaml.\n- **crazyflie_py/**: The package that contains the python library that wraps around the ROS 2 services and topics that connects with the crazyflie server nodes.\n- **crazyflie_examples/**:  The package that contains examples of using the crazyflie ROS 2 package. See :ref:`tutorials`.\n- **crazyflie_interfaces/**: The package that contains all msgs and srvs for the crazyflie ROS 2 project.\n- **crazyflie_sim/**: The package that contains our simulator.\n\nCrazyflie server\n----------------\n\nThe crazyflie server node connects multiple `Crazyflies <https://www.bitcraze.io/products/crazyflie-2-1/>`_ with on or more `Crazyradio PA dongles <https://www.bitcraze.io/products/crazyradio-pa/>`_.\n\nIt has three backends that you can choose from:\n\n- **cpp**: This is based on the `crazyflie-link-cpp <https://github.com/bitcraze/crazyflie-link-cpp>`_ on the lowest layer.\n- **cflib**: This is based on the `crazyflie-lib-python <https://www.bitcraze.io/documentation/repository/crazyflie-lib-python/master/>`_ up until the logging, parameter, and command sending handling.\n- **sim**: Our simulator behaves like a regular backend, offering ROS 2 topics and services, see below for more details on the simulation.\n\nIt handles several low level communication aspects with the Crazyflies:\n\n- **Parameter to ROS 2 parameters handling**: It receives the parameter ToC from the Crazyflie, transforms it into ROS 2 parameters, and sets the CF2 parameters based on the *crazyflies.yaml* input.\n- **Logging to ROS 2 topics handling**: The server sets up logblocks for data streaming in the crazyflie, and transforms the received variables into ROS 2 topics.\n- **Run-time configuration**: Both parameters and logging can be configured in run-time while the server is connected with the Crazyflies. Please check :ref:`usage`.\n\nIt also setups several flight command services:\n\n- **Takeoff / Land / GoTo**: With a single service command and a given height or coordinate, you can make the connected crazyflies take off, go to a position and land.\n- **Upload / Start trajectory**: You can upload a predefined trajectory and indicate if the Crazyflies need to start flying it.\n- **Emergency** : To turn off the motors in case something goes wrong.\n- **/all or /cf2** : The services are setup either for all crazyflies to respond to, or each individual crazyflie, depended on the prefix.\n\nSimulation\n----------\n\nThe simulator uses the Crazyflie firmware as a software-in-the-loop (SIL). It provides the same ROS interface as the server and therefore can be used with C++ or Python user code.\n\nCurrently, the desired setpoint is visualized in rviz (see :ref:`usage`) or a simple physics-based simulator can be used.\n\nSupport functionality with backends\n-----------------------------------\n\n+---------------------+---------+-----------+---------+\n| **Functionality**   | **Cpp** | **CFlib** | **Sim** |\n+=====================+=========+===========+=========+\n| Parameters          | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| Logging                                             |\n+---------------------+---------+-----------+---------+\n| - default: pose     | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - default: scan     | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - default: odom     | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - default: status   | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - custom            | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - Add/Remove Srv    | No      | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| Broadcasts          | Yes     | No        | n/a     |\n+---------------------+---------+-----------+---------+\n| Manual control                                      |\n+---------------------+---------+-----------+---------+\n| - cmd_full_state    | Yes     | Yes       | Yes     |\n+---------------------+---------+-----------+---------+\n| - cmd_position      | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - cmd_hover         | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - cmd_velocity_world| Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| High-level control                                  |\n+---------------------+---------+-----------+---------+\n| - takeoff/land      | Yes     | Yes       | Yes     |\n+---------------------+---------+-----------+---------+\n| - go_to             | Yes     | Yes       | Yes     |\n+---------------------+---------+-----------+---------+\n| - upload/start traj | Yes     | Yes       | Yes     |\n+---------------------+---------+-----------+---------+\n| Positioning System                                  |\n+---------------------+---------+-----------+---------+\n| - Motion Capture    | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - Flow Deck         | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - LightHouse        | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| - LPS               | Yes     | Yes       | No      |\n+---------------------+---------+-----------+---------+\n| Misc                                                |\n+---------------------+---------+-----------+---------+\n| - Arming            | Yes     | Yes       | n/a     |\n+---------------------+---------+-----------+---------+\n"
  },
  {
    "path": "docs2/requirements.txt",
    "content": "numpy\npyyaml\nsphinx\nsphinx-argparse\nsphinx-rtd-theme\nsphinx_design\nsphinxcontrib-programoutput\n"
  },
  {
    "path": "docs2/tutorials.rst",
    "content": ".. _tutorials:\n\nROS 2 Tutorials\n===============\n\nThis page shows tutorials which connects the Crazyflie through Crazyswarm2 to with external packages like RVIZ2, teleop_twist_keyboard, SLAM toolbox and NAV2 bringup. Have fun!\n\n\n.. warning::\n  These tutorials are for advanced use and still under development. Beware of errors and bugs and be sure to use https://github.com/IMRCLab/crazyswarm2/discussions for any support questions. Also this requires a bit of knowledge for ROS 2 so we highly recommend following `their beginner tutorials <https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html>`_.\n\n\n\nTeleoperation keyboard\n----------------------\n\nWe have an example of the telop_twist_keyboard package working together with the crazyflie\n\nFirst, make sure that the crazyflies.yaml has the right URI and if you are using the `Flow deck <https://www.bitcraze.io/products/flow-deck-v2/>`_ or `any other position system available <https://www.bitcraze.io/documentation/system/positioning//>`_ to the crazyflie.\nset the controller to 1 (PID).\n\nAnd if you  have not already, install the teleop package for the keyboard. (replace DISTRO with humble, iron, or jazzy):\n\n.. code-block:: bash\n\n    sudo apt-get install ros-DISTRO-teleop-twist-keyboard\n\nThen, first checkout keyboard_velmux_launch.py and make sure that the 'robot_prefix' of vel_mux matches your crazyflie ID in crazyfies.yaml ('cf231').\n\nThen run the following launch file to start up the crazyflie server (CFlib):\n\n.. code-block:: bash\n\n    ros2 launch crazyflie_examples keyboard_velmux_launch.py\n\nin another terminal run:\n\n.. code-block:: bash\n\n    ros2 run teleop_twist_keyboard teleop_twist_keyboard\n\nUse 't' to take off, and 'b' to land. For the rest, use the instructions of the telop package.\n\n\nVizualization with RVIZ2\n------------------------\n\n\nMake sure your crazyflie knows its position, either by a  `flow deck <https://www.bitcraze.io/products/flow-deck-v2/>`_ or `any other position system available <https://www.bitcraze.io/documentation/system/positioning//>`_ to the crazyflie.\n\nIn crazyflie.yaml, make sure that this following is added or uncommented\n\n.. code-block:: bash\n\n    all:\n    ...\n    firmware_logging:\n        enabled: true\n        default_topics:\n        pose:\n            frequency: 10 # Hz\n\nIn the first terminal, launch the server (use `backend:=cflib` if you need the odom topic)\n\n.. code-block:: bash\n\n    ros2 launch crazyflie launch.py\n\nIn the second terminal\n\n.. code-block:: bash\n\n    rviz2\n\nThen set 'fixed frame' to 'world' and add the TF plugin. Then in 'TF', check the 'show names' checkbox.\nThe crazyflie names should appear with their estimated position.\n\nThis RVIZ2 visualization can be done for the default topics:\n\n* 'pose': '/cf231/pose/' Transforms and Pose\n* 'odom': '/cf231/odom/' Odometry\n* 'scan': '/cf231/scan' Scan\n\nHere you can see an example of 5 crazyflies with the Pose default topic enabled, while taking off and landing\n\n.. raw:: html\n\n    <div style=\"position: relative; padding-bottom: 56.25%; margin-bottom: 20pt; height: 0; overflow: hidden; max-width: 100%; height: auto;\">\n        <iframe src=\"https://www.youtube.com/embed/w99hLldcSp4\" frameborder=\"0\" allowfullscreen style=\"position: absolute; top: 0; left: 0; width: 100%; height: 100%;\"></iframe>\n    </div>\n\nMapping with simple mapper\n--------------------------\n\nIf you have a crazyflie with a multiranger and flowdeck, you can try out some simple mapping.\n\nMake sure that the scan and odometry logging is enabled and the reference frame is set to odom in crazyflies.yaml:\n\n.. code-block:: bash\n\n  firmware_logging:\n    enabled: true\n    default_topics:\n      odom:\n        frequency: 10 # Hz\n      scan:\n        frequency: 10 # Hz\n\nand make sure that the pid controller and kalman filter is enabled:\n\n.. code-block:: bash\n\n  firmware_params:\n    stabilizer:\n      estimator: 2 # 1: complementary, 2: kalman\n      controller: 1 # 1: PID, 2: mellinger\n\nFinally make sure that the reference frame is set to 'cf231/odom' \n\n.. code-block:: bash\n\n    reference_frame: cf231/odom\n\nIf you are using a different name for your crazyflie, make sure to change the following in the example launch file (multiranger_simple_mapper_launch.py):\n\n.. code-block:: bash\n\n    crazyflie_name = '/cf231'\n\nThen start the simple mapper example launch file:\n\n.. code-block:: bash\n\n    ros2 launch crazyflie_examples multiranger_simple_mapper_launch.py\n\nAnd watch the mapping happening in rviz2 while controlling the crazyflie with the teleop node (see the sections above).\n\nMapping with the SLAM toolbox\n-----------------------------\n\nYou can connect the Crazyflie through ROS 2 with existing packages like the `SLAM toolbox <https://github.com/SteveMacenski/slam_toolbox/>`_.\nWith a `Flow deck <https://www.bitcraze.io/products/flow-deck-v2/>`_ and `Multi-ranger <https://www.bitcraze.io/products/multi-ranger-deck/>`_\n) a simple map can be created.\n\n.. note::\n  Mind that this will only show the mapping part of SLAM, as the ray matching with the sparse sensing Multi-ranger is quite challenging for the SLAM toolbox\n\nPreperation\n~~~~~~~~~~~\n\nAssuming you have installed ROS 2 and Crazyswarm2 according to the instructions and went through the guides on Usage, now install the slam toolbox:\n\n.. code-block:: bash\n\n    sudo apt-get install ros-DISTRO-slam-toolbox\n\nGo to crazyflie/config/crazyflie.yaml, change the URI of the crazyflie to the one yours has and put the crazyflies you don't use on 'enabled: false':\n\n.. code-block:: bash\n\n  cf231:\n    enabled: true\n    uri: radio://0/20/2M/E7E7E7E701\n\nAnd enable the following default topic logging and the reference frames:\n\n.. code-block:: bash\n\n  firmware_logging:\n    enabled: true\n    default_topics:\n      odom:\n        frequency: 10 # Hz\n      scan:\n        frequency: 10 # Hz\n\nAlso, make sure that the standard controller is set to 1 (PID) for the flowdeck and the state estimator is set to 2 (kalman):\n\n.. code-block:: bash\n\n  firmware_params:\n    stabilizer:\n      estimator: 2 # 1: complementary, 2: kalman\n      controller: 1 # 1: PID, 2: mellinger\n\n\nFinally make sure that the reference frame is set to 'cf231/odom' \n\n.. code-block:: bash\n\n    reference_frame: cf231/odom\n\n\nConnecting with the Crazyflie\n~~~~~~~~~~~~~~~~~~~~~~~~~~~~~\n\nLet's first look at the launch file real quick (multiranger_mapping_launch.py):\n\n\n.. code-block:: bash\n\n      return LaunchDescription([\n          IncludeLaunchDescription(\n          PythonLaunchDescriptionSource([os.path.join(\n              get_package_share_directory('crazyflie'), 'launch'),\n              '/launch.py']),\n          launch_arguments={\n              'backend': 'cflib',\n              'gui': 'false',\n              'teleop': 'false',\n              'mocap': 'false',\n              }.items()),\n          Node(\n              package='crazyflie',\n              executable='vel_mux.py',\n              name='vel_mux',\n              output='screen',\n              parameters=[{'hover_height': 0.3},\n                          {'incoming_twist_topic': '/cmd_vel'},\n                          {'robot_prefix': '/cf231'}]\n          ),\n          IncludeLaunchDescription(\n              PythonLaunchDescriptionSource(\n                  os.path.join(get_package_share_directory('slam_toolbox'), 'launch/online_async_launch.py')),\n              launch_arguments={\n                  'slam_params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/slam_params.yaml'),\n                  'use_sim_time': 'False',\n              }.items()\n          ),\n      ])\n\n      \nHere is an explanation of the nodes:\n\n* The first node enables the crazyflie server, namely the python version (cflib) as that currently has logging enabled. This takes the crazyflies.yaml file you just edited and uses those values to set up the crazyflie. You might need to change some topic strings based on your Crazyflie name (`/cf231` to something else)\n* The second node is a velocity command handler, which takes an incoming twist message, makes the Crazyflie take off to a fixed height and enables velocity control of external packages (you'll see why soon enough).\n* The third node is the slam toolbox node. You noted that we gave it some different parameters, which can be found in the crazyflie_examples/config/slam_params.yaml. Here we upped the speed of the map generation, decreased the resolution and turn of ray matching as mentioned in the warning above.\n\nTurn on your crazyflie and put it in the middle of the room you would like to map. Make sure to mark the starting position for later.\n\nNow startup the crazyflie server with the following example launch file, after sourcing the 'setup.bash' of course:\n\n.. code-block:: bash\n\n    source install/setup.bash\n    ros2 launch crazyflie_examples multiranger_mapping_launch.py\n\nYou should now see the M4 LED blinking green and red and the following appear on the screen:\n\n.. code-block:: bash\n\n    [INFO] [launch]: All log files can be found below /home/knmcguire/.ros/log/2022-10-03-16-15-53-553693-kim-legion-15498\n    [INFO] [launch]: Default logging verbosity is set to INFO\n    [INFO] [crazyflie_server.py-1]: process started with pid [15500]\n    [INFO] [vel_mux.py-2]: process started with pid [15502]\n    [INFO] [async_slam_toolbox_node-3]: process started with pid [15504]\n    [async_slam_toolbox_node-3] [INFO] [1664806553.866149124] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver\n    [vel_mux.py-2] [INFO] [1664806559.174521891] [vel_mux]: Velocity Multiplexer set for /cf231 with height 0.3 m using the /cmd_vel topic\n    [crazyflie_server.py-1] [INFO] [1664806560.043101845] [crazyflie_server]:  radio://0/20/2M/E7E7E7E701 is fully connected!\n    [crazyflie_server.py-1] [INFO] [1664806560.044138096] [crazyflie_server]: All Crazyflies are fully connected!\n    [crazyflie_server.py-1] [INFO] [1664806560.054259470] [crazyflie_server]:  radio://0/20/2M/E7E7E7E701: commander.enHighLevel is set to 1\n    [crazyflie_server.py-1] [INFO] [1664806560.105691178] [crazyflie_server]:  radio://0/20/2M/E7E7E7E701: stabilizer.controller is set to 1\n    [crazyflie_server.py-1] [INFO] [1664806560.107138259] [crazyflie_server]:  radio://0/20/2M/E7E7E7E701: stabilizer.estimator is set to 2\n    [crazyflie_server.py-1] [INFO] [1664806560.114968490] [crazyflie_server]: All Crazyflies parameters are initialized\n    [crazyflie_server.py-1] [INFO] [1664806560.116479518] [crazyflie_server]: radio://0/20/2M/E7E7E7E701 setup logging for scan at freq 10\n    [crazyflie_server.py-1] [INFO] [1664806560.118522365] [crazyflie_server]: radio://0/20/2M/E7E7E7E701 setup logging for odom at freq 10\n    [crazyflie_server.py-1] [INFO] [1664806560.123137907] [crazyflie_server]: All Crazyflies loggging are initialized\n    [async_slam_toolbox_node-3] [INFO] [1664806560.329904109] [slam_toolbox]: Message Filter dropping message: frame 'cf231' at time 1664806560.232 for reason 'discarding message because the queue is full'\n    [async_slam_toolbox_node-3] Info: clipped range threshold to be within minimum and maximum range!\n    [async_slam_toolbox_node-3] [WARN] [1664806560.333439709] [slam_toolbox]: maximum laser range setting (3.5 m) exceeds the capabilities of the used Lidar (3.5 m)\n    [async_slam_toolbox_node-3] Registering sensor: [Custom Described Lidar]\n\n\nIf anything is off, check if the crazyflie.yaml has been configured correctly!\n\nNow, open up a  rviv2 window in a seperate terminal with :\n\n.. code-block:: bash\n\n    source /opt/ros/DISTRO/setup.bash\n    rviz2\n\nAdd the following displays and panels to RVIZ:\n\n* Changed the 'Fixed frame' to 'map'\n* 'Add' button under displays and 'by topic' tab, select the '/map' topic.\n* 'Add' button under displays and 'by display type' add a transform.\n* 'Panels' on the top menu, select 'add new panel' and select the SLAMToolBoxPlugin\n\nIt should look like something like this:\n\n.. image:: images/slam_rviz2.jpg\n\n\nFlying and mapping\n~~~~~~~~~~~~~~~~~~\n\nWhile still connected to the crazyflie with the server, open another terminal and type:\n\n.. code-block:: bash\n\n    source /opt/ros/DISTRO/setup.bash\n    ros2 run teleop_twist_keyboard teleop_twist_keyboard\n\nand make the crazyflie take off with the 't' key on your keyboard. Now fly around the room to make a map of it.\n\n.. raw:: html\n\n    <div style=\"position: relative; padding-bottom: 56.25%; margin-bottom: 20pt; height: 0; overflow: hidden; max-width: 100%; height: auto;\">\n        <iframe src=\"https://www.youtube.com/embed/-NfKnlJMAHQ\" frameborder=\"0\" allowfullscreen style=\"position: absolute; top: 0; left: 0; width: 100%; height: 100%;\"></iframe>\n    </div>\n\n\n.. note::\n\n    Tip: start with turning slowly with yaw, which should be enough to get most of the room.\n\n\nOnce you are happy, you can save the map with 'Save Map' in the SLAM toolbox panel, and land the crazyflie with 't' with teleop_twist_keyboard.\n\nIf not, you could tweak with the parameters of  the `SLAM toolbox <https://github.com/SteveMacenski/slam_toolbox/>`_ to get a better result.\n\n\nConnecting with Nav2 Bringup\n----------------------------\n\nWith the previous tutorial you made a map of the environment, so now it is time to use it for navigation!\n\nPreperation\n~~~~~~~~~~~\n.. note::\n\n  This tutorial assume you have done the above mapping tutorial first, along with the yaml file changes\n\nFind the all the files that were created by the RVIZ2 slam toolbox plugin, which should be in format \\*.yaml, \\*.posegraph, \\*.data and \\*.pgm, and copy them in the /crazyflie_examples/data/ folder.\nEither you can replace those that are there already ('map.\\*'), or call them different and just change the name in the launch file, which will be explain now.\n\nNext, install the Navigation2 Bringup package:\n\n.. code-block:: bash\n\n  sudo apt-get install ros-DISTRO-nav2-bringup\n\nLooking at the Launch file\n~~~~~~~~~~~~~~~~~~~~~~~~~~\n\nLet's take a look at the launch file (multiranger_nav3_launch.py):\n\n.. code-block:: python\n\n      map_name = 'map'\n\n      return LaunchDescription([\n\n          IncludeLaunchDescription(\n              PythonLaunchDescriptionSource([os.path.join(\n                  get_package_share_directory('crazyflie'), 'launch'),\n                  '/launch.py']),\n              launch_arguments={\n                  'backend': 'cflib',\n                  'gui': 'false',\n                  'teleop': 'false',\n                  'mocap': 'false',\n                  }.items()),\n          Node(\n              package='crazyflie',\n              executable='vel_mux.py',\n              name='vel_mux',\n              output='screen',\n              parameters=[{'hover_height': 0.3},\n                          {'incoming_twist_topic': '/cmd_vel'},\n                          {'robot_prefix': '/cf231'}]\n          ),\n          IncludeLaunchDescription(\n              PythonLaunchDescriptionSource(\n                  os.path.join(get_package_share_directory('slam_toolbox'), 'launch/online_async_launch.py')),\n              launch_arguments={\n                  'slam_params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/slam_params.yaml'),\n                  'use_sim_time': 'False',\n              }.items()\n          ),\n          IncludeLaunchDescription(\n              PythonLaunchDescriptionSource(\n                  os.path.join(get_package_share_directory('nav2_bringup'), 'launch/bringup_launch.py')),\n              launch_arguments={\n                  'slam': 'False',\n                  'use_sim_time': 'False',\n                  'map': get_package_share_directory('crazyflie_examples') + '/data/' + map_name + '.yaml',\n                  'params_file': os.path.join(get_package_share_directory('crazyflie_examples'), 'config/nav2_params.yaml'),\n                  'autostart': 'True',\n                  'use_composition': 'True',\n                  'transform_publish_period': '0.02'\n              }.items()\n          ),\n          IncludeLaunchDescription(\n              PythonLaunchDescriptionSource(\n                  os.path.join(bringup_launch_dir, 'rviz_launch.py')),\n              launch_arguments={\n                  'rviz_config': os.path.join(\n                      get_package_share_directory('nav2_bringup'), 'rviz', 'nav2_default_view.rviz')}.items())\n      ])\n\n\nThe crazyflie_server, vel_mux and slam toolbox nodes are obviously the same as the mapping launch file example, with some key differences:\n\n* crazyflie_server: The reference frame is set to 'map'. This is to ensure compatibilty with the NAV2 bringup node later.\n* slam toolbox:  'map_frame' set to 'map, 'mode' set to localization with a 'map_file_name' and 'map_start_pose' (now remember marking the start position of the mapping tutorial?)\n\nThe next two nodes are new, which are included IncludeLaunchDescription to include other launch files (since these are pretty big).\n\n* Navigation Bringup: 'slam' is set to false since that is already enabled, 'map' includes the yaml file of what was created in the previous mapping tutorial. 'params_file' contains all the parameters that have been altered a bit for the crazyflie.\n* RVIZ2: 'rviz_config' is set to a default rviz2 file of Nav2 that saves us the trouble of setting everything up by hand.\n\nNavigate the Crazyflie\n~~~~~~~~~~~~~~~~~~~~~~\n\nIn a terminal run the following from the ROS 2 workspace.\n\n.. code-block:: bash\n\n    source install/setup.bash\n    ros2 launch crazyflie_examples multiranger_nav2_launch.py\n\nWe will not now show all the print-outs, just make sure that at the crazyflie is connected and it outputs the right transforms and topics like in the mapping tutorial\n\nNow, open another terminal and open up a teleop_twist_keyboard just like last time. Press 't' on your keyboard to make the crazyflie fly.\n\nOn top of the RVIZ2 window, you see the button 'Nav2 goal'. Click at in a free spot in the map and watch the crazyflie go places :).\n\nAlso try it out by putting obstacles along the path of the crazyflie like in the video here.\n\n.. raw:: html\n\n    <div style=\"position: relative; padding-bottom: 56.25%; margin-bottom: 20pt; height: 0; overflow: hidden; max-width: 100%; height: auto;\">\n        <iframe src=\"https://www.youtube.com/embed/1BKLPkQ6Gz8\" frameborder=\"0\" allowfullscreen style=\"position: absolute; top: 0; left: 0; width: 100%; height: 100%;\"></iframe>\n    </div>\n\nAs you noticed, the movement around the obstacles are pretty conservative. You can tune the values in /config/nav2_params.yaml, like the global or local planner's inflation_layer or the size of the robot.\nPlease check out  `NAV2's tuning documentation <https://navigation.ros.org/tuning/index.html/>`_ for more explanation of these values.\n\n.. note::\n  Final note. The SLAM performance and navigation performance of the Crazyflie with the multiranger is doable but not perfect. We absolutely encourage you to tweak and tune the parameters to get something better! (And if you do, please share :D)\n\n\n"
  },
  {
    "path": "docs2/usage.rst",
    "content": ".. _usage:\n\nUsage\n=====\n\n.. warning::\n    Do not forget to source your ROS 2 workspace in each terminal you would like to use it\n\n    .. code-block:: bash\n\n        . install/local_setup.bash\n\n\n.. warning::\n    If you work in a shared network (lab, classroom) or similar, you might want to avoid\n    controlling other robots. This is in particular true for simulation. In this case,\n    you can use\n\n    .. code-block:: bash\n\n        export ROS_LOCALHOST_ONLY=1\n        export ROS_DOMAIN_ID=<unique number between 0 and 101>\n\n    The first environment variable restricts ROS to your local machine. The second is useful\n    if you have multiple user accounts on the same machine (e.g., a shared workstation computer).\n    In such case, each user should use a unique `domain ID <https://docs.ros.org/en/iron/Concepts/Intermediate/About-Domain-ID.html>`_.\n\n\nConfiguration\n-------------\n\nAll configuration files are in crazyflie/config.\n\n* crazyflies.yaml : setting up everything related to the robots.\n* server.yaml : setting up everything related to the server.\n* motion_capture.yaml : configs for the motion capture package.\n* teleop.yaml : configs for remote controls.\n\ncrazyflies.yaml\n~~~~~~~~~~~~~~~\n\nEach crazyflie should have an unique URI which can `be changed in Bitcraze's CFclient <https://www.bitcraze.io/documentation/repository/crazyflie-clients-python/master/userguides/userguide_client/#firmware-configuration/>`_.\nThey can also be enabled in case you don't want the server to connect with it.\n\n.. code-block:: yaml\n\n    robots:\n        cf231:\n            enabled: true\n            uri: radio://0/80/2M/E7E7E7E7E7\n            initial_position: [0, 0, 0]\n            type: cf21  # see robot_types\n\n        cf5:\n            enabled: false\n            uri: radio://0/80/2M/E7E7E7E705\n            initial_position: [0, -0.5, 0]\n            type: cf21  # see robot_types\n\nThe yaml file also contains different robot_types, to indicate differences between each platform:\n\n.. code-block:: yaml\n\n    robot_types:\n        cf21:\n            motion_capture:\n                tracking: \"librigidbodytracker\"\n                # the following settings are only relevant if \"librigidbodytracker\" is used; see motion_capture.yaml\n                marker: default_single_marker\n                dynamics: default\n            big_quad: false\n            battery:\n                voltage_warning: 3.8  # V\n                voltage_critical: 3.7 # V\n\n        cf21_mocap_deck:\n            motion_capture:\n                tracking: \"librigidbodytracker\"\n                # the following settings are only relevant if \"librigidbodytracker\" is used; see motion_capture.yaml\n                marker: mocap_deck\n                dynamics: default\n            big_quad: false\n            battery:\n                voltage_warning: 3.8  # V\n                voltage_critical: 3.7 # V\n\nThe yaml file also contain an 'all' field, in case you have parameters or logging that you want enabled for all the connected crazyflies.\n\n\n.. code-block:: yaml\n\n    all:\n        firmware_logging:\n            enabled: false\n            default_topics:\n                pose:\n                frequency: 10 # Hz\n            #custom_topics:\n            #  topic_name1:\n            #    frequency: 10 # Hz\n            #    vars: [\"stateEstimateZ.x\", \"stateEstimateZ.y\", \"stateEstimateZ.z\", \"pm.vbat\"]\n            #  topic_name2:\n            #    frequency: 1 # Hz\n            #    vars: [\"stabilizer.roll\", \"stabilizer.pitch\", \"stabilizer.yaw\"]\n        firmware_params:\n            commander:\n                enHighLevel: 1\n            stabilizer:\n                estimator: 2 # 1: complementary, 2: kalman\n                controller: 2 # 1: PID, 2: mellinger\n\nThe above also contains an example of the firmware_logging field, where default topics can be enabled or custom topics based on the `existing log toc of the crazyflie <https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/api/logs//>`_.\nMoreover, it also contains the firmware_params field, where parameters can be set at startup.\nAlso see the `parameter list of the crazyflie <https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/api/params//>`_ for that.\n\n\nMind that you can also place the firmware_params and firmware_logging fields per crazyflie in 'robots'  or the 'robot_types' field.\nThe server node will upon initialization, first look at the params/logs from the individual crazyflie's settings, then the robot_types, and then anything in 'all' which has lowest priority.\n\nPositioning\n-----------\n\nThe Crazyflie can be positioned in different ways, including motion capture and onboard positioning.\nThis blogpost provides a good overview of the different positioning systems if you are unsure about which one you are using: `Positioning System Overview <https://www.bitcraze.io/2021/05/positioning-system-overview/>`_.\n\nMotion capture\n~~~~~~~~~~~~~~\n\nIf you have a motion capture system, you can input the specifics in the motion_capture.yaml file.\n\n.. code-block:: yaml\n\n    /motion_capture_tracking:\n        ros__parameters:\n            type: \"optitrack\"\n            hostname: \"optitrackPC\"\n\n`type` can be replaced by \"optitrack\", \"vicon\", \"qualisys\" or any of the other supported motion capture systems of the `motion capture tracking package <https://github.com/IMRCLab/motion_capture_tracking/tree/ros2/>`_.\n'hostname' is the hostname of the computer running the motion capture software which can either be the PC name or the IP.\nPlease check the documentation of the `motion capture tracking package <https://github.com/IMRCLab/motion_capture_tracking/tree/ros2/>`_ for any additional configuration that might be needed on the vendor software side.\n\nThere are two different modes for tracking rigid bodies:\n\n1. Using the vendor-specific software (e.g., VICON Tracker or OptiTrack Motive), or\n2. Using `librigidbodytracker`, which is a package built into the `motion capture tracking package <https://github.com/IMRCLab/motion_capture_tracking/tree/ros2/>`_ and allows to use identical marker configurations or a single marker per rigid body as long as the initial pose is known a-priori.\n\nYou can enable either mode in `crazyflies.yaml`:\n\n.. code-block:: yaml\n\n    robot_types:\n    cf21:\n        motion_capture:\n            tracking: \"librigidbodytracker\" # use \"vendor\" for vendor-specific software or \"librigidbodytracker\" for custom frame-by-frame tracking using motion capture point clouds\n            marker: default_single_marker\n            dynamics: default\n.. note::\n\n    For most experiments, we recommend putting a single marker on top of the robots and use the \"librigidbodytracker\" with the \"default_single_marker\" configuration.\n    In this mode, we use optimal task assignment at every frame, which makes this mode more robust to motion capture outliers compared to the duplicate marker arrangements.\n    The main disadvantage is that the yaw angle cannot be observed without moving in the xy-plane.\n    Nevertheless, it is possible to hover for 30 seconds in place for a Crazyflie 2.1, without causing flight instabilities.\n\n\nFor more in-depth information about the motion capture tracking package, see the `documentation <https://github.com/IMRCLab/motion_capture_tracking/tree/ros2/>`_.\n\nOnboard positioning\n~~~~~~~~~~~~~~~~~~~\n\nThe Crazyflie also supports several alternative positioning systems that provide direct onboard position or pose estimation.\nIn this case you do not need to receive positioning from an external system like with MoCap.\n\nInstructions per positioning system:\n\n* The `Loco positioning system <https://www.bitcraze.io/documentation/system/positioning/loco-positioning-system/>`_ - `Follow Bitcraze's tutorial on LPS here <https://www.bitcraze.io/documentation/tutorials/getting-started-with-loco-positioning-system/>`_.\n* The `Lighthouse positioning system <https://www.bitcraze.io/documentation/system/positioning/lighthouse/>`_ - `Follow Bitcraze's tutorial on Lighthouse here <https://www.bitcraze.io/documentation/tutorials/getting-started-with-lighthouse-positioning-system/>`_. Make sure to review the system management for saving and loading a system config, such that you don't have to redo the basestation geometry estimation for each crazyflie.\n* The `Flow deck <https://www.bitcraze.io/products/flow-deck-v2/>`_ -  `Follow Bitcraze's tutorial on the flowdeck here <https://www.bitcraze.io/documentation/tutorials/getting-started-with-flow-deck/>`_. Note that the flow deck provides an relative positoing estimate and might conflict when you are flying with crazyswarm2 if you are flying with absolute coordinates instead of relative ones.\n\nAlso in this case, make sure that motion_capture is disabled in the crazyflies.yaml file:\n\n.. code-block:: yaml\n\n    robot_types:\n        cf21:\n            motion_capture:\n                tracking: \"vendor\"\n\nAlso it is a good idea to turn on pose estimation logging such that you are able to see the poses and transforms of the Crazyflie updated in real life in rviz or the Swarm management gui.\n\n.. code-block:: yaml\n\n    firmware_logging:\n        enabled: true\n        default_topics:\n            pose:\n            frequency: 10 # Hz\n\n\nMoreover, be aware that the motion capture node is enabled in the launch file by default, which can be turned off by adding 'mocap:=False' to the launch command.\n\nSimulation\n----------\n\nAny usage of the ROS API, including high-level Python scripts, can be visualized before execution. The initial position and number of robots is taken from the crazyflies.yaml configuration file.\nThe simulation uses the firmware code as software-in-the-loop, and can optionally include the robot dynamics.\nThe configuration of the simulation (physics simulator, controller, etc.) can be changed in server.yaml.\n\nExample:\n\n.. code-block:: bash\n\n    [terminal]$ ros2 launch crazyflie_examples launch.py script:=hello_world backend:=sim\n\nwhich is a short-hand for the following two commands:\n\n.. code-block:: bash\n\n    [terminal1]$ ros2 launch crazyflie launch.py backend:=sim\n    [terminal2]$ ros2 run crazyflie_examples hello_world --ros-args -p use_sim_time:=True\n\nPhysical Experiments\n--------------------\n\nTeleoperation controller\n~~~~~~~~~~~~~~~~~~~~~~~~\n\nWe currently assume an XBox controller (the button mapping can be changed in teleop.yaml). It is possible to fly in different modes, including attitude-control and position-control (in which case any localization system can assist.)\n\n.. code-block:: bash\n\n    ros2 launch crazyflie launch.py\n\n\nPython scripts\n~~~~~~~~~~~~~~\n\nIn the first terminal run the server, in the second the desired script.\nYou may run the script multiple times or different scripts while leaving the server running.\n\n.. code-block:: bash\n\n    [terminal1]$ ros2 launch crazyflie launch.py\n    [terminal2]$ ros2 run crazyflie_examples hello_world\n\nIf you only want to run a single script once, you can also use:\n\n.. code-block:: bash\n\n    [terminal]$ ros2 launch crazyflie_examples launch.py script:=hello_world\n\nSwarm Management\n----------------\n\nThe launch file will also start a swarm management tool that is a ROS node and web-based GUI.\nIn the upper pane is the location of the drone visualized in a 3D window, similar to rviz.\nIn the lower pane, the status as well as log messages are visible (tabbed per drone).\nIn the future, we are planning to add support for rebooting and other actions.\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/USC.yaml",
    "content": "crazyflies:\n  - id: 1\n    channel: 100\n    type: \"default\"\n    initialPosition: [1.5, 1.5, 0.0]\n  - id: 2\n    channel: 110\n    type: \"default\"\n    initialPosition: [1.5, 1.0, 0.0]\n  - id: 3\n    channel: 120\n    type: \"default\"\n    initialPosition: [1.5, 0.5, 0.0]\n  - id: 4\n    channel: 100\n    type: \"default\"\n    initialPosition: [1.5, 0.0, 0.0]\n  - id: 5\n    channel: 110\n    type: \"default\"\n    initialPosition: [1.5, -0.5, 0.0]\n  - id: 6\n    channel: 120\n    type: \"default\"\n    initialPosition: [1.5, -1.0, 0.0]\n  - id: 7\n    channel: 100\n    type: \"default\"\n    initialPosition: [1.5, -1.5, 0.0]\n\n  - id: 8\n    channel: 110\n    type: \"default\"\n    initialPosition: [1.0, 1.5, 0.0]\n  - id: 9\n    channel: 120\n    type: \"default\"\n    initialPosition: [1.0, 1.0, 0.0]\n  - id: 10\n    channel: 100\n    type: \"default\"\n    initialPosition: [1.0, 0.5, 0.0]\n  - id: 11\n    channel: 110\n    type: \"default\"\n    initialPosition: [1.0, 0.0, 0.0]\n  - id: 12\n    channel: 120\n    type: \"default\"\n    initialPosition: [1.0, -0.5, 0.0]\n  - id: 13\n    channel: 100\n    type: \"default\"\n    initialPosition: [1.0, -1.0, 0.0]\n  - id: 14\n    channel: 110\n    type: \"default\"\n    initialPosition: [1.0, -1.5, 0.0]\n\n  - id: 15\n    channel: 120\n    type: \"default\"\n    initialPosition: [0.5, 1.5, 0.0]\n  - id: 16\n    channel: 100\n    type: \"default\"\n    initialPosition: [0.5, 1.0, 0.0]\n  - id: 17\n    channel: 110\n    type: \"default\"\n    initialPosition: [0.5, 0.5, 0.0]\n  - id: 18\n    channel: 120\n    type: \"default\"\n    initialPosition: [0.5, 0.0, 0.0]\n  - id: 19\n    channel: 100\n    type: \"default\"\n    initialPosition: [0.5, -0.5, 0.0]\n  - id: 20\n    channel: 110\n    type: \"default\"\n    initialPosition: [0.5, -1.0, 0.0]\n  - id: 21\n    channel: 120\n    type: \"default\"\n    initialPosition: [0.5, -1.5, 0.0]\n\n  - id: 22\n    channel: 100\n    type: \"default\"\n    initialPosition: [0.0, 1.5, 0.0]\n  - id: 23\n    channel: 110\n    type: \"default\"\n    initialPosition: [0.0, 1.0, 0.0]\n  - id: 24\n    channel: 120\n    type: \"default\"\n    initialPosition: [0.0, 0.5, 0.0]\n  - id: 25\n    channel: 100\n    type: \"default\"\n    initialPosition: [0.0, 0.0, 0.0]\n  - id: 26\n    channel: 110\n    type: \"default\"\n    initialPosition: [0.0, -0.5, 0.0]\n  - id: 27\n    channel: 120\n    type: \"default\"\n    initialPosition: [0.0, -1.0, 0.0]\n  - id: 28\n    channel: 100\n    type: \"default\"\n    initialPosition: [0.0, -1.5, 0.0]\n\n  - id: 29\n    channel: 110\n    type: \"default\"\n    initialPosition: [-0.5, 1.5, 0.0]\n  - id: 30\n    channel: 120\n    type: \"default\"\n    initialPosition: [-0.5, 1.0, 0.0]\n  - id: 31\n    channel: 100\n    type: \"default\"\n    initialPosition: [-0.5, 0.5, 0.0]\n  - id: 32\n    channel: 110\n    type: \"default\"\n    initialPosition: [-0.5, 0.0, 0.0]\n  - id: 33\n    channel: 120\n    type: \"default\"\n    initialPosition: [-0.5, -0.5, 0.0]\n  - id: 34\n    channel: 100\n    type: \"default\"\n    initialPosition: [-0.5, -1.0, 0.0]\n  - id: 35\n    channel: 110\n    type: \"default\"\n    initialPosition: [-0.5, -1.5, 0.0]\n\n  - id: 36\n    channel: 120\n    type: \"default\"\n    initialPosition: [-1.0, 1.5, 0.0]\n  - id: 37\n    channel: 100\n    type: \"default\"\n    initialPosition: [-1.0, 1.0, 0.0]\n  - id: 38\n    channel: 110\n    type: \"default\"\n    initialPosition: [-1.0, 0.5, 0.0]\n  - id: 39\n    channel: 120\n    type: \"default\"\n    initialPosition: [-1.0, 0.0, 0.0]\n  - id: 40\n    channel: 100\n    type: \"default\"\n    initialPosition: [-1.0, -0.5, 0.0]\n  - id: 41\n    channel: 110\n    type: \"default\"\n    initialPosition: [-1.0, -1.0, 0.0]\n  - id: 42\n    channel: 120\n    type: \"default\"\n    initialPosition: [-1.0, -1.5, 0.0]\n\n  - id: 43\n    channel: 100\n    type: \"default\"\n    initialPosition: [-1.5, 1.5, 0.0]\n  - id: 44\n    channel: 110\n    type: \"default\"\n    initialPosition: [-1.5, 1.0, 0.0]\n  - id: 45\n    channel: 120\n    type: \"default\"\n    initialPosition: [-1.5, 0.5, 0.0]\n  - id: 46\n    channel: 100\n    type: \"default\"\n    initialPosition: [-1.5, 0.0, 0.0]\n  - id: 47\n    channel: 110\n    type: \"default\"\n    initialPosition: [-1.5, -0.5, 0.0]\n  - id: 48\n    channel: 120\n    type: \"default\"\n    initialPosition: [-1.5, -1.0, 0.0]\n  - id: 49\n    channel: 100\n    type: \"default\"\n    initialPosition: [-1.5, -1.5, 0.0]\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/allCrazyflies.yaml",
    "content": "crazyflies:\n  - id: 1\n    channel: 100\n    initialPosition: [1.5, 1.5, 0.0]\n    type: medium\n  - id: 40\n    channel: 100\n    initialPosition: [-1.0, -0.5, 0.0]\n    type: default\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/figure8_smooth.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.050000,0.000000,-0.000000,0.000000,-0.000000,0.830443,-0.276140,-0.384219,0.180493,-0.000000,0.000000,-0.000000,0.000000,-1.356107,0.688430,0.587426,-0.329106,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,0.396058,0.918033,0.128965,-0.773546,0.339704,0.034310,-0.026417,-0.030049,-0.445604,-0.684403,0.888433,1.493630,-1.361618,-0.139316,0.158875,0.095799,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,0.922409,0.405715,-0.582968,-0.092188,-0.114670,0.101046,0.075834,-0.037926,-0.291165,0.967514,0.421451,-1.086348,0.545211,0.030109,-0.050046,-0.068177,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,0.923174,-0.431533,-0.682975,0.177173,0.319468,-0.043852,-0.111269,0.023166,0.289869,0.724722,-0.512011,-0.209623,-0.218710,0.108797,0.128756,-0.055461,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.405364,-0.834716,0.158939,0.288175,-0.373738,-0.054995,0.036090,0.078627,0.450742,-0.385534,-0.954089,0.128288,0.442620,0.055630,-0.060142,-0.076163,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.001062,-0.646270,-0.012560,-0.324065,0.125327,0.119738,0.034567,-0.063130,0.001593,-1.031457,0.015159,0.820816,-0.152665,-0.130729,-0.045679,0.080444,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,-0.402804,-0.820508,-0.132914,0.236278,0.235164,-0.053551,-0.088687,0.031253,-0.449354,-0.411507,0.902946,0.185335,-0.239125,-0.041696,0.016857,0.016709,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,-0.921641,-0.464596,0.661875,0.286582,-0.228921,-0.051987,0.004669,0.038463,-0.292459,0.777682,0.565788,-0.432472,-0.060568,-0.082048,-0.009439,0.041158,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,-0.923935,0.447832,0.627381,-0.259808,-0.042325,-0.032258,0.001420,0.005294,0.288570,0.873350,-0.515586,-0.730207,-0.026023,0.288755,0.215678,-0.148061,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.053185,-0.398611,0.850510,-0.144007,-0.485368,-0.079781,0.176330,0.234482,-0.153567,0.447039,-0.532729,-0.855023,0.878509,0.775168,-0.391051,-0.713519,0.391628,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/hover_swarm.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <arg name=\"joy_dev\" default=\"/dev/input/js0\" />\n\n  <rosparam command=\"load\" file=\"$(find crazyswarm)/launch/crazyflieTypes.yaml\" />\n  <rosparam command=\"load\" file=\"$(find crazyswarm)/launch/crazyflies.yaml\" />\n\n  <node pkg=\"crazyswarm\" type=\"crazyswarm_server\" name=\"crazyswarm_server\" output=\"screen\" >\n    <rosparam>\n      # Logging configuration (Use enable_logging to actually enable logging)\n      genericLogTopics: [\"log1\"]\n      genericLogTopicFrequencies: [10]\n      genericLogTopic_log1_Variables: [\"stateEstimate.x\", \"ctrltarget.x\"]\n      # firmware parameters for all drones (use crazyflieTypes.yaml to set per type, or\n      # allCrazyflies.yaml to set per drone)\n      firmwareParams:\n        commander:\n          enHighLevel: 1\n        stabilizer:\n          estimator: 2 # 1: complementary, 2: kalman\n          controller: 2 # 1: PID, 2: mellinger\n        ring:\n          effect: 16 # 6: double spinner, 7: solid color, 16: packetRate\n          solidBlue: 255 # if set to solid color\n          solidGreen: 0 # if set to solid color\n          solidRed: 0 # if set to solid color\n          headlightEnable: 0\n        locSrv:\n          extPosStdDev: 1e-3\n          extQuatStdDev: 0.5e-1\n        kalman:\n          resetEstimation: 1\n      # tracking\n      motion_capture_type: \"vicon\" # one of none,vicon,optitrack,qualisys,vrpn\n      object_tracking_type: \"libobjecttracker\" # one of motionCapture,libobjecttracker\n      send_position_only: False # set to False to send position+orientation; set to True to send position only\n      motion_capture_host_name: \"vicon\"\n      save_point_clouds: \"/dev/null\" # set to a valid path to log mocap point cloud binary file.\n      print_latency: False\n      write_csvs: False\n      force_no_cache: False\n      enable_parameters: True\n      enable_logging: False\n      enable_logging_pose: True\n    </rosparam>\n  </node>\n\n  <node name=\"joy\" pkg=\"joy\" type=\"joy_node\" output=\"screen\">\n    <param name=\"dev\" value=\"$(arg joy_dev)\" />\n  </node>\n\n  <node pkg=\"crazyswarm\" type=\"crazyswarm_teleop\" name=\"crazyswarm_teleop\" output=\"screen\">\n    <param name=\"csv_file\" value=\"$(find crazyswarm)/launch/figure8_smooth.csv\" />\n    <param name=\"timescale\" value=\"0.8\" />\n  </node>\n\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find crazyswarm)/launch/test.rviz\"/>\n\n  <!-- <node pkg=\"rqt_plot\" type=\"rqt_plot\" name=\"rqt_plot_x\" args=\"/cf2/log1/values[0]\"/> -->\n  <!-- <node pkg=\"rqt_plot\" type=\"rqt_plot\" name=\"rqt_plot_roll\" args=\"/cf1/log1/values[2] /cf1/log1/values[3]\"/> -->\n\n</launch>\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/mocap_helper.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n\n  <node pkg=\"crazyswarm\" type=\"mocap_helper\" name=\"mocap_helper\" output=\"screen\" >\n    <rosparam>\n      # tracking\n      motion_capture_type: \"vicon\" # one of vicon,optitrack,qualisys,vrpn\n      motion_capture_host_name: \"vicon\"\n    </rosparam>\n  </node>\n</launch>\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/object_tracker.yaml",
    "content": "hostName: vicon\nnumMarkerConfigurations: 2\nmarkerConfigurations:\n  \"0\":\n    numPoints: 4\n    offset: [0.0, -0.01, -0.04]\n    points:\n      \"0\": [0.0177184,0.0139654,0.0557585]\n      \"1\": [-0.0262914,0.0509139,0.0402475]\n      \"2\": [-0.0328889,-0.02757,0.0390601]\n      \"3\": [0.0431307,-0.0331216,0.0388839]\n\n  \"1\":\n    numPoints: 6\n    offset: [0.0, -0.01, -0.01]\n    points:\n      \"0\": [0.0475664,0.0440101,0.0066103]\n      \"1\": [0.0479611,-0.0333709,0.00626755]\n      \"2\": [0.0186841,0.0113895,0.020396]\n      \"3\": [-0.0136136,0.0296063,0.0112455]\n      \"4\": [-0.0292848,0.0437507,0.00688335]\n      \"5\": [-0.028405,-0.0334036,0.00734073]\nnumDynamicsConfigurations: 1\ndynamicsConfigurations:\n  \"0\":\n    maxXVelocity: 2.0\n    maxYVelocity: 2.0\n    maxZVelocity: 2.0\n    maxPitchRate: 20.0\n    maxRollRate: 20.0\n    maxYawRate: 5.0\n    maxRoll: 1.4\n    maxPitch: 1.4\nnumObjects: 5\nobjects:\n  \"0\":\n    name: cf01/cf01\n    markerConfiguration: 0\n    dynamicsConfiguration: 0\n    initialPosition: [0, 1.0, 0]\n    initialYaw: 0\n  \"1\":\n    name: cf03/cf03\n    markerConfiguration: 0\n    dynamicsConfiguration: 0\n    initialPosition: [0, 0.50, 0]\n    initialYaw: 0\n  \"2\":\n    name: cf05/cf05\n    markerConfiguration: 0\n    dynamicsConfiguration: 0\n    initialPosition: [0, 0.00, 0]\n    initialYaw: 0\n  \"3\":\n    name: cf07/cf07\n    markerConfiguration: 0\n    dynamicsConfiguration: 0\n    initialPosition: [0, -0.5, 0]\n    initialYaw: 0\n  \"4\":\n    name: cf09/cf09\n    markerConfiguration: 0\n    dynamicsConfiguration: 0\n    initialPosition: [0, -1.0, 0]\n    initialYaw: 0\n# numObjects: 9\n# objects:\n#   \"0\":\n#     name: cf01/cf01\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, 1.0, 0]\n#     initialYaw: 0\n#   \"1\":\n#     name: cf02/cf02\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, 0.75, 0]\n#     initialYaw: 0\n#   \"2\":\n#     name: cf03/cf03\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, 0.50, 0]\n#     initialYaw: 0\n#   \"3\":\n#     name: cf04/cf04\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, 0.25, 0]\n#     initialYaw: 0\n#   \"4\":\n#     name: cf05/cf05\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, 0.00, 0]\n#     initialYaw: 0\n#   \"5\":\n#     name: cf06/cf06\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, -0.25, 0]\n#     initialYaw: 0\n#   \"6\":\n#     name: cf07/cf07\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, -0.5, 0]\n#     initialYaw: 0\n#   \"7\":\n#     name: cf08/cf08\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, -0.75, 0]\n#     initialYaw: 0\n#   \"8\":\n#     name: cf09/cf09\n#     markerConfiguration: 0\n#     dynamicsConfiguration: 0\n#     initialPosition: [0, -1.0, 0]\n#     initialYaw: 0\n\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/rqt.perspective",
    "content": "{\n  \"keys\": {}, \n  \"groups\": {\n    \"pluginmanager\": {\n      \"keys\": {\n        \"running-plugins\": {\n          \"type\": \"repr\", \n          \"repr\": \"{u'rqt_top/TOP': [1], u'rqt_console/Console': [1]}\"\n        }\n      }, \n      \"groups\": {\n        \"plugin__rqt_pose_view__PoseView__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"view_matrix\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'[[0.2507918179035187, 0.15131781995296478, -0.9561414122581482, 0.0], [-0.9592954516410828, 0.1713167428970337, -0.22450637817382812, 0.0], [0.12983129918575287, 0.9735260605812073, 0.18812307715415955, 0.0], [0.0, -3.0, -17.5, 1.0]]'\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_plot__Plot__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"dock_widget__DataPlotWidget\": {\n              \"keys\": {\n                \"dockable\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"parent\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"None\"\n                }\n              }, \n              \"groups\": {}\n            }, \n            \"plugin\": {\n              \"keys\": {\n                \"autoscroll\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"plot_type\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"topics\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u''\"\n                }, \n                \"y_limits\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"[u'-0.65374175167526', u'4.45411825773817']\"\n                }, \n                \"x_limits\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"[u'8.13676911709831', u'115.200047016144']\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_plot__Plot__2\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"dock_widget__DataPlotWidget\": {\n              \"keys\": {\n                \"dockable\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"parent\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"None\"\n                }\n              }, \n              \"groups\": {}\n            }, \n            \"plugin\": {\n              \"keys\": {\n                \"autoscroll\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"plot_type\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"topics\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u''\"\n                }, \n                \"y_limits\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"[u'-0.245330169725861', u'33.3296037777205']\"\n                }, \n                \"x_limits\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"[u'-58.8226690666928', u'106.694982051849']\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_graph__RosGraph__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"graph_type_combo_box_index\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"topic_filter_line_edit_text\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'/'\"\n                }, \n                \"filter_line_edit_text\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'/'\"\n                }, \n                \"highlight_connections_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"actionlib_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"quiet_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"dead_sinks_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"leaf_topics_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"namespace_cluster_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"auto_fit_graph_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_topic__TopicPlugin__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"tree_widget_header_state\": {\n                  \"type\": \"repr(QByteArray.hex)\", \n                  \"repr(QByteArray.hex)\": \"QtCore.QByteArray('000000ff000000000000000100000000000000000100000000000000000000000000000000000002e5000000050101000100000000000000000500000064ffffffff000000810000000300000005000000c700000001000000030000011800000001000000030000006c0000000100000003000000360000000100000003000000640000000100000003')\", \n                  \"pretty-print\": \"                              d                     l     6     d    \"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_top__TOP__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"dock_widget__\": {\n              \"keys\": {\n                \"dockable\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"True\"\n                }, \n                \"parent\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"None\"\n                }\n              }, \n              \"groups\": {}\n            }, \n            \"plugin\": {\n              \"keys\": {\n                \"is_regex\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"0\"\n                }, \n                \"filter_text\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u''\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_robot_monitor__RobotMonitor__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"splitter\": {\n                  \"type\": \"repr(QByteArray.hex)\", \n                  \"repr(QByteArray.hex)\": \"QtCore.QByteArray('000000ff00000000000000030000006400000064000000c801000000090100000002')\", \n                  \"pretty-print\": \"       d d       \"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_dep__RosPackGraph__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"filter_line_edit_text\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'(Separate pkgs by comma)'\"\n                }, \n                \"highlight_connections_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"with_stacks_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"depth_combo_box_index\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"hide_transitives_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'false'\"\n                }, \n                \"package_type_combo_box\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"directions_combo_box_index\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'0'\"\n                }, \n                \"colorize_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'false'\"\n                }, \n                \"mark_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"auto_fit_graph_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_tf_tree__RosTfTree__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"plugin\": {\n              \"keys\": {\n                \"highlight_connections_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }, \n                \"auto_fit_graph_check_box_state\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'true'\"\n                }\n              }, \n              \"groups\": {}\n            }\n          }\n        }, \n        \"plugin__rqt_console__Console__1\": {\n          \"keys\": {}, \n          \"groups\": {\n            \"dock_widget__ConsoleWidget\": {\n              \"keys\": {\n                \"dockable\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"True\"\n                }, \n                \"parent\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"None\"\n                }\n              }, \n              \"groups\": {}\n            }, \n            \"plugin\": {\n              \"keys\": {\n                \"show_highlighted_only\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"False\"\n                }, \n                \"message_limit\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"20000\"\n                }, \n                \"exclude_filters\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'severity'\"\n                }, \n                \"table_splitter\": {\n                  \"type\": \"repr(QByteArray.hex)\", \n                  \"repr(QByteArray.hex)\": \"QtCore.QByteArray('000000ff0000000000000002000001910000000001000000090100000002')\", \n                  \"pretty-print\": \"               \"\n                }, \n                \"highlight_filters\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"u'message'\"\n                }, \n                \"paused\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"False\"\n                }, \n                \"settings_exist\": {\n                  \"type\": \"repr\", \n                  \"repr\": \"True\"\n                }, \n                \"filter_splitter\": {\n                  \"type\": \"repr(QByteArray.hex)\", \n                  \"repr(QByteArray.hex)\": \"QtCore.QByteArray('000000ff0000000000000002000000ea0000000001000000090100000002')\", \n                  \"pretty-print\": \"               \"\n                }\n              }, \n              \"groups\": {\n                \"exclude_filter_0\": {\n                  \"keys\": {\n                    \"enabled\": {\n                      \"type\": \"repr\", \n                      \"repr\": \"True\"\n                    }, \n                    \"itemlist\": {\n                      \"type\": \"repr\", \n                      \"repr\": \"u''\"\n                    }\n                  }, \n                  \"groups\": {}\n                }, \n                \"highlight_filter_0\": {\n                  \"keys\": {\n                    \"regex\": {\n                      \"type\": \"repr\", \n                      \"repr\": \"False\"\n                    }, \n                    \"text\": {\n                      \"type\": \"repr\", \n                      \"repr\": \"u''\"\n                    }, \n                    \"enabled\": {\n                      \"type\": \"repr\", \n                      \"repr\": \"True\"\n                    }\n                  }, \n                  \"groups\": {}\n                }\n              }\n            }\n          }\n        }\n      }\n    }, \n    \"mainwindow\": {\n      \"keys\": {\n        \"geometry\": {\n          \"type\": \"repr(QByteArray.hex)\", \n          \"repr(QByteArray.hex)\": \"QtCore.QByteArray('01d9d0cb00010000000000000000028400000590000004af000000010000029c0000058f000004ae000000000000')\", \n          \"pretty-print\": \"                       \"\n        }, \n        \"state\": {\n          \"type\": \"repr(QByteArray.hex)\", \n          \"repr(QByteArray.hex)\": \"QtCore.QByteArray('000000ff00000000fd00000001000000030000058f000001e2fc010000000dfb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0031005f005f00440061007400610050006c006f00740057006900640067006500740100000000000003d50000000000000000fb00000042007200710074005f0070006c006f0074005f005f0050006c006f0074005f005f0032005f005f00440061007400610050006c006f007400570069006400670065007401000001f2000001e30000000000000000fb00000044007200710074005f00670072006100700068005f005f0052006f007300470072006100700068005f005f0031005f005f0052006f007300470072006100700068005500690100000000000003d50000000000000000fb00000050007200710074005f006400650070005f005f0052006f0073005000610063006b00470072006100700068005f005f0031005f005f0052006f0073005000610063006b00470072006100700068005500690100000000000003d50000000000000000fb00000022007200710074005f0074006f0070005f005f0054004f0050005f005f0031005f005f0100000000000002f7000000dc00fffffffb00000066007200710074005f006c006f0067006700650072005f006c006500760065006c005f005f004c006f0067006700650072004c006500760065006c005f005f0031005f005f004c006f0067006700650072004c006500760065006c0057006900640067006500740100000220000001b50000000000000000fb0000004c007200710074005f0063006f006e0073006f006c0065005f005f0043006f006e0073006f006c0065005f005f0031005f005f0043006f006e0073006f006c006500570069006400670065007401000002fd000002920000019500fffffffb00000062007200710074005f0072006f0062006f0074005f006d006f006e00690074006f0072005f005f0052006f0062006f0074004d006f006e00690074006f0072005f005f0031005f005f0052006f0062006f00740020004d006f006e00690074006f00720100000427000000d20000000000000000fb00000078007200710074005f00720075006e00740069006d0065005f006d006f006e00690074006f0072005f005f00520075006e00740069006d0065004d006f006e00690074006f0072005f005f0031005f005f00520075006e00740069006d0065004d006f006e00690074006f0072005700690064006700650074010000038e0000016b0000000000000000fb0000004c007200710074005f0074006f007000690063005f005f0054006f0070006900630050006c007500670069006e005f005f0031005f005f0054006f00700069006300570069006400670065007401000003750000021a0000000000000000fb0000004c007200710074005f00740066005f0074007200650065005f005f0052006f0073005400660054007200650065005f005f0031005f005f0052006f00730054006600540072006500650055006901000003ca000001c50000000000000000fb00000050007200710074005f0070006f00730065005f0076006900650077005f005f0050006f007300650056006900650077005f005f0031005f005f0047004c005600690065007700570069006400670065007401000004da000000b50000000000000000fb00000042007200710074005f006e00610076005f0076006900650077005f005f004e0061007600690067006100740069006f006e0056006900650077005f005f0031005f005f01000004a9000000e600000000000000000000058f0000000000000004000000040000000800000008fc00000001000000030000000100000036004d0069006e0069006d0069007a006500640044006f0063006b00570069006400670065007400730054006f006f006c0062006100720000000000ffffffff0000000000000000')\", \n          \"pretty-print\": \"                 Brqt_plot__Plot__1__DataPlotWidget          Brqt_plot__Plot__2__DataPlotWidget          Drqt_graph__RosGraph__1__RosGraphUi          Prqt_dep__RosPackGraph__1__RosPackGraphUi          \\\"rqt_top__TOP__1__          frqt_logger_level__LoggerLevel__1__LoggerLevelWidget          Lrqt_console__Console__1__ConsoleWidget          brqt_robot_monitor__RobotMonitor__1__Robot Monitor          xrqt_runtime_monitor__RuntimeMonitor__1__RuntimeMonitorWidget          Lrqt_topic__TopicPlugin__1__TopicWidget          Lrqt_tf_tree__RosTfTree__1__RosTfTreeUi          Prqt_pose_view__PoseView__1__GLViewWidget          Brqt_nav_view__NavigationView__1__                            6MinimizedDockWidgetsToolbar        \"\n        }\n      }, \n      \"groups\": {\n        \"toolbar_areas\": {\n          \"keys\": {\n            \"MinimizedDockWidgetsToolbar\": {\n              \"type\": \"repr\", \n              \"repr\": \"8\"\n            }\n          }, \n          \"groups\": {}\n        }\n      }\n    }\n  }\n}"
  },
  {
    "path": "ros_ws/src/crazyswarm/launch/test.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 89\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n      Splitter Ratio: 0.5\n    Tree Height: 348\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: PointCloud\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        cf36:\n          Value: true\n        cf37:\n          Value: true\n        cf38:\n          Value: true\n        cf39:\n          Value: true\n        cf40:\n          Value: true\n        cf41:\n          Value: true\n        cf42:\n          Value: true\n        world:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        world:\n          cf36:\n            {}\n          cf37:\n            {}\n          cf38:\n            {}\n          cf39:\n            {}\n          cf40:\n            {}\n          cf41:\n            {}\n          cf42:\n            {}\n      Update Interval: 0\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/PointCloud\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: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: PointCloud\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0199999996\n      Style: Spheres\n      Topic: /pointCloud\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: world\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 8.83146\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0.732263565\n        Y: -0.013760739\n        Z: -0.270162851\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 0.695397973\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 3.13357997\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: true\n  Height: 1160\n  Hide Left Dock: true\n  Hide Right Dock: true\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a000003e9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006f00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000041000003e9000000f300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003e9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000041000003e9000000bb00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000027c0000003efc0100000002fb0000000800540069006d006501000000000000027c0000027600fffffffb0000000800540069006d006501000000000000045000000000000000000000027c000003e900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: true\n  Width: 636\n  X: 640\n  Y: 18\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/backgroundComputation.py",
    "content": "#!/usr/bin/env python\n\n\"\"\"Demonstrate running a slow computation without blocking the main thread.\n\nComputations that take more than a few milliseconds, such as multi-robot\nplanning algorithms, often cannot run in the main script thread:\n\n1. In simulation, the 3d graphics will not update during a blocking call.\n2. In a streaming setpoint mode such as cmdVelocityWorld, the hardware expects\n   to receive setpoints several times per second, even if the setpoint is\n   constant.\n\nTherefore, we must run the computations in a separate thread or process while\nthe main thread (1) allows the visualizer to update, and/or (2) sends a\nsetpoint on the radio.\n\nDue to the global interpreter lock (GIL) in CPython, it's better to use\nprocesss instead of threads. We illustrate one method here, including passing\narguments to the long-running function and receiving outputs using a queue.\n\"\"\"\n\nfrom __future__ import print_function\nimport multiprocessing\nimport time\n\nimport numpy as np\n\nfrom pycrazyswarm import *\n\n\ncrazyflies_yaml = \"\"\"\ncrazyflies:\n- channel: 100\n  id: 1\n  initialPosition: [1.0, 0.0, 0.0]\n\"\"\"\n\nZ = 1.0  # Altitude.\n\n\ndef slow(output_queue, seconds):\n    time.sleep(seconds)\n    queue.put(\"OK\")\n\n\nif __name__ == \"__main__\":\n\n    # The amount of time the slow computation will take. Also demonstrates how\n    # to pass args.\n    computation_time = 4.0\n\n    # The queue is used to get outputs back from the background process.\n    queue = multiprocessing.Queue()\n\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml)\n    timeHelper = swarm.timeHelper\n    cf = swarm.allcfs.crazyflies[0]\n\n    # Demonstration using high-level commands: timeHelper.sleep loops for us.\n    p = multiprocessing.Process(target=slow, args=(queue, computation_time))\n    p.start()\n    print(\"first process started.\")\n    cf.takeoff(targetHeight=Z, duration=2.0)\n    timeHelper.sleep(3.0)\n    p.join()\n    print(\"result:\", queue.get())\n\n    # Demonstration using low-level setpoints.\n    p = multiprocessing.Process(target=slow, args=(queue, computation_time))\n    p.start()\n    print(\"second process started\")\n\n    t0 = timeHelper.time()\n    while p.is_alive():\n        t = timeHelper.time() - t0\n        x = np.cos(t)\n        y = np.sin(t)\n        cf.cmdPosition([x, y, Z], yaw=0.0)\n        timeHelper.sleep(timeHelper.dt)\n\n    print(\"result:\", queue.get())\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/cmdVelocityCircle.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\nfrom pycrazyswarm import *\n\n\nZ = 1.0\nsleepRate = 30\n\n\ndef goCircle(timeHelper, cf, totalTime, radius, kPosition):\n        startTime = timeHelper.time()\n        pos = cf.position()\n        startPos = cf.initialPosition + np.array([0, 0, Z])\n        center_circle = startPos - np.array([radius, 0, 0])\n        while True:\n            time = timeHelper.time() - startTime\n            omega = 2 * np.pi / totalTime\n            vx = -radius * omega * np.sin(omega * time)  \n            vy = radius * omega * np.cos(omega * time)\n            desiredPos = center_circle + radius * np.array(\n                [np.cos(omega * time), np.sin(omega * time), 0])\n            errorX = desiredPos - cf.position() \n            cf.cmdVelocityWorld(np.array([vx, vy, 0] + kPosition * errorX), yawRate=0)\n            timeHelper.sleepForRate(sleepRate)\n\n\nif __name__ == \"__main__\":\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(2 + Z)\n    goCircle(timeHelper, allcfs.crazyflies[0], totalTime=4, radius=1, kPosition=1)\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/collisionAvoidance.py",
    "content": "\"\"\"Demonstration of Buffered Voronoi Cell collision avoidance algorithm.\"\"\"\n\nfrom __future__ import print_function\nimport argparse\nimport time\n\nimport numpy as np\nimport scipy as sp\nimport scipy.spatial\nimport scipy.optimize\n\nimport pycrazyswarm\nimport pycrazyswarm.util as util\nimport pycrazyswarm.cfsim.cffirmware as firm\n\n\nZ = 1.0  # Takeoff altitude.\n\n\ndef main():\n\n    # Crazyswarm's inner parser must add help to get all params.\n    parser = argparse.ArgumentParser(add_help=False)\n\n    group = parser.add_argument_group(\"Collision avoidance\", \"\")\n    group.add_argument(\n        \"--noavoid\",\n        help=\"Disable collision avoidance.\",\n        action=\"store_true\"\n    )\n    group.add_argument(\n        \"--assign\",\n        help=(\"Use optimal start-goal assignment instead of random assignment.\"),\n        action=\"store_true\"\n    )\n    group.add_argument(\n        \"--loops\",\n        type=int,\n        default=1,\n        help=\"Repeat the experiment this many times, without resetting start positions.\",\n    )\n    args, unknown = parser.parse_known_args()\n\n    if args.assign:\n        duration = 3.0\n    else:\n        duration = 10.0\n\n    # Construct the Crazyswarm objects.\n    rows, cols = 3, 5\n    N = rows * cols\n    crazyflies_yaml = util.grid_yaml(rows, cols, spacing=0.5)\n    swarm = pycrazyswarm.Crazyswarm(crazyflies_yaml=crazyflies_yaml, parent_parser=parser)\n    timeHelper = swarm.timeHelper\n    cfs = swarm.allcfs.crazyflies\n\n    # Tell the visualizer to draw collision volume ellipsoids. Ellipsoids\n    # change from green to red when a collision occurs. Make the radii slightly\n    # smaller than the radii used for the collision avoidance algorithm as a\n    # fudge factor.\n    #\n    # To show collisions on purpose, use --noavoid without --assign.\n    xy_radius = 0.125\n    radii = 1.0 * xy_radius * np.array([1.0, 1.0, 3.0])\n    timeHelper.visualizer.showEllipsoids(0.95 * radii)\n\n    swarm.allcfs.takeoff(targetHeight=Z, duration=Z+1.0)\n    timeHelper.sleep(Z + 2.0)\n\n    if not args.noavoid:\n        for i, cf in enumerate(cfs):\n            others = cfs[:i] + cfs[(i+1):]\n            cf.enableCollisionAvoidance(others, radii)\n\n    for _ in range(args.loops):\n        # Goals are randomly positioned in the XY plane, with some random\n        # perturbations in Z. If we didn't add the perturbations, we'd get purely\n        # 2D movement that doesn't take advantage of the free space in the Z axis\n        # to reduce conflicts.\n        #\n        # A more robust solution would be to add some random bias direction to each\n        # robot's reference direction, so it will have a preferred altitude when\n        # far away from the goal, giving Z separation even when the starts and\n        # goals are all coplanar.\n        #\n        # Minimum goal distance of 5*radius ensures that robots are never trying to\n        # squeeze too tightly in between two other robots.\n        #\n        goals = util.poisson_disk_sample(N, dim=2, mindist=5*xy_radius)\n        goals_z = Z * np.ones(N) + 0.2 * np.random.uniform(-1.0, 1.0, size=N)\n        goals = np.hstack([goals, goals_z[:,None]])\n\n        starts = np.stack([cf.position() for cf in cfs])\n        starts[:, 2] += Z\n\n        all_pts = np.vstack([goals, starts])\n        bbox_min = np.amin(all_pts, axis=0) - 4.0 * xy_radius\n        bbox_max = np.amax(all_pts, axis=0) + 4.0 * xy_radius\n\n        # Optimal assignment with sum of Euclidean distances objective guarantees\n        # no collisions when following straight-line trajectories IF the robots\n        # have no volume. If not, collisions may occur, but they are rare in\n        # practice if the start and goal positions are sufficiently dispersed and\n        # not collinear.\n        #\n        # Since we have our own collision avoidance, we use squared Euclidean\n        # distance instead. Minimizing sum of squared distances is closer to\n        # minimizing the # maximum distance for any robot, which generally is more\n        # important in multi-robot applications. We could use e.g. Euclidean^4 to\n        # approximate maximum distance even more closely.\n        #\n        if args.assign:\n            dists = sp.spatial.distance.cdist(starts, goals, \"sqeuclidean\")\n            _, assignments = sp.optimize.linear_sum_assignment(dists)\n            goals = goals[assignments,:]\n\n        for goal, cf in zip(goals, cfs):\n            cf.goTo(goal, yaw=0.0, duration=duration)\n        timeHelper.sleep(duration + 1.0)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/collisionAvoidanceHighConflict.py",
    "content": "\"\"\"Worst-case test of Buffered Voronoi Cell collision avoidance algorithm.\n\nComputes the center of all initial positions, and tells each robot to go straight across the center. Many are forced to wait. This stresses two components of the collision avoidance algorithm:\n\n- Dealing with full \"deadlocks\" that require a sidestep maneuver\n- Handling situations when the goals are far away from the current positions.\n\nAlso will cause high-gain controllers without proper windup handling to fail.\n\"\"\"\n\nfrom __future__ import print_function\nimport argparse\n\nimport numpy as np\n\nimport pycrazyswarm\n\n\nZ = 1.0  # Takeoff altitude.\nduration = 6.0  # Duration of all goTos.\n\n\ndef positionGoTo(timeHelper, cfs, goals, kp=1.0, velMax=0.5):\n    while True:\n        positions = np.row_stack([cf.position() for cf in cfs])\n        errors = positions - goals\n\n        # Check stopping criterion.\n        distances = np.linalg.norm(errors, axis=1)\n        assert len(distances) == len(cfs)\n        if np.all(distances < 0.1):\n            break\n\n        # Command direct to goal.\n        # Rely on BVCA algorithm and controller to not be too aggressive.\n        for cf, goal in zip(cfs, goals):\n            cf.cmdPosition(goal, yaw=0)\n\n        timeHelper.sleepForRate(30)\n\n\ndef velocityGoTo(timeHelper, cfs, goals, kp=2.0, velMax=0.5):\n    while True:\n        positions = np.row_stack([cf.position() for cf in cfs])\n        errors = positions - goals\n\n        # Check stopping criterion.\n        distances = np.linalg.norm(errors, axis=1)\n        assert len(distances) == len(cfs)\n        if np.all(distances < 0.1):\n            break\n\n        # Compute P-only linear position control law.\n        # Rely on BVCA algorithm and controller to not be too aggressive.\n        velocities = -kp * errors\n        for cf, vel in zip(cfs, velocities):\n            cf.cmdVelocityWorld(vel, yawRate=0)\n\n        timeHelper.sleepForRate(30)\n\n\ndef main():\n    # Crazyswarm's inner parser must add help to get all params.\n    parser = argparse.ArgumentParser(add_help=False)\n    group = parser.add_argument_group(\"Collision avoidance\", \"\")\n    group.add_argument(\n        \"--mode\",\n        help=\"Control mode to use.\",\n        choices=[\"goto\", \"velocity\", \"position\"],\n        default=\"goto\",\n    )\n    args, unknown = parser.parse_known_args()\n\n    swarm = pycrazyswarm.Crazyswarm(parent_parser=parser)\n    timeHelper = swarm.timeHelper\n    cfs = swarm.allcfs.crazyflies\n\n    xy_radius = 0.3\n    radii = xy_radius * np.array([1.0, 1.0, 3.0])\n\n    for i, cf in enumerate(cfs):\n        others = cfs[:i] + cfs[(i+1):]\n        cf.enableCollisionAvoidance(others, radii)\n\n    # Everyone will go straight across the center, causing many conflicts.\n    initialPositions = np.row_stack([cf.initialPosition for cf in cfs])\n    initialPositions[:,2] = Z\n    center = np.mean(initialPositions, axis=0)\n    goals = center + (center - initialPositions)\n\n    swarm.allcfs.takeoff(targetHeight=Z, duration=Z+1.0)\n    timeHelper.sleep(Z + 2.0)\n\n    if args.mode == \"goto\":\n        for goal, cf in zip(goals, cfs):\n            cf.goTo(goal, yaw=0.0, duration=duration)\n        timeHelper.sleep(duration + 1.0)\n        for cf in cfs:\n            cf.goTo(cf.initialPosition + [0.0, 0.0, Z], yaw=0.0, duration=duration)\n        timeHelper.sleep(duration + 1.0)\n\n    elif args.mode == \"velocity\":\n        velocityGoTo(timeHelper, cfs, goals)\n        velocityGoTo(timeHelper, cfs, initialPositions)\n        for cf in cfs:\n            cf.notifySetpointsStop()\n\n    elif args.mode == \"position\":\n        positionGoTo(timeHelper, cfs, goals)\n        positionGoTo(timeHelper, cfs, initialPositions)\n        for cf in cfs:\n            cf.notifySetpointsStop()\n\n    else:\n        raise ValueError(\"--mode {} not understood.\".format(args.mode))\n\n    for cf in cfs:\n        cf.disableCollisionAvoidance()\n\n    swarm.allcfs.land(targetHeight=0.04, duration=Z+1.0)\n    timeHelper.sleep(Z + 2.0)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/conftest.py",
    "content": "import subprocess\n\nimport pytest\n\n\nHAVE_ROS = subprocess.call(\"type roslaunch\", shell=True) == 0\n\n\ndef pytest_runtest_setup(item):\n    markers = [mark.name for mark in item.iter_markers()]\n    if \"ros\" in markers and not HAVE_ROS:\n        pytest.skip(\"ROS is not installed.\")\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing2_pps/pp1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.000000,0.000000,0.000000,0.000000,0.049761,-0.053341,0.024521,-0.004466,0.000000,0.000000,0.000000,0.000000,-0.047980,0.053167,-0.024798,0.004559,0.000000,0.000000,0.000000,0.000000,0.069667,-0.076972,0.035856,-0.006587,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.016474,0.048198,0.039172,-0.000273,-0.005454,0.004504,-0.001889,0.000335,-0.015051,-0.042957,-0.032434,0.003363,0.005455,-0.004616,0.001972,-0.000355,0.021964,0.062835,0.047796,-0.004475,-0.007894,0.006667,-0.002844,0.000510,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.101065,0.117430,0.029351,-0.003128,0.000437,-0.000302,0.000117,-0.000020,-0.084623,-0.089646,-0.013642,0.006053,-0.000454,0.000322,-0.000137,0.000028,0.124559,0.133272,0.021741,-0.008390,0.000650,-0.000468,0.000193,-0.000036,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.244950,0.167544,0.020896,-0.002771,-0.000028,0.000016,-0.000006,0.000001,-0.182098,-0.099602,0.003542,0.005686,0.000068,0.000014,0.000092,-0.000042,0.271520,0.152748,-0.002072,-0.007870,-0.000054,0.000058,-0.000071,0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.430603,0.200965,0.012511,-0.002802,0.000001,-0.000001,0.000001,-0.000000,-0.272340,-0.074859,0.021650,0.006472,0.000050,-0.000875,-0.000593,0.000129,0.414281,0.124796,-0.026026,-0.008149,-0.000050,-0.000115,0.000389,-0.000070,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.641278,0.217586,0.004114,-0.002794,0.000004,-0.000001,0.000000,-0.000000,-0.320367,-0.018982,0.026409,-0.009451,-0.008727,0.016363,-0.005650,0.000088,0.505056,0.049365,-0.047560,-0.004173,0.002756,-0.000776,0.000254,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.860186,0.217442,-0.004251,-0.002782,0.000004,-0.000001,-0.000000,0.000000,-0.320317,0.019106,0.026420,0.009345,-0.008589,0.001584,0.000401,-0.000152,0.504923,-0.049598,-0.047469,0.004210,0.002723,-0.000742,-0.000098,0.000069,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.070598,0.200603,-0.012586,-0.002778,-0.000001,0.000002,-0.000001,0.000001,-0.272202,0.074892,0.021595,-0.006457,0.000036,0.000335,-0.000215,0.000045,0.414017,-0.124831,-0.025944,0.008132,-0.000049,-0.000099,0.000084,-0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.255837,0.167102,-0.020902,-0.002748,0.000028,-0.000026,0.000025,-0.000020,-0.181970,0.099560,0.003519,-0.005678,0.000069,-0.000082,0.000058,-0.000028,0.271288,-0.152664,-0.002034,0.007857,-0.000053,0.000064,-0.000058,0.000036,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.399295,0.117044,-0.029288,-0.003104,-0.000435,0.000194,-0.000451,0.000333,-0.084552,0.089580,-0.013641,-0.006045,-0.000453,0.000229,-0.000509,0.000354,0.124434,-0.133153,0.021738,0.008376,0.000649,-0.000323,0.000728,-0.000510,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.483590,0.048016,-0.039034,-0.000260,0.005431,-0.000009,0.006714,-0.004447,-0.015037,0.042918,-0.032407,-0.003357,0.005450,-0.000120,0.007108,-0.004555,0.021940,-0.062767,0.047748,0.004465,-0.007885,0.000160,-0.010239,0.006579,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing2_pps/pp2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.500000,0.000000,0.000000,0.000000,-0.049660,0.053230,-0.024469,0.004457,0.000000,0.000000,0.000000,0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000016,-0.000019,0.000009,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.483558,-0.048107,-0.039103,0.000267,0.005443,-0.004494,0.001885,-0.000334,0.000000,0.000000,0.000000,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000005,0.000014,0.000010,-0.000002,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.399114,-0.117238,-0.029319,0.003116,-0.000436,0.000301,-0.000117,0.000020,0.000000,0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000026,0.000026,0.000002,-0.000002,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.255442,-0.167324,-0.020899,0.002760,0.000028,-0.000016,0.000006,-0.000001,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,-0.000000,0.000000,0.000052,0.000025,-0.000003,-0.000001,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.069996,-0.200783,-0.012548,0.002790,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,-0.000000,0.000073,0.000017,-0.000005,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.859453,-0.217513,-0.004182,0.002788,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,-0.000000,-0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000084,0.000006,-0.000006,-0.000000,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.640547,-0.217513,0.004182,0.002788,-0.000000,0.000000,-0.000000,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000084,-0.000006,-0.000006,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.430004,-0.200783,0.012548,0.002790,0.000001,-0.000002,0.000001,-0.000001,0.000000,-0.000000,-0.000000,0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000072,-0.000017,-0.000005,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.244558,-0.167324,0.020899,0.002760,-0.000028,0.000026,-0.000025,0.000020,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000051,-0.000024,-0.000002,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.100886,-0.117238,0.029319,0.003116,0.000436,-0.000195,0.000452,-0.000334,0.000000,-0.000000,0.000000,0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000025,-0.000025,0.000002,0.000002,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.016442,-0.048107,0.039103,0.000267,-0.005443,0.000009,-0.006729,0.004457,0.000000,-0.000000,0.000000,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000005,-0.000013,0.000009,0.000002,-0.000002,0.000000,-0.000002,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing4_pps/pp1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.000000,0.000000,0.000000,0.000000,0.074358,-0.080059,0.036875,-0.006725,1.000000,0.000000,0.000000,0.000000,0.008664,-0.009525,0.004428,-0.000812,0.000000,0.000000,0.000000,0.000000,-0.002250,0.002432,-0.001121,0.000205,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.024449,0.071312,0.057458,-0.001035,-0.008190,0.006785,-0.002853,0.000506,1.002754,0.007908,0.006087,-0.000474,-0.000977,0.000822,-0.000349,0.000063,-0.000734,-0.002134,-0.001699,0.000059,0.000255,-0.000206,0.000087,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.148433,0.170714,0.040898,-0.005289,0.000657,-0.000457,0.000177,-0.000031,1.015833,0.017204,0.003094,-0.000964,0.000079,-0.000056,0.000022,-0.000004,-0.004388,-0.004952,-0.001072,0.000218,-0.000011,0.000014,-0.000005,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.355103,0.237838,0.026423,-0.004755,-0.000042,0.000021,-0.000004,-0.000000,1.035207,0.020639,0.000363,-0.000904,-0.000006,0.000000,0.000002,-0.000001,-0.010196,-0.006442,-0.000402,0.000244,0.000014,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.614583,0.276330,0.012050,-0.004802,-0.000006,0.000018,-0.000035,0.000012,1.055300,0.018635,-0.002373,-0.000922,-0.000014,0.000016,-0.000030,0.000012,-0.016782,-0.006455,0.000422,0.000310,0.000023,-0.000003,0.000010,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.898151,0.285966,-0.002481,-0.004923,-0.000019,-0.000075,0.000229,-0.000047,1.070624,0.011048,-0.005271,-0.001012,0.000025,-0.000068,0.000233,-0.000071,-0.022479,-0.004567,0.001544,0.000466,0.000055,0.000032,-0.000055,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.176801,0.266828,-0.015668,-0.002815,0.001396,-0.000316,-0.000097,0.000046,1.075508,-0.001869,-0.006837,0.000571,0.000681,-0.000534,0.000198,-0.000030,-0.025000,-0.000002,0.002850,0.000043,-0.000473,0.000100,0.000060,-0.000024,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.426175,0.230793,-0.019379,-0.000710,-0.000018,-0.000060,0.000048,-0.000012,1.067689,-0.012797,-0.004037,0.000863,-0.000073,0.000035,-0.000009,0.000001,-0.022446,0.004625,0.001530,-0.000503,0.000072,0.000015,-0.000022,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.636839,0.189744,-0.021735,-0.000825,-0.000006,0.000013,-0.000008,0.000002,1.051672,-0.018444,-0.001647,0.000777,-0.000001,-0.000000,-0.000000,0.000000,-0.016723,0.006449,0.000397,-0.000299,0.000023,-0.000009,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.804023,0.143807,-0.024188,-0.000797,0.000021,-0.000018,0.000016,-0.000013,1.032357,-0.019413,0.000674,0.000767,-0.000006,0.000005,-0.000005,0.000003,-0.010157,0.006415,-0.000403,-0.000240,0.000012,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.922850,0.093034,-0.026678,-0.001046,-0.000300,0.000126,-0.000296,0.000227,1.014382,-0.015768,0.002989,0.000819,0.000071,-0.000034,0.000078,-0.000056,-0.004373,0.004933,-0.001066,-0.000217,-0.000012,0.000009,-0.000021,0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.987916,0.035776,-0.030046,0.001017,0.003816,0.000037,0.004573,-0.003089,1.002481,-0.007141,0.005535,0.000379,-0.000873,0.000014,-0.001119,0.000725,-0.000732,0.002127,-0.001694,-0.000060,0.000254,-0.000002,0.000310,-0.000204,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing4_pps/pp2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,2.000000,0.000000,0.000000,0.000000,-0.085060,0.091827,-0.042346,0.007729,1.000000,0.000000,0.000000,0.000000,-0.011426,0.012606,-0.005869,0.001078,0.000000,0.000000,0.000000,0.000000,0.117649,-0.129952,0.060532,-0.011120,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.972150,-0.081078,-0.064972,0.001623,0.009397,-0.007800,0.003285,-0.000584,0.996389,-0.010343,-0.007897,0.000701,0.001295,-0.001099,0.000475,-0.000087,0.037110,0.106192,0.080846,-0.007468,-0.013318,0.011253,-0.004802,0.000862,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.832020,-0.191942,-0.044705,0.006483,-0.000755,0.000524,-0.000202,0.000035,0.979435,-0.022104,-0.003710,0.001352,-0.000116,0.000142,-0.000109,0.000031,0.210676,0.225702,0.037151,-0.014062,0.001100,-0.000796,0.000334,-0.000064,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.601458,-0.263273,-0.026848,0.005877,0.000050,-0.000002,-0.000015,0.000005,0.954921,-0.025655,0.000093,0.001218,0.000046,-0.000493,0.000552,-0.000151,0.460042,0.259795,-0.002727,-0.013177,-0.000104,0.000136,-0.000187,0.000061,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.317250,-0.299209,-0.009069,0.005918,-0.000020,-0.000226,0.000179,-0.000040,0.930531,-0.021843,0.004198,0.002223,0.000573,0.004004,-0.003664,0.000785,0.703838,0.214378,-0.043047,-0.013837,-0.000090,-0.000364,0.001110,-0.000225,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.014784,-0.300010,0.008143,0.005743,0.000120,0.000148,-0.000302,0.000040,0.916807,-0.000954,0.015873,-0.001243,-0.006882,0.001496,0.002684,-0.001162,0.861762,0.089675,-0.076816,-0.003512,0.006868,-0.001569,-0.000392,0.000211,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.728666,-0.266808,0.023876,0.003050,-0.002283,0.000524,0.000143,-0.000070,0.926617,0.014976,0.001651,-0.000825,0.000169,0.000759,-0.000789,0.000227,0.876227,-0.055746,-0.063297,0.007797,0.000513,-0.000436,0.000200,-0.000039,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.487099,-0.216048,0.025245,-0.000431,0.000030,0.000094,-0.000076,0.000018,0.942785,0.017131,0.000717,-0.000387,0.000081,-0.000186,0.000141,-0.000036,0.765219,-0.158151,-0.039012,0.008115,-0.000041,0.000034,-0.000016,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.295932,-0.166585,0.024325,-0.000239,0.000010,-0.000019,0.000012,-0.000003,0.960245,0.017388,-0.000469,-0.000378,-0.000008,0.000030,-0.000021,0.000005,0.576152,-0.211896,-0.014742,0.008088,0.000006,-0.000008,0.000004,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.153432,-0.118659,0.023588,-0.000262,-0.000015,0.000012,-0.000010,0.000009,0.976791,0.015341,-0.001562,-0.000351,0.000009,-0.000008,0.000006,-0.000003,0.357601,-0.217123,0.009494,0.008038,-0.000051,0.000051,-0.000051,0.000038,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.058094,-0.072265,0.022873,-0.000088,0.000205,-0.000079,0.000190,-0.000152,0.990224,0.011178,-0.002610,-0.000376,-0.000043,0.000020,-0.000047,0.000034,0.157998,-0.174009,0.033847,0.008659,0.000776,-0.000373,0.000853,-0.000606,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.008779,-0.026278,0.022718,-0.001563,-0.002648,-0.000056,-0.003070,0.002117,0.998380,0.004716,-0.003782,-0.000091,0.000546,-0.000003,0.000683,-0.000449,0.027145,-0.078221,0.060826,0.003892,-0.009498,0.000145,-0.012184,0.007895,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing4_pps/pp3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.000000,0.000000,0.000000,0.000000,0.016259,-0.018257,0.008563,-0.001580,0.000000,0.000000,0.000000,0.000000,-0.014991,0.019018,-0.009348,0.001774,0.000000,0.000000,0.000000,0.000000,0.148973,-0.165605,0.077344,-0.014231,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.004984,0.014067,0.010248,-0.001570,-0.001873,0.001595,-0.000679,0.000121,-0.003547,-0.008546,-0.002733,0.005348,0.001973,-0.001813,0.000811,-0.000150,0.046480,0.132309,0.099085,-0.011379,-0.016991,0.014403,-0.006148,0.001102,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.026892,0.027105,0.002598,-0.002469,0.000140,-0.000071,-0.000030,0.000019,-0.008657,0.004676,0.016041,0.006095,-0.000161,0.000091,0.000033,-0.000021,0.258861,0.271218,0.037953,-0.019703,0.001375,-0.000931,0.000260,-0.000023,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.054185,0.025050,-0.004740,-0.002572,-0.000017,-0.000177,0.000515,-0.000125,0.018098,0.054910,0.034331,0.006295,0.000063,0.000198,-0.000616,0.000128,0.549010,0.290259,-0.018802,-0.019125,-0.000193,-0.000231,0.000901,-0.000174,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.072118,0.009115,-0.009226,0.001522,0.002458,-0.000489,-0.000884,0.000354,0.113407,0.140895,0.049012,0.000674,-0.003717,0.000805,0.000344,-0.000143,0.801646,0.197544,-0.069776,-0.010267,0.006084,-0.001551,0.000088,0.000099,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.074968,-0.000208,-0.000623,0.001182,-0.000849,0.000500,-0.000182,0.000016,0.301277,0.231159,0.038932,-0.004282,0.000448,0.000109,-0.000271,0.000067,0.923867,0.044989,-0.076195,0.003768,0.003099,-0.000982,-0.000007,0.000053,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.074804,0.000215,0.000429,-0.000302,-0.000525,-0.000376,-0.000266,0.000250,0.567438,0.297354,0.027198,-0.004488,-0.000740,0.000144,0.000020,-0.000020,0.898592,-0.088280,-0.055107,0.008055,-0.000070,-0.000075,0.000049,-0.000014,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.074228,-0.003664,-0.006140,-0.002751,0.002339,-0.000247,-0.000293,0.000094,0.886905,0.336028,0.010624,-0.006291,-0.000404,0.000132,-0.000002,-0.000006,0.763150,-0.174786,-0.031666,0.007522,-0.000193,0.000062,-0.000000,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.063566,-0.017176,-0.005248,0.001569,0.000004,-0.000133,0.000091,-0.000021,1.226986,0.337392,-0.009513,-0.006845,0.000007,0.000015,-0.000012,0.000004,0.564085,-0.216037,-0.009705,0.007259,0.000007,0.000001,-0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.042652,-0.023213,-0.000917,0.001349,-0.000022,0.000029,-0.000020,0.000008,1.548034,0.297893,-0.029943,-0.006752,0.000057,-0.000055,0.000053,-0.000041,0.345607,-0.213656,0.012073,0.007225,-0.000047,0.000045,-0.000046,0.000036,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.019865,-0.021008,0.003157,0.001435,0.000108,-0.000055,0.000121,-0.000084,1.809246,0.217734,-0.050474,-0.007451,-0.000861,0.000396,-0.000913,0.000665,0.151236,-0.167826,0.033971,0.007808,0.000729,-0.000347,0.000795,-0.000568,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.003538,-0.010095,0.007612,0.000802,-0.001284,0.000029,-0.001677,0.001074,1.968340,0.092141,-0.073771,-0.001927,0.010694,-0.000068,0.013390,-0.008799,0.025797,-0.074491,0.058285,0.003262,-0.008970,0.000116,-0.011429,0.007430,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/crossing4_pps/pp4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.000000,0.000000,0.000000,0.000000,0.011715,-0.013364,0.006309,-0.001168,2.000000,0.000000,0.000000,0.000000,-0.206797,0.227923,-0.106059,0.019470,0.000000,0.000000,0.000000,0.000000,-0.003633,0.004009,-0.001867,0.000343,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.003491,0.009713,0.006742,-0.001504,-0.001373,0.001181,-0.000505,0.000090,1.934536,-0.187641,-0.143579,0.012292,0.023365,-0.019682,0.008362,-0.001493,-0.001148,-0.003286,-0.002506,0.000227,0.000413,-0.000347,0.000148,-0.000027,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.017836,0.016698,0.000114,-0.002142,0.000102,-0.000046,-0.000037,0.000018,1.626160,-0.403152,-0.069257,0.023915,-0.001873,0.001246,-0.000325,0.000022,-0.006526,-0.006999,-0.001155,0.000442,-0.000029,0.000029,-0.000014,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.032543,0.010586,-0.006325,-0.002286,-0.000036,-0.000162,0.000473,-0.000103,1.176737,-0.472976,-0.000700,0.023154,0.000250,0.000388,-0.001388,0.000283,-0.014249,-0.008012,0.000155,0.000465,0.000033,-0.000017,0.000039,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.034691,-0.007761,-0.010099,0.001783,0.002622,-0.000478,-0.000504,0.000152,0.725748,-0.408319,0.059269,0.010184,-0.008723,0.001994,0.000529,-0.000274,-0.021599,-0.006114,0.001903,0.000774,0.000101,0.000119,-0.000241,0.000060,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.020407,-0.016465,0.001850,0.002755,-0.001987,0.000327,0.000229,-0.000088,0.380408,-0.282896,0.059599,-0.003788,-0.000418,0.000497,-0.000268,0.000057,-0.024997,-0.000014,0.003665,-0.000352,-0.000818,0.000517,-0.000118,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.007029,-0.010051,0.003059,-0.000410,0.000015,0.000106,-0.000082,0.000020,0.153191,-0.175455,0.047881,-0.003846,0.000048,-0.000052,0.000028,-0.000006,-0.022112,0.004899,0.001206,-0.000634,0.000180,-0.000027,-0.000011,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.999686,-0.004924,0.002169,-0.000233,0.000011,-0.000020,0.000012,-0.000003,0.021790,-0.091172,0.036406,-0.003825,-0.000005,0.000005,-0.000003,0.000001,-0.016494,0.005963,0.000051,-0.000237,0.000044,-0.000011,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.996700,-0.001283,0.001467,-0.000238,-0.000002,0.000003,-0.000002,0.000000,-0.036803,-0.029842,0.024923,-0.003829,-0.000000,0.000001,-0.000001,0.000001,-0.010681,0.005492,-0.000465,-0.000120,0.000021,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.996646,0.000937,0.000754,-0.000236,0.000001,-0.000001,0.000001,-0.000001,-0.045550,0.008521,0.013446,-0.003815,0.000013,-0.000015,0.000017,-0.000011,-0.005754,0.004279,-0.000715,-0.000053,0.000013,-0.000002,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.998100,0.001736,0.000042,-0.000246,-0.000013,0.000007,-0.000015,0.000010,-0.027395,0.023968,0.001950,-0.003961,-0.000193,0.000108,-0.000239,0.000158,-0.002232,0.002732,-0.000816,-0.000024,-0.000003,0.000002,-0.000008,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.999622,0.001047,-0.000716,-0.000175,0.000151,-0.000006,0.000207,-0.000128,-0.005605,0.015420,-0.010287,-0.002913,0.002283,-0.000104,0.003159,-0.001953,-0.000343,0.001022,-0.000872,0.000046,0.000107,0.000001,0.000124,-0.000085,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/csv_sequence.py",
    "content": "#!/usr/bin/env python\n\nfrom __future__ import print_function\n\nimport argparse\nimport os\nimport os.path\n\nimport numpy as np\nimport csv\n\nfrom pycrazyswarm import *\nimport uav_trajectory\n\nimport pycrazyswarm.cfsim.cffirmware as firm\n\n\ndef main():\n\n    parser = argparse.ArgumentParser(add_help=False)\n    parser.add_argument(\"path\",\n        type=str,\n        help=\"directory containing numbered subdirectories for each robot,\" +\n            \"each of which contains numbered <n>.csv files for each formation change\")\n    swarm = Crazyswarm(parent_parser=parser)\n    args, unknown = parser.parse_known_args()\n\n    #\n    # DATA LOADING\n    #\n    folder_path = os.path.split(args.path)[0]\n    print(\"folder_path:\", folder_path)\n\n    # ...capability matrices...\n    with open(os.path.join(folder_path, \"Capability_matrices.csv\")) as f:\n        read_data = csv.reader(f, delimiter=\",\")\n        data = list(read_data)\n        C_matrices = np.array(data).astype(\"int\")\n\n    # ...simulation parameters...\n    with open(os.path.join(folder_path, \"sim_parameter.txt\")) as f:\n        lines = [line.rstrip('\\n') for line in f]\n        n = int(lines[0])\n        r = int(lines[1])\n\n    # ...trajectory sequences...\n    root = args.path\n    robot_dirs = sorted(os.listdir(root), key=int)\n    seqs = [load_all_csvs(os.path.join(root, d)) for d in robot_dirs]\n    N = len(robot_dirs)\n    steps = len(seqs[0])\n    assert C_matrices.shape[0] == steps + 2, \"capabilities / trajs mismatch\"\n\n    print(\"loading complete\")\n\n    #\n    # DATA VALIDATION / PROCESSING\n    #\n\n    # transpose / reshape capabilities to (time, robot, capability)\n    C_matrices = C_matrices.reshape((r, n, -1)).transpose([2, 1, 0])\n    # lower brightness\n    C_matrices = 0.6 * C_matrices\n\n    # validate sequences w.r.t. each other\n    assert all(len(seq) == steps for seq in seqs)\n    for i in range(steps):\n        agent_lens = [seq[i].duration for seq in seqs]\n        assert all(agent_lens == agent_lens[0])\n    step_lens = [t.duration for t in seqs[0]]\n\n    print(\"validation complete\")\n\n    #\n    # CRAZYSWARM INITIALIZATION\n    #\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n    crazyflies = allcfs.crazyflies\n\n    # support trials on <N robots\n    if len(crazyflies) < N:\n        N = len(crazyflies)\n        seqs = seqs[:N]\n        C_matrices = C_matrices[:,:N,:]\n    print(\"using\", N, \"crazyflies\")\n\n    # transposed copy - by timestep instead of robot\n    seqs_t = zip(*seqs)\n\n    # check that crazyflies.yaml initial positions match sequences.\n    # only compare xy positions.\n    # assume that cf id numerical order matches sequence order,\n    # but id's don't need to be 1..N.\n    crazyflies = sorted(crazyflies, key=lambda cf: cf.id)\n    init_positions = np.stack([cf.initialPosition for cf in crazyflies])\n    evals = [seq[0].eval(0.0).pos for seq in seqs]\n    traj_starts = np.stack(evals)\n    errs = init_positions - traj_starts\n    errnorms = np.linalg.norm(errs[:,:2], axis=1)\n    assert not np.any(np.abs(errnorms) > 0.1)\n\n    # planners for takeoff and landing\n    planners = [firm.planner() for cf in crazyflies]\n    for p in planners:\n        firm.plan_init(p)\n\n    #\n    # ASSORTED OTHER SETUP\n    #\n\n    # local helper fn to set colors\n    def set_colors(i):\n        for cf, color in zip(crazyflies, C_matrices[i]):\n            cf.setLEDColor(*color)\n\n    # timing parameters\n    timescale = 1.0\n    pause_between = 1.5\n    takeoff_time = 3.0\n    land_time = 4.0\n\n    #\n    # RUN DEMO\n    #\n\n    print(\"validation complete\")\n\n    # takeoff\n    print(\"takeoff\")\n    z_init = traj_starts[0,2]\n\n    for cf, p in zip(crazyflies, planners):\n        p.lastKnownPosition = cf.position()\n        vposition = firm.mkvec(*p.lastKnownPosition)\n        firm.plan_takeoff(p, vposition, 0.0, z_init, takeoff_time, 0.0)\n\n    poll_planners(crazyflies, timeHelper, planners, takeoff_time)\n    end_pos = np.stack([cf.position() for cf in crazyflies])\n\n    # set to full capability colors\n    set_colors(0)\n\n    # pause - all is well...\n    hover(crazyflies, timeHelper, end_pos, pause_between)\n\n    # set colors first capability loss\n    set_colors(1)\n\n    # pause - reacting to capability loss\n    hover(crazyflies, timeHelper, end_pos, pause_between)\n\n    # main loop!\n    for step in range(steps):\n\n        # move - new configuration after capability loss\n        print(\"executing trajectory\", step, \"/\", steps)\n        poll_trajs(crazyflies, timeHelper, seqs_t[step], timescale)\n        end_pos = np.stack([cf.position() for cf in crazyflies])\n\n        # done with this step's trajs - hover for a few sec\n        hover(crazyflies, timeHelper, end_pos, pause_between)\n\n        # change the LEDs - another capability loss\n        if step < steps - 1:\n            set_colors(step + 2)\n\n        # hover some more\n        hover(crazyflies, timeHelper, end_pos, pause_between)\n\n    # land\n    print(\"landing\")\n\n    end_pos = np.stack([cf.position() for cf in crazyflies])\n    for cf, p, pos in zip(crazyflies, planners, end_pos):\n        vposition = firm.mkvec(*pos)\n        firm.plan_land(p, vposition, 0.0, 0.06, land_time, 0.0)\n\n    poll_planners(crazyflies, timeHelper, planners, land_time)\n\n    # cut power\n    print(\"sequence complete.\")\n    allcfs.emergency()\n\nPOLL_RATE = 100 # Hz\n\ndef poll_trajs(crazyflies, timeHelper, trajs, timescale):\n    duration = trajs[0].duration\n    start_time = timeHelper.time()\n    while not timeHelper.isShutdown():\n        t = (timeHelper.time() - start_time) / timescale\n        if t > duration:\n            break\n        for cf, traj in zip(crazyflies, trajs):\n            ev = traj.eval(t)\n            cf.cmdFullState(\n                ev.pos,\n                ev.vel,\n                ev.acc,\n                ev.yaw,\n                ev.omega)\n        timeHelper.sleepForRate(POLL_RATE)\n\n\ndef poll_planners(crazyflies, timeHelper, planners, duration):\n    start_time = timeHelper.time()\n    while not timeHelper.isShutdown():\n        t = timeHelper.time() - start_time\n        if t > duration:\n            break\n        for cf, planner in zip(crazyflies, planners):\n            ev = firm.plan_current_goal(planner, t)\n            cf.cmdFullState(\n                ev.pos,\n                ev.vel,\n                ev.acc,\n                ev.yaw,\n                ev.omega)\n        timeHelper.sleepForRate(POLL_RATE)\n\n\ndef hover(crazyflies, timeHelper, positions, duration):\n    start_time = timeHelper.time()\n    zero = np.zeros(3)\n    while not timeHelper.isShutdown():\n        t = timeHelper.time() - start_time\n        if t > duration:\n            break\n        for cf, pos in zip(crazyflies, positions):\n            cf.cmdFullState(\n                pos,\n                zero,\n                zero,\n                0.0,\n                zero)\n        timeHelper.sleepForRate(POLL_RATE)\n\n\ndef load_all_csvs(path):\n    csvs = os.listdir(path)\n    csvs = sorted(csvs, key=lambda s: int(os.path.splitext(s)[0])) # numerical order\n    names, exts = zip(*[os.path.splitext(os.path.basename(f)) for f in csvs])\n    assert all(e == \".csv\" for e in exts)\n    steps = len(names)\n    assert set(names) == set([str(i) for i in range(1, steps + 1)])\n    trajs = [uav_trajectory.Trajectory() for _ in range(steps)]\n    for t, csv in zip(trajs, csvs):\n        t.loadcsv(os.path.join(path, csv))\n    return trajs\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/example_cmd_pos.py",
    "content": "from pycrazyswarm import *\nimport numpy as np\n\nswarm = Crazyswarm()\ntimeHelper = swarm.timeHelper\nallcfs = swarm.allcfs\n\nZ = 0\n# takeoff\nwhile Z < 1.0:\n    for cf in allcfs.crazyflies:\n        pos = np.array(cf.initialPosition) + np.array([0, 0, Z])\n        cf.cmdPosition(pos)\n    timeHelper.sleep(0.1)\n    Z += 0.05\n\n# land\nwhile Z > 0.0:\n    for cf in allcfs.crazyflies:\n        pos = np.array(cf.initialPosition) + np.array([0, 0, Z])\n        cf.cmdPosition(pos)\n    timeHelper.sleep(0.1)\n    Z -= 0.05\n\n# turn-off motors\nfor cf in allcfs.crazyflies:\n    cf.cmdStop()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/graphVisualization.py",
    "content": "#!/usr/bin/env python\n\n\"\"\"Demonstrates the graph visualization feature of the 3D visualizer.\"\"\"\n\nimport numpy as np\n\nfrom pycrazyswarm import *\n\ncrazyflies_yaml = \"\"\"\ncrazyflies:\n- id: 1\n  channel: 110\n  initialPosition: [-1.0, 0.0, 0.0]\n- id: 2\n  channel: 120\n  initialPosition: [-0.5, 0.0, 0.0]\n- id: 3\n  channel: 100\n  initialPosition: [0.0, 0.0, 0.0]\n- id: 4\n  channel: 110\n  initialPosition: [0.5, 0.0, 0.0]\n- id: 5\n  channel: 120\n  initialPosition: [1.0, 0.0, 0.0]\n\"\"\"\n\n# Cycle between pentagon and star to show graph visualization.\nt = np.linspace(0, 2 * np.pi, 6)[:-1]\npositions = np.column_stack([np.cos(t), np.sin(t), np.ones_like(t)])\npermutations = np.stack([np.arange(5), [0, 2, 4, 1, 3]])\ngraph_edges_pentagon = (\n    (0, 1),\n    (1, 2),\n    (2, 3),\n    (3, 4),\n    (4, 0),\n)\ngraph_edges_star = (\n    (0, 2),\n    (0, 3),\n    (1, 3),\n    (1, 4),\n    (2, 4),\n)\n\nif __name__ == \"__main__\":\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml)\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n    visualizer = timeHelper.visualizer\n    visualizer.setGraph(graph_edges_star)\n\n    cfs = allcfs.crazyflies\n\n    allcfs.takeoff(targetHeight=1.0, duration=2.0)\n    timeHelper.sleep(2.5)\n\n    # First, cycle between pentagon and star by moving.\n    n_cycles = 4\n    for cycle in range(n_cycles):\n        for i in range(5):\n            index = permutations[cycle % 2][i]\n            pos = positions[index]\n            cfs[i].goTo(pos, 0, 3.0)\n\n        timeHelper.sleep(6.0)\n\n    # Then, cycle between pentagon and star by changing the graph.\n    edges = (graph_edges_pentagon, graph_edges_star)\n    for cycle in range(n_cycles):\n        visualizer.setGraph(edges[cycle % 2])\n        timeHelper.sleep(6.0)\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/individual_hover.py",
    "content": "#!/usr/bin/env python\n\nfrom __future__ import print_function\n\nfrom pycrazyswarm import *\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    for cf in allcfs.crazyflies:\n        print(cf.id)\n        cf.takeoff(1.0, 2.5)\n        print(\"press button to continue\")\n        swarm.input.waitUntilButtonPressed()\n        cf.land(0.04, 2.5)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/led_colors.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\n\nfrom pycrazyswarm import *\nimport uav_trajectory\n\nif __name__ == \"__main__\":\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    # Configure the CFs so that the LED ring displays the solid color.\n    # Overrides the launch file and the firmware default.\n    for cf in allcfs.crazyflies:\n        cf.setParam(\"ring/effect\", 7)\n\n    # Generate all possible on/off rgb values.\n    rgb_bits = [tuple((x >> k) & 0x1 for k in range(3)) for x in range(8)]\n\n    allcfs.takeoff(targetHeight=1.0, duration=2.0)\n    timeHelper.sleep(2.5)\n\n    TRIALS = 1\n    for i in range(TRIALS):\n        for rgb in rgb_bits:\n            for cf in allcfs.crazyflies:\n                cf.setLEDColor(*rgb)\n            timeHelper.sleep(1.0)\n\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/pytest.ini",
    "content": "[pytest]\nmarkers =\n    ros: tests that can only run when ROS is installed.\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-1.500000,0.000000,0.000000,0.000000,0.017623,-0.018891,0.008684,-0.001582,0.000000,0.000000,0.000000,0.000000,0.009122,-0.009778,0.004495,-0.000819,1.500000,0.000000,0.000000,0.000000,-0.024018,0.025745,-0.011835,0.002156,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.494166,0.017070,0.013874,-0.000096,-0.001931,0.001595,-0.000669,0.000119,0.003020,0.008837,0.007183,-0.000049,-0.001000,0.000826,-0.000346,0.000061,1.492048,-0.023267,-0.018913,0.000129,0.002632,-0.002174,0.000912,-0.000162,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.464205,0.041593,0.010399,-0.001106,0.000155,-0.000107,0.000041,-0.000007,0.018532,0.021536,0.005386,-0.000572,0.000080,-0.000055,0.000021,-0.000004,1.451206,-0.056703,-0.014180,0.001507,-0.000211,0.000146,-0.000056,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.413237,0.059354,0.007409,-0.000979,-0.000010,0.000006,-0.000002,0.000000,0.044924,0.030737,0.003839,-0.000507,-0.000005,0.000003,-0.000001,0.000000,1.381719,-0.080927,-0.010108,0.001335,0.000013,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.347459,0.071215,0.004447,-0.000990,0.000001,-0.000000,0.000000,-0.000000,0.078990,0.036883,0.002305,-0.000513,0.000000,-0.000000,0.000000,-0.000000,1.292027,-0.097110,-0.006069,0.001349,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.272786,0.077142,0.001480,-0.000989,0.000000,-0.000000,0.000000,-0.000000,0.117665,0.039956,0.000768,-0.000512,-0.000000,0.000000,-0.000000,0.000000,1.190197,-0.105201,-0.002023,0.001348,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.195152,0.077137,-0.001485,-0.000988,0.000000,-0.000000,0.000000,-0.000000,0.157877,0.039956,-0.000768,-0.000512,0.000000,-0.000000,0.000000,-0.000000,1.084322,-0.105201,0.002023,0.001348,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.120489,0.071201,-0.004451,-0.000989,-0.000000,0.000001,-0.000000,0.000000,0.196552,0.036882,-0.002305,-0.000513,-0.000000,0.000000,-0.000000,0.000000,0.982493,-0.097110,0.006069,0.001349,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.054729,0.059333,-0.007412,-0.000978,0.000010,-0.000009,0.000009,-0.000007,0.230617,0.030736,-0.003839,-0.000507,0.000005,-0.000005,0.000005,-0.000004,0.892801,-0.080927,0.010108,0.001335,-0.000013,0.000012,-0.000012,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.003783,0.041572,-0.010397,-0.001105,-0.000154,0.000069,-0.000160,0.000118,0.257008,0.021536,-0.005386,-0.000572,-0.000080,0.000036,-0.000083,0.000061,0.823314,-0.056702,0.014180,0.001507,0.000211,-0.000094,0.000219,-0.000162,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.973840,0.017058,-0.013866,-0.000095,0.001930,-0.000003,0.002386,-0.001580,0.272520,0.008837,-0.007183,-0.000049,0.001000,-0.000002,0.001236,-0.000819,0.782472,-0.023267,0.018912,0.000129,-0.002632,0.000004,-0.003254,0.002156,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.314090,0.000000,0.000000,0.000000,-0.031461,0.033971,-0.015667,0.002860,-0.227130,0.000000,0.000000,0.000000,-0.001420,0.001536,-0.000709,0.000130,1.346800,0.000000,0.000000,0.000000,-0.005097,0.005504,-0.002538,0.000463,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.324387,-0.029974,-0.024009,0.000613,0.003476,-0.002886,0.001216,-0.000216,-0.227593,-0.001347,-0.001074,0.000033,0.000157,-0.000131,0.000055,-0.000010,1.345132,-0.004856,-0.003890,0.000099,0.000563,-0.000468,0.000197,-0.000035,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.376168,-0.070898,-0.016477,0.002409,-0.000280,0.000195,-0.000076,0.000013,-0.229909,-0.003158,-0.000718,0.000114,-0.000013,0.000009,-0.000003,0.000001,1.336742,-0.011487,-0.002670,0.000390,-0.000045,0.000032,-0.000012,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.461283,-0.097136,-0.009845,0.002180,0.000017,-0.000011,0.000004,-0.000001,-0.233678,-0.004277,-0.000406,0.000101,0.000000,-0.000001,0.000000,-0.000000,1.322952,-0.015738,-0.001595,0.000353,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.566074,-0.110252,-0.003264,0.002196,-0.000002,0.000000,-0.000000,0.000000,-0.238260,-0.004787,-0.000105,0.000098,-0.000001,-0.000000,0.000000,-0.000000,1.305973,-0.017863,-0.000528,0.000356,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.677395,-0.110196,0.003318,0.002193,-0.000000,-0.000002,0.000001,-0.000001,-0.243055,-0.004707,0.000183,0.000093,-0.000001,-0.000000,0.000000,-0.000000,1.287938,-0.017852,0.000539,0.000355,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.782081,-0.096990,0.009878,0.002169,-0.000019,0.000017,-0.000017,0.000013,-0.247487,-0.004068,0.000453,0.000086,-0.000003,0.000000,-0.000000,0.000000,1.270979,-0.015710,0.001602,0.000351,-0.000003,0.000003,-0.000003,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.867030,-0.070726,0.016468,0.002391,0.000278,-0.000128,0.000295,-0.000215,-0.251018,-0.002910,0.000705,0.000089,0.000010,-0.000005,0.000012,-0.000009,1.257222,-0.011452,0.002668,0.000387,0.000045,-0.000021,0.000048,-0.000035,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.918667,-0.029878,0.023942,0.000600,-0.003463,0.000021,-0.004333,0.002849,-0.253126,-0.001209,0.000977,0.000014,-0.000138,0.000001,-0.000172,0.000113,1.248861,-0.004837,0.003876,0.000096,-0.000560,0.000003,-0.000701,0.000461,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.928930,0.000000,0.000000,0.000000,0.018359,-0.019622,0.009008,-0.001639,-0.253540,0.000000,0.000000,0.000000,0.004469,-0.004774,0.002191,-0.000399,1.247200,0.000000,0.000000,0.000000,0.015019,-0.016055,0.007371,-0.001342,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.922824,0.017899,0.014630,0.000002,-0.002006,0.001652,-0.000692,0.000122,-0.252053,0.004361,0.003568,0.000004,-0.000488,0.000402,-0.000168,0.000030,1.252194,0.014637,0.011960,-0.000003,-0.001641,0.001352,-0.000566,0.000100,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.891215,0.044111,0.011317,-0.001053,0.000160,-0.000110,0.000043,-0.000007,-0.244345,0.010765,0.002772,-0.000253,0.000039,-0.000027,0.000010,-0.000002,1.278033,0.036048,0.009234,-0.000866,0.000131,-0.000090,0.000035,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.836756,0.063878,0.008498,-0.000923,-0.000011,0.000006,-0.000002,0.000000,-0.231040,0.015620,0.002094,-0.000223,-0.000003,0.000001,-0.000001,0.000000,1.322518,0.052156,0.006914,-0.000759,-0.000008,0.000005,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.765309,0.078082,0.005700,-0.000936,-0.000000,-0.000000,-0.000000,0.000000,-0.213551,0.019132,0.001416,-0.000228,-0.000001,0.000000,-0.000000,0.000000,1.380824,0.063690,0.004615,-0.000769,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.682465,0.086670,0.002888,-0.000939,-0.000001,0.000000,-0.000000,0.000000,-0.193230,0.021280,0.000730,-0.000230,-0.000001,0.000000,-0.000000,0.000000,1.448360,0.070613,0.002309,-0.000769,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.593847,0.089625,0.000065,-0.000943,-0.000001,0.000000,-0.000000,0.000000,-0.171452,0.022047,0.000036,-0.000233,-0.000001,0.000000,-0.000000,0.000000,1.520513,0.072924,0.000002,-0.000769,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.505101,0.086921,-0.002772,-0.000948,-0.000001,0.000000,-0.000000,0.000000,-0.149603,0.021418,-0.000666,-0.000235,-0.000001,0.000000,-0.000000,0.000000,1.592671,0.070623,-0.002304,-0.000769,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.421901,0.078526,-0.005626,-0.000954,-0.000002,0.000001,-0.000001,0.000000,-0.129087,0.019378,-0.001375,-0.000238,-0.000001,0.000000,-0.000000,0.000000,1.660220,0.063706,-0.004612,-0.000769,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.349956,0.064410,-0.008488,-0.000948,0.000009,-0.000009,0.000009,-0.000007,-0.111322,0.015914,-0.002088,-0.000236,0.000002,-0.000002,0.000002,-0.000002,1.718546,0.052177,-0.006914,-0.000760,0.000008,-0.000008,0.000007,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.294981,0.044583,-0.011389,-0.001084,-0.000163,0.000072,-0.000168,0.000124,-0.097732,0.011027,-0.002812,-0.000270,-0.000040,0.000018,-0.000042,0.000031,1.763050,0.036065,-0.009237,-0.000867,-0.000131,0.000058,-0.000135,0.000100,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.263005,0.018126,-0.014801,-0.000016,0.002034,-0.000000,0.002505,-0.001663,-0.089820,0.004487,-0.003662,-0.000006,0.000504,-0.000000,0.000621,-0.000412,1.788903,0.014646,-0.011966,-0.000004,0.001642,0.000000,0.002021,-0.001343,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.256820,0.000000,0.000000,0.000000,0.002673,-0.002869,0.001320,-0.000241,-0.088289,0.000000,0.000000,0.000000,0.025135,-0.027029,0.012443,-0.002268,1.793900,0.000000,0.000000,0.000000,-0.040169,0.043197,-0.019886,0.003625,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.255937,0.002580,0.002090,-0.000023,-0.000294,0.000243,-0.000102,0.000018,-0.080009,0.024173,0.019525,-0.000290,-0.002765,0.002288,-0.000962,0.000171,1.780668,-0.038628,-0.031198,0.000467,0.004418,-0.003657,0.001537,-0.000273,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.251425,0.006246,0.001537,-0.000177,0.000023,-0.000016,0.000006,-0.000001,-0.037869,0.058157,0.014105,-0.001729,0.000222,-0.000154,0.000060,-0.000010,1.713334,-0.092923,-0.022530,0.002766,-0.000355,0.000246,-0.000096,0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.243806,0.008830,0.001053,-0.000160,-0.000002,0.000001,-0.000000,0.000000,0.032781,0.081583,0.009387,-0.001549,-0.000014,0.000008,-0.000003,0.000001,1.600460,-0.130330,-0.014984,0.002477,0.000023,-0.000013,0.000005,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.234086,0.010447,0.000561,-0.000167,-0.000001,-0.000000,-0.000000,-0.000000,0.122194,0.095680,0.004703,-0.001565,0.000000,-0.000000,0.000000,-0.000000,1.457637,-0.152817,-0.007493,0.002502,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.223246,0.011063,0.000052,-0.000173,-0.000002,-0.000000,0.000000,-0.000000,0.221013,0.100392,0.000009,-0.001565,-0.000000,-0.000000,-0.000000,-0.000000,1.299827,-0.160302,0.000008,0.002500,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.212305,0.010643,-0.000475,-0.000179,-0.000002,0.000000,0.000000,0.000000,0.319849,0.095713,-0.004689,-0.001567,-0.000001,0.000001,-0.000001,0.000001,1.142033,-0.152787,0.007507,0.002500,0.000001,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.202316,0.009152,-0.001018,-0.000181,0.000001,-0.000001,0.000001,-0.000001,0.409306,0.081636,-0.009382,-0.001552,0.000014,-0.000013,0.000013,-0.000010,0.999251,-0.130281,0.014989,0.002474,-0.000023,0.000021,-0.000021,0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.194363,0.006570,-0.001573,-0.000204,-0.000025,0.000012,-0.000027,0.000020,0.480010,0.058209,-0.014111,-0.001734,-0.000222,0.000101,-0.000233,0.000171,0.886428,-0.092874,0.022524,0.002762,0.000354,-0.000160,0.000371,-0.000272,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.189591,0.002745,-0.002211,-0.000040,0.000315,-0.000001,0.000393,-0.000259,0.522190,0.024199,-0.019544,-0.000293,0.002768,-0.000010,0.003441,-0.002271,0.819134,-0.038603,0.031180,0.000464,-0.004415,0.000016,-0.005488,0.003623,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.188650,0.000000,0.000000,0.000000,-0.007257,0.007812,-0.003598,0.000656,0.530480,0.000000,0.000000,0.000000,-0.036547,0.039308,-0.018097,0.003299,0.805910,0.000000,0.000000,-0.000000,0.034481,-0.037077,0.017068,-0.003112,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.191037,-0.006964,-0.005614,0.000097,0.000799,-0.000662,0.000278,-0.000049,0.518443,-0.035134,-0.028368,0.000434,0.004021,-0.003328,0.001399,-0.000248,0.817270,0.033165,0.026791,-0.000395,-0.003792,0.003139,-0.001319,0.000234,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.203151,-0.016689,-0.004009,0.000512,-0.000065,0.000044,-0.000017,0.000003,0.457218,-0.084470,-0.020453,0.002526,-0.000323,0.000224,-0.000087,0.000015,0.875094,0.079812,0.019368,-0.002369,0.000304,-0.000211,0.000082,-0.000014,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.223372,-0.023290,-0.002614,0.000455,0.000002,-0.000003,0.000001,-0.000000,0.354650,-0.118387,-0.013562,0.002261,0.000019,-0.000012,0.000004,-0.000001,0.972065,0.111994,0.012905,-0.002123,-0.000020,0.000011,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.248821,-0.027156,-0.001256,0.000447,-0.000003,0.000001,-0.000000,0.000000,0.224972,-0.138692,-0.006736,0.002277,-0.000003,0.000000,0.000000,-0.000000,1.094828,0.131389,0.006480,-0.002148,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.276789,-0.028337,0.000070,0.000438,-0.000001,0.000000,-0.000000,0.000000,0.081818,-0.145344,0.000080,0.002267,-0.000003,-0.000000,0.000000,-0.000000,1.230548,0.137902,0.000032,-0.002151,-0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.304619,-0.026887,0.001377,0.000433,-0.000001,-0.000000,0.000000,-0.000000,-0.061182,-0.138394,0.006866,0.002258,-0.000001,-0.000002,0.000001,-0.000001,1.366330,0.131508,-0.006428,-0.002156,-0.000002,0.000002,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.329697,-0.022838,0.002669,0.000425,-0.000005,0.000004,-0.000004,0.000003,-0.190454,-0.117900,0.013615,0.002229,-0.000022,0.000019,-0.000019,0.000015,1.489254,0.112188,-0.012884,-0.002136,0.000019,-0.000018,0.000018,-0.000014,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.349443,-0.016227,0.003960,0.000473,0.000061,-0.000028,0.000064,-0.000047,-0.292516,-0.083982,0.020398,0.002486,0.000320,-0.000145,0.000335,-0.000246,1.586427,0.080006,-0.019390,-0.002385,-0.000305,0.000138,-0.000320,0.000235,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.361187,-0.006727,0.005441,0.000072,-0.000768,0.000003,-0.000953,0.000630,-0.353351,-0.034886,0.028186,0.000409,-0.003988,0.000014,-0.004956,0.003272,1.644405,0.033264,-0.026863,-0.000405,0.003805,-0.000014,0.004731,-0.003123,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.363490,0.000000,0.000000,0.000000,-0.006351,0.006841,-0.003152,0.000575,-0.365300,0.000000,0.000000,-0.000000,0.046869,-0.050397,0.023200,-0.004229,1.655800,0.000000,0.000000,0.000000,-0.021876,0.023532,-0.010835,0.001975,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.365577,-0.006086,-0.004899,0.000093,0.000700,-0.000580,0.000244,-0.000043,-0.349858,0.045081,0.036417,-0.000536,-0.005155,0.004266,-0.001793,0.000318,1.648597,-0.021023,-0.016970,0.000266,0.002407,-0.001993,0.000838,-0.000149,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.376149,-0.014545,-0.003471,0.000456,-0.000056,0.000039,-0.000015,0.000003,-0.271259,0.108489,0.026329,-0.003219,0.000414,-0.000287,0.000112,-0.000019,1.611973,-0.050515,-0.012213,0.001518,-0.000193,0.000134,-0.000052,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.393737,-0.020219,-0.002220,0.000411,0.000004,-0.000002,0.000001,-0.000000,-0.139442,0.152243,0.017550,-0.002882,-0.000026,0.000015,-0.000005,0.000001,1.550661,-0.070737,-0.008068,0.001361,0.000012,-0.000007,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.415764,-0.023420,-0.000979,0.000415,0.000000,0.000000,-0.000000,-0.000000,0.027453,0.178641,0.008836,-0.002911,0.000001,-0.000000,0.000000,-0.000000,1.473225,-0.082764,-0.003953,0.001375,-0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.439748,-0.024134,0.000264,0.000411,-0.000005,-0.000002,0.000000,-0.000000,0.212019,0.187582,0.000106,-0.002911,-0.000002,-0.000001,0.000000,-0.000000,1.387883,-0.086547,0.000168,0.001371,-0.000003,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.463214,-0.022404,0.001444,0.000367,-0.000019,-0.000004,0.000003,-0.000000,0.396794,0.179049,-0.008650,-0.002931,-0.000009,0.000001,-0.000000,0.000001,1.302871,-0.082115,0.004250,0.001344,-0.000012,-0.000004,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.483828,-0.018500,0.002417,0.000286,-0.000014,0.000009,-0.000004,0.000002,0.564254,0.152927,-0.017474,-0.002932,0.000023,-0.000022,0.000024,-0.000019,1.226335,-0.069641,0.008193,0.001282,-0.000019,0.000015,-0.000012,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.499632,-0.012827,0.003267,0.000316,0.000047,-0.000021,0.000048,-0.000036,0.696780,0.109168,-0.026411,-0.003274,-0.000417,0.000189,-0.000437,0.000321,1.166162,-0.049419,0.012083,0.001429,0.000188,-0.000085,0.000196,-0.000144,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.508838,-0.005222,0.004261,0.000008,-0.000587,0.000000,-0.000723,0.000480,0.775918,0.045422,-0.036669,-0.000569,0.005199,-0.000020,0.006466,-0.004267,1.130409,-0.020473,0.016563,0.000212,-0.002335,0.000007,-0.002898,0.001915,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.510620,0.000000,0.000000,0.000000,0.008697,-0.009352,0.004305,-0.000785,0.791480,0.000000,0.000000,0.000000,-0.045367,0.048787,-0.022459,0.004095,1.123400,0.000000,0.000000,0.000000,-0.004625,0.004974,-0.002290,0.000417,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.507755,0.008365,0.006757,-0.000100,-0.000957,0.000792,-0.000333,0.000059,0.776535,-0.043628,-0.035237,0.000526,0.004990,-0.004130,0.001736,-0.000308,1.121877,-0.004446,-0.003590,0.000055,0.000509,-0.000421,0.000177,-0.000031,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.493171,0.020128,0.004884,-0.000598,0.000077,-0.000053,0.000021,-0.000004,0.700484,-0.104955,-0.025450,0.003123,-0.000400,0.000278,-0.000108,0.000019,1.114128,-0.010692,-0.002590,0.000319,-0.000041,0.000028,-0.000011,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.468716,0.028242,0.003253,-0.000536,-0.000005,0.000003,-0.000001,0.000000,0.572991,-0.147213,-0.016929,0.002797,0.000026,-0.000015,0.000005,-0.000001,1.101145,-0.014987,-0.001719,0.000286,0.000002,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.437760,0.033130,0.001632,-0.000542,-0.000000,-0.000000,0.000000,-0.000000,0.411662,-0.172625,-0.008471,0.002825,-0.000001,0.000001,-0.000000,0.000000,1.084726,-0.017562,-0.000856,0.000288,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.403539,0.034769,0.000006,-0.000542,-0.000000,-0.000000,0.000000,-0.000000,0.233391,-0.181095,0.000000,0.002823,-0.000000,0.000000,-0.000000,0.000000,1.066595,-0.018412,0.000006,0.000287,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.369307,0.033153,-0.001622,-0.000543,-0.000000,0.000000,-0.000000,0.000000,0.055119,-0.172625,0.008471,0.002825,0.000001,-0.000002,0.000001,-0.000001,1.048475,-0.017541,0.000865,0.000286,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.338319,0.028280,-0.003249,-0.000538,0.000005,-0.000005,0.000004,-0.000004,-0.106210,-0.147213,0.016929,0.002797,-0.000026,0.000024,-0.000023,0.000019,1.032086,-0.014953,0.001722,0.000283,-0.000003,0.000002,-0.000002,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.313825,0.020166,-0.004888,-0.000601,-0.000077,0.000035,-0.000081,0.000059,-0.233703,-0.104955,0.025449,0.003123,0.000400,-0.000181,0.000420,-0.000308,1.019138,-0.010657,0.002586,0.000316,0.000041,-0.000018,0.000043,-0.000031,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.299212,0.008384,-0.006771,-0.000102,0.000959,-0.000004,0.001192,-0.000787,-0.309755,-0.043628,0.035237,0.000526,-0.004990,0.000018,-0.006203,0.004095,1.011417,-0.004429,0.003577,0.000053,-0.000506,0.000002,-0.000629,0.000416,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.296340,0.000000,0.000000,0.000000,0.024896,-0.026775,0.012327,-0.002247,-0.324700,0.000000,0.000000,0.000000,0.027538,-0.029612,0.013632,-0.002485,1.009900,0.000000,0.000000,0.000000,0.029305,-0.031514,0.014507,-0.002645,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.288140,0.023937,0.019330,-0.000293,-0.002739,0.002267,-0.000953,0.000169,-0.315628,0.026485,0.021394,-0.000317,-0.003029,0.002507,-0.001054,0.000187,1.019554,0.028183,0.022763,-0.000339,-0.003223,0.002668,-0.001121,0.000199,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.246421,0.057564,0.013946,-0.001718,0.000220,-0.000153,0.000059,-0.000010,-0.269454,0.063729,0.015461,-0.001893,0.000243,-0.000169,0.000066,-0.000011,1.068683,0.067803,0.016443,-0.002017,0.000259,-0.000180,0.000070,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.176513,0.080702,0.009258,-0.001539,-0.000014,0.000008,-0.000003,0.000000,-0.192028,0.089414,0.010297,-0.001695,-0.000016,0.000009,-0.000003,0.000001,1.151049,0.095110,0.010942,-0.001806,-0.000017,0.000009,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.088099,0.094573,0.004607,-0.001553,0.000001,-0.000000,0.000000,0.000000,-0.094022,0.104890,0.005172,-0.001712,0.000001,-0.000000,-0.000000,-0.000000,1.255286,0.111541,0.005480,-0.001826,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.009529,0.099134,-0.000045,-0.001548,0.000002,0.000000,-0.000000,-0.000000,0.014329,0.110099,0.000037,-0.001713,-0.000002,-0.000001,0.000000,-0.000000,1.370480,0.117022,0.000001,-0.001826,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.107073,0.094410,-0.004675,-0.001539,0.000001,0.000001,-0.000000,0.000000,0.122750,0.105026,-0.005117,-0.001724,-0.000003,0.000002,-0.000001,0.000001,1.485678,0.111547,-0.005476,-0.001826,-0.000000,0.000001,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.195270,0.080450,-0.009278,-0.001522,0.000014,-0.000013,0.000013,-0.000010,0.220935,0.089620,-0.010282,-0.001709,0.000016,-0.000015,0.000014,-0.000011,1.589924,0.095123,-0.010940,-0.001807,0.000017,-0.000015,0.000015,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.264923,0.057323,-0.013914,-0.001700,-0.000219,0.000099,-0.000229,0.000168,0.298567,0.063924,-0.015488,-0.001908,-0.000244,0.000110,-0.000256,0.000188,1.672304,0.067816,-0.016445,-0.002018,-0.000259,0.000117,-0.000271,0.000199,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.306451,0.023818,-0.019241,-0.000282,0.002723,-0.000010,0.003385,-0.002234,0.344894,0.026581,-0.021465,-0.000325,0.003041,-0.000011,0.003781,-0.002496,1.721443,0.028190,-0.022768,-0.000340,0.003224,-0.000012,0.004008,-0.002646,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.314610,0.000000,0.000000,0.000000,0.007182,-0.007778,0.003592,-0.000656,0.354000,0.000000,0.000000,0.000000,-0.051742,0.056156,-0.025957,0.004745,1.731100,0.000000,0.000000,0.000000,-0.001494,0.001611,-0.000743,0.000136,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.316950,0.006796,0.005410,-0.000181,-0.000796,0.000663,-0.000280,0.000050,0.337201,-0.048719,-0.038610,0.001517,0.005749,-0.004792,0.002024,-0.000360,1.730610,-0.001426,-0.001145,0.000026,0.000165,-0.000137,0.000058,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.328611,0.015872,0.003567,-0.000590,0.000064,-0.000045,0.000018,-0.000003,0.254010,-0.112730,-0.024691,0.004461,-0.000465,0.000326,-0.000128,0.000022,1.728140,-0.003388,-0.000796,0.000112,-0.000013,0.000009,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.347493,0.021350,0.001932,-0.000537,-0.000003,0.000003,-0.000002,-0.000000,0.120806,-0.149569,-0.012286,0.004087,0.000030,-0.000017,0.000006,-0.000001,1.724061,-0.004670,-0.000490,0.000100,0.000000,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.370236,0.023595,0.000304,-0.000560,-0.000021,-0.000011,0.000004,0.000000,-0.036945,-0.161818,0.000050,0.004118,-0.000003,-0.000004,0.000002,-0.000001,1.719000,-0.005349,-0.000184,0.000112,0.000012,0.000007,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.393547,0.022410,-0.001549,-0.000672,-0.000014,0.000007,0.000001,-0.000003,-0.194601,-0.149393,0.012350,0.004064,-0.000033,0.000031,-0.000029,0.000022,1.713596,-0.005313,0.000258,0.000182,0.000010,-0.000006,0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.413726,0.017257,-0.003630,-0.000747,-0.000072,0.000034,-0.000079,0.000057,-0.327589,-0.112499,0.024680,0.004435,0.000464,-0.000216,0.000497,-0.000359,1.708729,-0.004229,0.000835,0.000206,0.000018,-0.000009,0.000020,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.426546,0.007563,-0.005954,-0.000286,0.000902,-0.000010,0.001144,-0.000746,-0.410587,-0.048591,0.038520,0.001499,-0.005732,0.000053,-0.007232,0.004730,1.705556,-0.001892,0.001475,0.000090,-0.000229,0.000003,-0.000293,0.000190,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.429160,0.000000,0.000000,0.000000,-0.030662,0.033500,-0.015530,0.002844,-0.427340,0.000000,0.000000,0.000000,-0.005032,0.005497,-0.002548,0.000467,1.704900,0.000000,0.000000,0.000000,0.049491,-0.054072,0.025067,-0.004591,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.419312,-0.028419,-0.022195,0.001296,0.003432,-0.002875,0.001219,-0.000218,-0.428956,-0.004663,-0.003642,0.000213,0.000563,-0.000472,0.000200,-0.000036,1.720795,0.045871,0.035825,-0.002092,-0.005540,0.004640,-0.001967,0.000351,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.371552,-0.063778,-0.012752,0.003033,-0.000279,0.000197,-0.000078,0.000014,-0.436793,-0.010465,-0.002092,0.000498,-0.000046,0.000032,-0.000013,0.000002,1.797884,0.102943,0.020582,-0.004896,0.000450,-0.000318,0.000126,-0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.297910,-0.080683,-0.004234,0.002812,0.000019,-0.000013,0.000005,-0.000001,-0.448877,-0.013239,-0.000694,0.000461,0.000003,-0.000002,0.000001,-0.000000,1.916748,0.130227,0.006834,-0.004538,-0.000031,0.000020,-0.000008,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.215815,-0.080683,0.004234,0.002812,-0.000019,0.000018,-0.000018,0.000014,-0.462347,-0.013238,0.000695,0.000461,-0.000003,0.000003,-0.000003,0.000002,2.049255,0.130227,-0.006834,-0.004538,0.000031,-0.000030,0.000030,-0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.142172,-0.063779,0.012752,0.003034,0.000279,-0.000133,0.000305,-0.000218,-0.474429,-0.010463,0.002092,0.000498,0.000046,-0.000022,0.000050,-0.000036,2.168118,0.102941,-0.020582,-0.004896,-0.000450,0.000215,-0.000492,0.000351,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.094411,-0.028420,0.022196,0.001296,-0.003432,0.000046,-0.004379,0.002844,-0.482264,-0.004662,0.003641,0.000213,-0.000563,0.000008,-0.000718,0.000467,2.245205,0.045870,-0.035825,-0.002092,0.005540,-0.000075,0.007067,-0.004590,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.084563,0.000000,0.000000,0.000000,-0.017594,0.018648,-0.008529,0.001548,-0.483880,0.000000,0.000000,0.000000,0.008489,-0.009112,0.004191,-0.000764,2.261100,0.000000,0.000000,0.000000,-0.022098,0.023309,-0.010637,0.001928,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.078636,-0.017472,-0.014504,-0.000283,0.001904,-0.001559,0.000649,-0.000114,-0.481075,0.008198,0.006645,-0.000069,-0.000933,0.000770,-0.000324,0.000057,2.253602,-0.022173,-0.018562,-0.000555,0.002381,-0.001940,0.000807,-0.000142,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.047257,-0.044415,-0.012186,0.000721,-0.000158,0.000102,-0.000040,0.000007,-0.466731,0.019860,0.004893,-0.000563,0.000072,-0.000051,0.000020,-0.000003,2.213417,-0.057292,-0.016219,0.000741,-0.000181,0.000128,-0.000048,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.008711,-0.066931,-0.010395,0.000562,0.000002,-0.000003,0.000002,-0.000000,-0.442504,0.028083,0.003347,-0.000514,-0.000008,0.000003,0.000000,0.000001,2.140554,-0.087827,-0.014363,0.000609,0.000017,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.085475,-0.086033,-0.008705,0.000568,0.000007,0.000005,-0.000002,-0.000000,-0.411593,0.033224,0.001805,-0.000485,0.000039,0.000024,-0.000004,-0.000001,2.038983,-0.114687,-0.012482,0.000640,0.000008,0.000005,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.179634,-0.101696,-0.006936,0.000608,0.000002,-0.000008,0.000003,-0.000000,-0.376990,0.035627,0.000748,-0.000198,0.000069,-0.000016,-0.000001,0.000001,1.912465,-0.137683,-0.010485,0.000696,0.000014,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.287661,-0.113759,-0.005144,0.000578,-0.000012,-0.000001,0.000001,-0.000000,-0.340761,0.036724,0.000410,-0.000073,0.000003,-0.000006,0.000003,-0.000000,1.765005,-0.156519,-0.008331,0.000736,0.000009,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.405998,-0.122358,-0.003476,0.000537,-0.000007,0.000002,-0.000000,-0.000000,-0.303701,0.037318,0.000178,-0.000084,-0.000003,0.000001,-0.000000,0.000000,1.600900,-0.170941,-0.006079,0.000761,0.000003,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.531300,-0.127719,-0.001893,0.000521,-0.000002,0.000000,-0.000000,-0.000000,-0.266291,0.037414,-0.000085,-0.000090,-0.000001,0.000000,-0.000000,-0.000000,1.424642,-0.180808,-0.003785,0.000766,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.660394,-0.129953,-0.000344,0.000513,-0.000002,0.000000,0.000000,-0.000000,-0.229052,0.036972,-0.000359,-0.000093,-0.000001,-0.000000,0.000000,-0.000000,1.240815,-0.186079,-0.001485,0.000767,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.790180,-0.129109,0.001184,0.000506,-0.000001,0.000000,0.000000,-0.000000,-0.192533,0.035970,-0.000645,-0.000098,-0.000001,-0.000000,0.000000,-0.000000,1.054018,-0.186746,0.000819,0.000769,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.917600,-0.125228,0.002695,0.000501,-0.000001,-0.000000,0.000000,-0.000000,-0.157307,0.034382,-0.000945,-0.000103,-0.000001,-0.000000,0.000000,-0.000000,0.868860,-0.182801,0.003127,0.000770,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.039633,-0.118341,0.004189,0.000494,-0.000002,-0.000000,0.000000,-0.000000,-0.123975,0.032178,-0.001262,-0.000109,-0.000002,-0.000000,0.000000,-0.000000,0.689956,-0.174235,0.005441,0.000772,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.153293,-0.108489,0.005658,0.000485,-0.000003,-0.000000,0.000000,-0.000000,-0.093169,0.029321,-0.001598,-0.000115,-0.000001,0.000000,0.000000,-0.000000,0.521935,-0.161034,0.007762,0.000775,0.000001,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.255640,-0.095727,0.007099,0.000476,-0.000002,0.000000,0.000000,-0.000000,-0.065563,0.025774,-0.001950,-0.000119,-0.000001,0.000000,-0.000000,-0.000000,0.369439,-0.143183,0.010090,0.000777,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.343794,-0.080108,0.008517,0.000470,-0.000001,-0.000001,0.000000,-0.000000,-0.041859,0.021514,-0.002310,-0.000121,-0.000000,0.000000,-0.000000,0.000000,0.237123,-0.120672,0.012422,0.000778,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.414916,-0.061669,0.009916,0.000458,-0.000009,0.000007,-0.000007,0.000006,-0.022777,0.016531,-0.002672,-0.000119,0.000002,-0.000002,0.000002,-0.000002,0.129650,-0.093496,0.014748,0.000764,-0.000013,0.000011,-0.000011,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.466214,-0.040463,0.011332,0.000568,0.000134,-0.000057,0.000134,-0.000102,-0.009036,0.010830,-0.003041,-0.000149,-0.000036,0.000015,-0.000036,0.000027,0.051663,-0.061701,0.017111,0.000936,0.000207,-0.000088,0.000207,-0.000157,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.494668,-0.015751,0.013146,-0.000344,-0.001700,-0.000012,-0.002050,0.001379,-0.001425,0.004210,-0.003516,0.000095,0.000454,0.000003,0.000547,-0.000368,0.008179,-0.024137,0.020095,-0.000464,-0.002617,-0.000017,-0.003164,0.002125,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.968010,0.000000,0.000000,0.000000,0.012990,-0.013793,0.006314,-0.001147,0.275540,0.000000,0.000000,0.000000,-0.014705,0.015606,-0.007142,0.001297,0.774520,0.000000,0.000000,0.000000,0.020335,-0.021583,0.009877,-0.001794,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.963646,0.012851,0.010634,0.000167,-0.001407,0.001156,-0.000483,0.000085,0.270596,-0.014561,-0.012059,-0.000200,0.001594,-0.001306,0.000545,-0.000096,0.781356,0.020133,0.016671,0.000273,-0.002205,0.001806,-0.000754,0.000133,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.940642,0.032473,0.008802,-0.000574,0.000113,-0.000077,0.000029,-0.000005,0.244513,-0.036836,-0.010000,0.000649,-0.000127,0.000087,-0.000033,0.000006,0.817414,0.050917,0.013815,-0.000901,0.000175,-0.000120,0.000046,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.899881,0.048563,0.007324,-0.000479,-0.000007,0.000004,-0.000001,0.000000,0.198260,-0.055119,-0.008323,0.000545,0.000008,-0.000004,0.000002,-0.000000,0.881337,0.076165,0.011488,-0.000756,-0.000011,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.844477,0.061758,0.005869,-0.000486,0.000000,-0.000000,0.000000,-0.000000,0.135368,-0.070114,-0.006668,0.000554,-0.000000,0.000000,-0.000000,0.000000,0.968227,0.096848,0.009191,-0.000768,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.777336,0.072038,0.004411,-0.000486,0.000000,-0.000000,0.000000,-0.000000,0.059140,-0.081789,-0.005008,0.000553,0.000000,0.000000,-0.000000,0.000000,1.073497,0.112926,0.006887,-0.000768,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.701374,0.079402,0.002953,-0.000486,-0.000000,-0.000000,-0.000000,0.000000,-0.027105,-0.090147,-0.003349,0.000553,0.000000,-0.000000,0.000000,-0.000000,1.192543,0.124398,0.004585,-0.000768,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.619504,0.083851,0.001496,-0.000486,-0.000000,-0.000000,-0.000000,0.000000,-0.120047,-0.095185,-0.001690,0.000553,0.000000,0.000000,0.000000,-0.000000,1.320757,0.131264,0.002282,-0.000768,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.534643,0.085385,0.000038,-0.000486,-0.000000,-0.000000,-0.000000,0.000000,-0.216369,-0.096905,-0.000030,0.000553,0.000000,0.000000,0.000000,-0.000000,1.453536,0.133526,-0.000021,-0.000768,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.449707,0.084001,-0.001422,-0.000487,-0.000000,0.000000,-0.000000,0.000000,-0.312751,-0.095305,0.001631,0.000554,0.000000,-0.000000,0.000000,-0.000000,1.586274,0.131182,-0.002323,-0.000767,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.367616,0.079695,-0.002885,-0.000489,-0.000001,0.000000,-0.000000,0.000000,-0.405871,-0.090380,0.003294,0.000555,0.000000,-0.000000,0.000000,-0.000000,1.714365,0.124233,-0.004625,-0.000767,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.291295,0.072456,-0.004356,-0.000492,-0.000001,0.000000,-0.000000,0.000000,-0.492401,-0.082125,0.004963,0.000558,0.000001,-0.000000,0.000000,-0.000000,1.833206,0.112683,-0.006924,-0.000766,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.223689,0.062261,-0.005842,-0.000500,-0.000003,0.000001,-0.000000,0.000000,-0.569004,-0.070521,0.006643,0.000563,0.000002,-0.000001,0.000000,-0.000000,1.938200,0.096540,-0.009217,-0.000762,0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.167771,0.049071,-0.007348,-0.000499,0.000006,-0.000006,0.000006,-0.000005,-0.632318,-0.055541,0.008337,0.000560,-0.000007,0.000007,-0.000007,0.000006,2.024764,0.075831,-0.011484,-0.000743,0.000012,-0.000010,0.000009,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.126547,0.032872,-0.008886,-0.000595,-0.000114,0.000049,-0.000115,0.000086,-0.678964,-0.037183,0.010062,0.000668,0.000129,-0.000055,0.000129,-0.000097,2.088372,0.050633,-0.013767,-0.000884,-0.000173,0.000075,-0.000175,0.000132,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.103249,0.013021,-0.010772,0.000164,0.001428,0.000006,0.001737,-0.001162,-0.705311,-0.014721,0.012182,-0.000190,-0.001614,-0.000007,-0.001963,0.001314,2.124211,0.019999,-0.016569,0.000283,0.002188,0.000010,0.002658,-0.001780,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.098826,0.000000,0.000000,0.000000,0.006737,-0.007274,0.003355,-0.000612,-0.710310,0.000000,0.000000,0.000000,0.014754,-0.015930,0.007347,-0.001341,2.131000,0.000000,0.000000,0.000000,-0.025908,0.027973,-0.012901,0.002355,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.096621,0.006419,0.005142,-0.000131,-0.000744,0.000618,-0.000260,0.000046,-0.705480,0.014059,0.011264,-0.000285,-0.001630,0.001353,-0.000570,0.000101,2.122519,-0.024688,-0.019779,0.000500,0.002862,-0.002376,0.001001,-0.000178,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.085532,0.015184,0.003530,-0.000516,0.000060,-0.000042,0.000016,-0.000003,-0.681188,0.033267,0.007738,-0.001127,0.000131,-0.000091,0.000036,-0.000006,2.079861,-0.058417,-0.013589,0.001980,-0.000230,0.000161,-0.000063,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.067302,0.020806,0.002110,-0.000467,-0.000004,0.000002,-0.000001,0.000000,-0.641241,0.045599,0.004633,-0.001021,-0.000008,0.000005,-0.000002,0.000000,2.009713,-0.080074,-0.008137,0.001793,0.000015,-0.000009,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.044855,0.023617,0.000700,-0.000470,0.000001,-0.000000,0.000000,-0.000000,-0.592035,0.051784,0.001548,-0.001031,0.000000,-0.000000,0.000000,-0.000000,1.923304,-0.090938,-0.002719,0.001810,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.021008,0.023608,-0.000708,-0.000469,-0.000000,0.000000,-0.000000,0.000000,-0.539734,0.051788,-0.001544,-0.001031,-0.000000,0.000001,-0.000000,0.000000,1.831457,-0.090946,0.002711,0.001811,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.001423,0.020785,-0.002113,-0.000465,0.000004,-0.000004,0.000004,-0.000003,-0.490521,0.045609,-0.004631,-0.001022,0.000008,-0.000008,0.000008,-0.000006,1.745032,-0.080095,0.008133,0.001795,-0.000015,0.000014,-0.000014,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.019631,0.015163,-0.003528,-0.000514,-0.000060,0.000027,-0.000063,0.000046,-0.450563,0.033278,-0.007739,-0.001128,-0.000131,0.000060,-0.000139,0.000101,1.674862,-0.058440,0.013591,0.001982,0.000231,-0.000106,0.000244,-0.000178,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.030703,0.006408,-0.005134,-0.000130,0.000743,-0.000005,0.000930,-0.000611,-0.426262,0.014065,-0.011268,-0.000286,0.001631,-0.000010,0.002041,-0.001342,1.632185,-0.024700,0.019788,0.000502,-0.002864,0.000018,-0.003584,0.002356,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.032904,0.000000,0.000000,0.000000,-0.018746,0.020159,-0.009280,0.001692,-0.421430,0.000000,0.000000,0.000000,-0.002915,0.003135,-0.001443,0.000263,1.623700,0.000000,0.000000,0.000000,0.017904,-0.019254,0.008863,-0.001616,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.026729,-0.018026,-0.014559,0.000218,0.002062,-0.001707,0.000717,-0.000127,-0.422390,-0.002802,-0.002263,0.000034,0.000321,-0.000265,0.000112,-0.000020,1.629598,0.017218,0.013906,-0.000208,-0.001969,0.001630,-0.000685,0.000122,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.004692,-0.043362,-0.010513,0.001291,-0.000166,0.000115,-0.000045,0.000008,-0.427274,-0.006739,-0.001633,0.000201,-0.000026,0.000018,-0.000007,0.000001,1.659611,0.041420,0.010044,-0.001233,0.000158,-0.000110,0.000043,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.057364,-0.060816,-0.006991,0.001156,0.000011,-0.000006,0.000002,-0.000000,-0.435459,-0.009448,-0.001084,0.000180,0.000002,-0.000001,0.000000,-0.000000,1.709926,0.058097,0.006681,-0.001104,-0.000010,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.124009,-0.071308,-0.003496,0.001167,-0.000001,0.000000,-0.000000,0.000000,-0.445811,-0.011074,-0.000540,0.000182,-0.000000,0.000000,0.000000,-0.000000,1.773594,0.068126,0.003343,-0.001115,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.197647,-0.074802,0.000003,0.001166,-0.000000,0.000000,-0.000000,0.000000,-0.457243,-0.011611,0.000003,0.000181,-0.000000,0.000000,0.000000,-0.000000,1.843949,0.071469,0.000000,-0.001114,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.271280,-0.071298,0.003501,0.001167,0.000000,-0.000001,0.000000,-0.000000,-0.468670,-0.011061,0.000546,0.000181,0.000000,-0.000000,0.000000,-0.000000,1.914304,0.068126,-0.003343,-0.001115,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.337910,-0.060798,0.006993,0.001155,-0.000011,0.000010,-0.000010,0.000008,-0.479005,-0.009428,0.001087,0.000179,-0.000002,0.000002,-0.000001,0.000001,1.977973,0.058098,-0.006681,-0.001104,0.000010,-0.000009,0.000009,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.390562,-0.043343,0.010511,0.001289,0.000165,-0.000075,0.000173,-0.000127,-0.487167,-0.006718,0.001631,0.000199,0.000026,-0.000012,0.000027,-0.000020,2.028288,0.041421,-0.010044,-0.001233,-0.000158,0.000072,-0.000166,0.000122,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.421968,-0.018016,0.014551,0.000217,-0.002061,0.000008,-0.002561,0.001691,-0.492034,-0.002791,0.002255,0.000033,-0.000319,0.000001,-0.000397,0.000262,2.058302,0.017218,-0.013906,-0.000208,0.001969,-0.000007,0.002448,-0.001616,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.428140,0.000000,0.000000,0.000000,-0.022189,0.024080,-0.011130,0.002035,-0.492990,0.000000,0.000000,0.000000,0.013340,-0.014477,0.006692,-0.001223,2.064200,0.000000,0.000000,-0.000000,-0.016439,0.017840,-0.008246,0.001507,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.435344,-0.020894,-0.016560,0.000649,0.002465,-0.002055,0.000868,-0.000155,-0.488659,0.012562,0.009957,-0.000390,-0.001482,0.001235,-0.000522,0.000093,2.058862,-0.015480,-0.012270,0.000480,0.001826,-0.001522,0.000643,-0.000115,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.471026,-0.048355,-0.010596,0.001911,-0.000199,0.000140,-0.000055,0.000010,-0.467205,0.029075,0.006373,-0.001149,0.000120,-0.000084,0.000033,-0.000006,2.032425,-0.035829,-0.007853,0.001416,-0.000148,0.000104,-0.000041,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.528170,-0.064174,-0.005282,0.001751,0.000013,-0.000008,0.000003,-0.000000,-0.432843,0.038591,0.003179,-0.001052,-0.000008,0.000004,-0.000002,0.000000,1.990081,-0.047554,-0.003917,0.001297,0.000010,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.595868,-0.069459,0.000003,0.001765,-0.000000,-0.000001,0.000001,-0.000000,-0.392130,0.041775,0.000002,-0.001061,-0.000000,0.000001,-0.000000,0.000000,1.939912,-0.051478,-0.000002,0.001308,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.663560,-0.064163,0.005286,0.001749,-0.000013,0.000012,-0.000012,0.000010,-0.351414,0.038597,-0.003176,-0.001053,0.000008,-0.000007,0.000007,-0.000006,1.889739,-0.047562,0.003914,0.001297,-0.000009,0.000009,-0.000009,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.720690,-0.048340,0.010596,0.001910,0.000199,-0.000093,0.000214,-0.000154,-0.317044,0.029084,-0.006373,-0.001150,-0.000120,0.000056,-0.000129,0.000093,1.847386,-0.035839,0.007853,0.001417,0.000148,-0.000069,0.000159,-0.000115,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.756359,-0.020885,0.016554,0.000647,-0.002464,0.000023,-0.003110,0.002033,-0.295583,0.012567,-0.009960,-0.000390,0.001483,-0.000014,0.001871,-0.001224,1.820940,-0.015486,0.012274,0.000481,-0.001827,0.000017,-0.002306,0.001508,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.763560,0.000000,0.000000,0.000000,-0.000168,0.000199,-0.000095,0.000018,-0.291250,0.000000,0.000000,0.000000,0.024511,-0.026359,0.012135,-0.002212,1.815600,0.000000,0.000000,0.000000,-0.021370,0.022977,-0.010577,0.001928,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.763607,-0.000126,-0.000076,0.000033,0.000020,-0.000018,0.000008,-0.000001,-0.283176,0.023570,0.019036,-0.000285,-0.002696,0.002232,-0.000938,0.000166,1.808558,-0.020559,-0.016610,0.000241,0.002350,-0.001945,0.000817,-0.000145,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.763767,-0.000151,0.000053,0.000040,-0.000003,0.000001,-0.000001,0.000000,-0.242091,0.056697,0.013745,-0.001688,0.000217,-0.000150,0.000058,-0.000010,1.772708,-0.049492,-0.012020,0.001465,-0.000188,0.000131,-0.000051,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.763828,0.000062,0.000153,0.000025,-0.000005,-0.000001,0.000000,0.000000,-0.173222,0.079519,0.009143,-0.001510,-0.000013,0.000008,-0.000003,0.000000,1.712562,-0.069477,-0.008021,0.001315,0.000013,-0.000007,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.763594,0.000422,0.000195,0.000002,-0.000006,-0.000000,0.000000,0.000000,-0.086077,0.093249,0.004582,-0.001522,0.000001,-0.000000,0.000000,-0.000000,1.636387,-0.081543,-0.004037,0.001333,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.762982,0.000792,0.000163,-0.000022,-0.000004,0.000001,-0.000001,0.000000,0.010233,0.097851,0.000021,-0.001519,-0.000000,-0.000000,-0.000000,0.000000,1.552141,-0.085614,-0.000033,0.001336,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.762051,0.001040,0.000079,-0.000034,-0.000003,0.000001,-0.000000,0.000000,0.106585,0.093332,-0.004544,-0.001526,-0.000003,0.000002,-0.000001,0.000001,1.467831,-0.081668,0.003980,0.001339,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.760968,0.001088,-0.000035,-0.000041,-0.000001,0.000000,0.000000,-0.000000,0.193845,0.079661,-0.009124,-0.001519,0.000012,-0.000012,0.000012,-0.000010,1.391483,-0.069690,0.007993,0.001328,-0.000012,0.000011,-0.000011,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.759957,0.000891,-0.000164,-0.000047,-0.000005,0.000002,-0.000005,0.000003,0.262864,0.056845,-0.013760,-0.001701,-0.000218,0.000099,-0.000228,0.000167,1.331112,-0.049713,0.012042,0.001484,0.000190,-0.000086,0.000199,-0.000146,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.759282,0.000407,-0.000314,-0.000024,0.000050,-0.000001,0.000065,-0.000042,0.304069,0.023647,-0.019092,-0.000294,0.002706,-0.000010,0.003365,-0.002221,1.295082,-0.020674,0.016694,0.000254,-0.002365,0.000009,-0.002941,0.001941,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.759140,0.000000,0.000000,0.000000,0.020863,-0.022366,0.010282,-0.001873,0.312170,0.000000,0.000000,-0.000000,-0.011527,0.012365,-0.005686,0.001036,1.288000,0.000000,0.000000,-0.000000,0.017452,-0.018710,0.008602,-0.001567,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.752234,0.020203,0.016416,-0.000119,-0.002287,0.001889,-0.000792,0.000140,0.308358,-0.011147,-0.009047,0.000079,0.001264,-0.001045,0.000438,-0.000078,1.293777,0.016899,0.013731,-0.000100,-0.001913,0.001580,-0.000663,0.000117,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.716784,0.049202,0.012286,-0.001315,0.000183,-0.000127,0.000049,-0.000008,0.288823,-0.027084,-0.006725,0.000740,-0.000101,0.000070,-0.000027,0.000005,1.323428,0.041152,0.010274,-0.001101,0.000153,-0.000106,0.000041,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.656515,0.070162,0.008729,-0.001166,-0.000012,0.000007,-0.000002,0.000000,0.255699,-0.038500,-0.004721,0.000657,0.000006,-0.000004,0.000001,-0.000000,1.373833,0.058675,0.007296,-0.000976,-0.000010,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.578797,0.084098,0.005201,-0.001179,0.000000,-0.000000,0.000000,-0.000000,0.213138,-0.045960,-0.002735,0.000663,-0.000001,0.000000,0.000000,-0.000000,1.438823,0.070318,0.004343,-0.000987,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.490677,0.090963,0.001664,-0.001179,-0.000000,0.000000,0.000000,0.000000,0.165106,-0.049443,-0.000750,0.000660,-0.000002,-0.000000,-0.000000,-0.000000,1.512497,0.076046,0.001385,-0.000986,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.399230,0.090752,-0.001875,-0.001178,0.000002,-0.000001,0.000001,-0.000000,0.115571,-0.048973,0.001211,0.000641,-0.000011,0.000001,0.000000,-0.000000,1.588943,0.075861,-0.001568,-0.000982,0.000003,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.311529,0.083479,-0.005386,-0.001154,0.000014,-0.000001,-0.000002,0.000001,0.068439,-0.044671,0.003069,0.000595,-0.000017,0.000002,0.000002,-0.000001,1.662257,0.069793,-0.004491,-0.000962,0.000010,-0.000000,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.234578,0.069293,-0.008781,-0.001113,0.000013,-0.000011,0.000011,-0.000008,0.027419,-0.036799,0.004786,0.000559,-0.000007,0.000006,-0.000006,0.000004,1.726605,0.057957,-0.007332,-0.000933,0.000011,-0.000009,0.000009,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.175174,0.048394,-0.012172,-0.001257,-0.000179,0.000080,-0.000185,0.000137,-0.004037,-0.025549,0.006493,0.000636,0.000094,-0.000042,0.000097,-0.000072,1.776300,0.040492,-0.010178,-0.001055,-0.000150,0.000067,-0.000155,0.000115,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.140357,0.019809,-0.016121,-0.000085,0.002236,-0.000003,0.002762,-0.001831,-0.022380,-0.010411,0.008492,0.000021,-0.001171,0.000001,-0.001443,0.000958,1.805436,0.016579,-0.013491,-0.000074,0.001872,-0.000002,0.002312,-0.001533,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.133590,0.000000,0.000000,0.000000,-0.018087,0.019534,-0.009010,0.001645,-0.025934,0.000000,0.000000,0.000000,0.024455,-0.026403,0.012176,-0.002222,1.811100,0.000000,0.000000,0.000000,-0.006099,0.006571,-0.003028,0.000552,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.139508,-0.017223,-0.013790,0.000360,0.001999,-0.001660,0.000699,-0.000124,-0.017928,0.023304,0.018671,-0.000471,-0.002702,0.002243,-0.000945,0.000168,1.809097,-0.005840,-0.004699,0.000093,0.000672,-0.000557,0.000234,-0.000042,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.169247,-0.040702,-0.009437,0.001393,-0.000161,0.000112,-0.000044,0.000008,0.022340,0.055147,0.012831,-0.001868,0.000218,-0.000152,0.000059,-0.000010,1.798958,-0.013943,-0.003318,0.000441,-0.000054,0.000037,-0.000014,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.218078,-0.055689,-0.005600,0.001260,0.000007,-0.000008,0.000003,-0.000000,0.088565,0.075601,0.007688,-0.001692,-0.000015,0.000008,-0.000003,0.000001,1.782109,-0.019353,-0.002106,0.000405,0.000012,0.000003,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.278106,-0.063107,-0.001824,0.001251,-0.000004,0.000002,-0.000001,0.000000,0.170153,0.085869,0.002572,-0.001710,0.000000,-0.000000,0.000000,-0.000000,1.761069,-0.022295,-0.000808,0.000458,0.000008,-0.000005,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.341789,-0.063012,0.001918,0.001247,0.000001,-0.000001,0.000000,-0.000000,0.256884,0.085884,-0.002557,-0.001710,-0.000001,0.000001,-0.000001,0.000001,1.738428,-0.022521,0.000584,0.000465,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.401636,-0.055436,0.005653,0.001236,-0.000010,0.000010,-0.000010,0.000008,0.338501,0.075641,-0.007679,-0.001695,0.000014,-0.000013,0.000013,-0.000010,1.716956,-0.019960,0.001975,0.000460,-0.000004,0.000004,-0.000004,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.450186,-0.040419,0.009412,0.001365,0.000159,-0.000073,0.000169,-0.000123,0.404771,0.055192,-0.012835,-0.001872,-0.000218,0.000100,-0.000231,0.000168,1.699430,-0.014628,0.003375,0.000507,0.000058,-0.000027,0.000062,-0.000045,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.479695,-0.017075,0.013682,0.000342,-0.001979,0.000012,-0.002476,0.001628,0.445076,0.023328,-0.018688,-0.000474,0.002705,-0.000017,0.003385,-0.002225,1.688732,-0.006202,0.004961,0.000135,-0.000721,0.000005,-0.000903,0.000593,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/1/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.485560,0.000000,0.000000,-0.000000,0.008760,-0.009458,0.004362,-0.000796,0.453090,0.000000,0.000000,-0.000000,-0.034750,0.037520,-0.017304,0.003158,1.686600,0.000000,0.000000,0.000000,-0.017359,0.018743,-0.008644,0.001578,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.482693,0.008347,0.006687,-0.000169,-0.000968,0.000804,-0.000338,0.000060,0.441715,-0.033113,-0.026528,0.000672,0.003839,-0.003188,0.001343,-0.000239,1.680918,-0.016541,-0.013252,0.000336,0.001918,-0.001592,0.000671,-0.000119,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.468271,0.019749,0.004593,-0.000670,0.000078,-0.000054,0.000021,-0.000004,0.384502,-0.078347,-0.018222,0.002656,-0.000309,0.000216,-0.000084,0.000015,1.652337,-0.039137,-0.009103,0.001327,-0.000154,0.000108,-0.000042,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.444556,0.027069,0.002749,-0.000606,-0.000005,0.000003,-0.000001,0.000000,0.290427,-0.107383,-0.010907,0.002406,0.000020,-0.000012,0.000004,-0.000001,1.605343,-0.053642,-0.005448,0.001202,0.000010,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.415347,0.030738,0.000917,-0.000612,0.000000,-0.000000,0.000000,-0.000000,0.174555,-0.121938,-0.003639,0.002427,-0.000001,0.000001,-0.000000,0.000000,1.547460,-0.060913,-0.001818,0.001212,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.384303,0.030738,-0.000917,-0.000612,-0.000000,0.000000,-0.000000,0.000000,0.051404,-0.121938,0.003640,0.002427,0.000001,-0.000002,0.000001,-0.000001,1.485940,-0.060913,0.001818,0.001212,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.355094,0.027069,-0.002749,-0.000606,0.000005,-0.000005,0.000005,-0.000004,-0.064468,-0.107382,0.010907,0.002406,-0.000020,0.000019,-0.000019,0.000015,1.428057,-0.053642,0.005448,0.001202,-0.000010,0.000009,-0.000009,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.331380,0.019750,-0.004593,-0.000670,-0.000078,0.000036,-0.000083,0.000060,-0.158543,-0.078346,0.018222,0.002656,0.000309,-0.000142,0.000327,-0.000239,1.381063,-0.039138,0.009103,0.001327,0.000154,-0.000071,0.000164,-0.000119,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.316958,0.008347,-0.006687,-0.000169,0.000968,-0.000006,0.001211,-0.000796,-0.215755,-0.033113,0.026527,0.000672,-0.003839,0.000024,-0.004805,0.003158,1.352482,-0.016541,0.013252,0.000336,-0.001918,0.000012,-0.002400,0.001578,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-1.000000,0.000000,0.000000,0.000000,0.029267,-0.031371,0.014421,-0.002627,0.000000,0.000000,0.000000,0.000000,-0.011809,0.012658,-0.005819,0.001060,1.500000,0.000000,0.000000,0.000000,-0.005453,0.005845,-0.002687,0.000489,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.990310,0.028352,0.023046,-0.000157,-0.003208,0.002649,-0.001111,0.000197,-0.003910,-0.011439,-0.009298,0.000064,0.001294,-0.001069,0.000448,-0.000079,1.498195,-0.005282,-0.004294,0.000029,0.000598,-0.000493,0.000207,-0.000037,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.940543,0.069094,0.017280,-0.001836,0.000257,-0.000178,0.000069,-0.000012,-0.023990,-0.027878,-0.006972,0.000741,-0.000104,0.000072,-0.000028,0.000005,1.488923,-0.012873,-0.003219,0.000342,-0.000048,0.000033,-0.000013,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.855869,0.098613,0.012317,-0.001626,-0.000016,0.000009,-0.000003,0.000001,-0.058153,-0.039788,-0.004969,0.000656,0.000007,-0.000004,0.000001,-0.000000,1.473148,-0.018372,-0.002295,0.000303,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.746576,0.118333,0.007396,-0.001644,0.000001,-0.000000,0.000000,-0.000000,-0.102250,-0.047744,-0.002984,0.000663,-0.000000,0.000000,-0.000000,0.000000,1.452786,-0.022046,-0.001378,0.000306,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.622491,0.128193,0.002465,-0.001643,-0.000000,0.000000,-0.000000,0.000000,-0.152315,-0.051722,-0.000994,0.000663,0.000000,-0.000000,-0.000000,0.000000,1.429668,-0.023883,-0.000459,0.000306,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.493476,0.128194,-0.002465,-0.001643,0.000000,-0.000000,0.000000,-0.000000,-0.204368,-0.051721,0.000995,0.000663,-0.000000,0.000000,-0.000000,0.000000,1.405632,-0.023883,0.000459,0.000306,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.369390,0.118335,-0.007395,-0.001644,-0.000001,0.000001,-0.000001,0.000001,-0.254432,-0.047743,0.002984,0.000663,0.000000,-0.000001,0.000000,-0.000000,1.382515,-0.022046,0.001378,0.000306,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.260094,0.098615,-0.012317,-0.001627,0.000016,-0.000015,0.000015,-0.000012,-0.298528,-0.039787,0.004969,0.000656,-0.000007,0.000006,-0.000006,0.000005,1.362152,-0.018372,0.002295,0.000303,-0.000003,0.000003,-0.000003,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.175419,0.069096,-0.017280,-0.001836,-0.000257,0.000115,-0.000267,0.000197,-0.332691,-0.027877,0.006972,0.000741,0.000104,-0.000046,0.000108,-0.000079,1.346377,-0.012873,0.003219,0.000342,0.000048,-0.000021,0.000050,-0.000037,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.125651,0.028353,-0.023046,-0.000157,0.003208,-0.000005,0.003966,-0.002627,-0.352770,-0.011439,0.009298,0.000064,-0.001294,0.000002,-0.001600,0.001060,1.337105,-0.005282,0.004294,0.000029,-0.000598,0.000001,-0.000739,0.000489,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.074477,0.000000,0.000000,0.000000,-0.032392,0.034971,-0.016127,0.002944,0.435880,0.000000,0.000000,-0.000000,-0.005973,0.006452,-0.002976,0.000543,1.284200,0.000000,0.000000,0.000000,-0.019973,0.021569,-0.009948,0.001816,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.085082,-0.030872,-0.024737,0.000621,0.003578,-0.002971,0.001251,-0.000222,0.433926,-0.005687,-0.004553,0.000120,0.000660,-0.000548,0.000231,-0.000041,1.277664,-0.019025,-0.015236,0.000393,0.002207,-0.001833,0.000772,-0.000137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.138433,-0.073070,-0.017008,0.002473,-0.000287,0.000201,-0.000078,0.000014,0.424107,-0.013436,-0.003114,0.000459,-0.000054,0.000037,-0.000014,0.000003,1.244805,-0.044982,-0.010445,0.001531,-0.000179,0.000124,-0.000048,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.226189,-0.100187,-0.010192,0.002244,0.000020,-0.000011,0.000004,-0.000001,0.407988,-0.018385,-0.001853,0.000413,0.000003,-0.000002,0.000001,-0.000000,1.190813,-0.061608,-0.006237,0.001381,0.000010,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.334313,-0.113798,-0.003409,0.002266,-0.000001,0.000000,-0.000000,0.000000,0.388163,-0.020850,-0.000611,0.000414,-0.000001,0.000000,-0.000000,0.000000,1.124356,-0.069917,-0.002070,0.001390,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.449253,-0.113818,0.003390,0.002267,0.000001,-0.000002,0.000001,-0.000001,0.367116,-0.020831,0.000629,0.000413,0.000000,-0.000000,0.000000,-0.000000,1.053758,-0.069889,0.002098,0.001389,0.000000,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.557415,-0.100242,0.010177,0.002247,-0.000019,0.000018,-0.000017,0.000014,0.347327,-0.018335,0.001866,0.000410,-0.000003,0.000003,-0.000003,0.000003,0.987356,-0.061529,0.006257,0.001377,-0.000011,0.000011,-0.000011,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.645237,-0.073141,0.017009,0.002481,0.000289,-0.000132,0.000306,-0.000223,0.331266,-0.013373,0.003112,0.000453,0.000053,-0.000024,0.000056,-0.000041,0.933458,-0.044882,0.010443,0.001520,0.000177,-0.000081,0.000187,-0.000137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.698650,-0.030914,0.024766,0.000628,-0.003584,0.000022,-0.004486,0.002949,0.321501,-0.005651,0.004528,0.000114,-0.000655,0.000004,-0.000820,0.000539,0.900685,-0.018966,0.015195,0.000383,-0.002199,0.000014,-0.002751,0.001809,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.709270,0.000000,0.000000,0.000000,0.022790,-0.024337,0.011168,-0.002032,0.319560,0.000000,0.000000,0.000000,-0.002105,0.002246,-0.001030,0.000187,0.894170,0.000000,0.000000,-0.000000,0.038025,-0.040652,0.018665,-0.003397,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.701680,0.022264,0.018228,0.000042,-0.002487,0.002048,-0.000857,0.000152,0.318858,-0.002061,-0.001691,-0.000008,0.000230,-0.000189,0.000079,-0.000014,0.906811,0.037053,0.030270,-0.000014,-0.004156,0.003424,-0.001434,0.000254,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.662291,0.055053,0.014232,-0.001269,0.000198,-0.000137,0.000053,-0.000009,0.315203,-0.005116,-0.001332,0.000115,-0.000018,0.000013,-0.000005,0.000001,0.972208,0.091221,0.023351,-0.002200,0.000332,-0.000229,0.000088,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.594170,0.080071,0.010846,-0.001108,-0.000013,0.000007,-0.000003,0.000000,0.308861,-0.007468,-0.001025,0.000101,0.000002,-0.000001,0.000000,-0.000000,1.084756,0.131929,0.017458,-0.001929,-0.000021,0.000012,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.504370,0.098408,0.007483,-0.001127,-0.000002,0.000000,-0.000000,0.000000,0.300471,-0.009207,-0.000712,0.000107,0.000002,0.000001,0.000001,-0.000000,1.232202,0.161013,0.011615,-0.001954,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.399608,0.109983,0.004088,-0.001138,-0.000004,0.000001,-0.000001,0.000000,0.290662,-0.010298,-0.000370,0.000124,0.000006,-0.000001,0.000001,-0.000000,1.402875,0.178378,0.005748,-0.001958,-0.000002,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.286679,0.114728,0.000647,-0.001158,-0.000006,0.000002,-0.000002,0.000000,0.280125,-0.010639,0.000041,0.000150,0.000007,-0.000002,0.000001,-0.000000,1.585042,0.183996,-0.000133,-0.001962,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.172468,0.112523,-0.002871,-0.001195,-0.000017,0.000001,-0.000006,0.000002,0.269682,-0.010088,0.000516,0.000161,-0.000002,-0.000001,-0.000003,0.000001,1.766943,0.177843,-0.006019,-0.001959,0.000003,0.000000,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.064031,0.103110,-0.006602,-0.001314,-0.000042,0.000008,-0.000000,0.000000,0.260266,-0.008600,0.000945,0.000109,-0.000024,0.000001,0.000001,-0.000000,1.936813,0.159949,-0.011858,-0.001925,0.000014,0.000001,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.031129,0.085837,-0.010713,-0.001397,0.000002,-0.000009,0.000012,-0.000010,0.252697,-0.006468,0.001152,0.000038,-0.000011,0.000003,-0.000001,0.000001,2.082994,0.130520,-0.017538,-0.001854,0.000028,-0.000021,0.000018,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.104850,0.060180,-0.015025,-0.001606,-0.000227,0.000101,-0.000233,0.000172,0.247411,-0.004080,0.001229,0.000025,0.000009,-0.000004,0.000012,-0.000009,2.194134,0.089898,-0.023175,-0.002103,-0.000322,0.000143,-0.000334,0.000248,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.148212,0.024714,-0.020080,-0.000148,0.002798,-0.000005,0.003461,-0.002292,0.244592,-0.001526,0.001300,-0.000067,-0.000158,-0.000002,-0.000186,0.000127,2.258489,0.036399,-0.029784,0.000046,0.004071,0.000002,0.005003,-0.003326,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.156660,0.000000,0.000000,0.000000,-0.013056,0.014080,-0.006490,0.001184,0.244080,0.000000,0.000000,0.000000,0.032890,-0.035368,0.016282,-0.002968,2.270900,0.000000,0.000000,0.000000,-0.039619,0.042586,-0.019601,0.003573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.152378,-0.012474,-0.010017,0.000223,0.001441,-0.001195,0.000503,-0.000090,0.254915,0.031631,0.025549,-0.000380,-0.003618,0.002994,-0.001258,0.000223,2.257839,-0.038139,-0.030831,0.000425,0.004356,-0.003604,0.001514,-0.000268,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.130769,-0.029660,-0.006985,0.000969,-0.000117,0.000081,-0.000035,0.000006,0.310058,0.076104,0.018459,-0.002263,0.000290,-0.000201,0.000078,-0.000013,2.191292,-0.091916,-0.022387,0.002694,-0.000348,0.000242,-0.000092,0.000016,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.095029,-0.040950,-0.004362,0.000831,-0.000017,-0.000005,0.000003,-0.000000,0.402510,0.106757,0.012278,-0.002033,-0.000020,0.000012,-0.000004,0.000001,2.079501,-0.129230,-0.015020,0.002435,0.000035,-0.000014,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.050528,-0.047262,-0.001988,0.000756,-0.000013,0.000005,-0.000002,0.000000,0.519502,0.125176,0.006133,-0.002050,0.000002,-0.000001,0.000000,-0.000000,1.937711,-0.151873,-0.007594,0.002495,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.002024,-0.049004,0.000236,0.000733,-0.000002,0.000001,-0.000000,0.000000,0.648763,0.131297,-0.000010,-0.002047,0.000000,-0.000000,-0.000000,-0.000000,1.780742,-0.159567,-0.000097,0.002501,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.046012,-0.046338,0.002429,0.000730,0.000000,-0.000001,0.000000,-0.000000,0.778003,0.125138,-0.006149,-0.002047,-0.000001,0.000002,-0.000001,0.000001,1.623579,-0.152257,0.007409,0.002503,0.000001,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.089192,-0.039292,0.004614,0.000723,-0.000007,0.000006,-0.000006,0.000005,0.894946,0.106704,-0.012276,-0.002026,0.000019,-0.000017,0.000017,-0.000014,1.481234,-0.129934,0.014903,0.002479,-0.000023,0.000021,-0.000021,0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.123149,-0.027895,0.006815,0.000809,0.000106,-0.000048,0.000111,-0.000081,0.987352,0.076067,-0.018448,-0.002262,-0.000290,0.000131,-0.000304,0.000223,1.368676,-0.092685,0.022453,0.002767,0.000354,-0.000160,0.000371,-0.000272,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.143332,-0.011559,0.009350,0.000121,-0.001319,0.000004,-0.001637,0.001082,1.042469,0.031618,-0.025537,-0.000380,0.003616,-0.000013,0.004495,-0.002967,1.301504,-0.038542,0.031123,0.000472,-0.004410,0.000016,-0.005483,0.003619,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.147290,0.000000,0.000000,0.000000,-0.003762,0.004045,-0.001862,0.000339,1.053300,0.000000,0.000000,0.000000,-0.032931,0.035413,-0.016302,0.002972,1.288300,0.000000,0.000000,0.000000,0.001073,-0.001154,0.000531,-0.000097,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.148530,-0.003619,-0.002924,0.000043,0.000414,-0.000342,0.000144,-0.000026,1.042452,-0.031669,-0.025578,0.000382,0.003622,-0.002998,0.001260,-0.000224,1.288654,0.001033,0.000835,-0.000012,-0.000118,0.000098,-0.000041,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.154840,-0.008711,-0.002116,0.000258,-0.000033,0.000023,-0.000009,0.000002,0.987247,-0.076187,-0.018475,0.002267,-0.000291,0.000202,-0.000078,0.000014,1.290455,0.002487,0.000605,-0.000073,0.000009,-0.000007,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.165426,-0.012229,-0.001412,0.000231,0.000002,-0.000001,0.000000,-0.000000,0.894698,-0.106865,-0.012291,0.002030,0.000019,-0.000011,0.000004,-0.000001,1.293478,0.003493,0.000405,-0.000066,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.178836,-0.014357,-0.000714,0.000233,-0.000000,0.000000,-0.000000,0.000000,0.777583,-0.125319,-0.006153,0.002050,-0.000001,0.000000,-0.000000,0.000000,1.297310,0.004104,0.000206,-0.000066,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.193674,-0.015086,-0.000015,0.000233,0.000000,0.000000,0.000000,0.000000,0.648160,-0.131477,-0.000005,0.002049,0.000000,0.000000,-0.000000,0.000000,1.301554,0.004317,0.000007,-0.000066,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.208542,-0.014417,0.000685,0.000234,0.000001,-0.000000,0.000000,-0.000000,0.518728,-0.125339,0.006144,0.002051,0.000001,-0.000002,0.000001,-0.000001,1.305812,0.004133,-0.000192,-0.000066,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.222039,-0.012342,0.001391,0.000236,-0.000000,0.000002,-0.000002,0.000002,0.401582,-0.106903,0.012285,0.002032,-0.000018,0.000017,-0.000017,0.000014,1.309686,0.003549,-0.000393,-0.000068,-0.000000,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.232753,-0.008843,0.002122,0.000271,0.000035,-0.000016,0.000036,-0.000026,0.308993,-0.076227,0.018478,0.002271,0.000291,-0.000132,0.000305,-0.000224,1.312773,0.002555,-0.000606,-0.000081,-0.000011,0.000005,-0.000011,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.239174,-0.003692,0.002976,0.000053,-0.000424,0.000002,-0.000528,0.000348,0.253756,-0.031690,0.025593,0.000384,-0.003625,0.000013,-0.004506,0.002975,1.314632,0.001072,-0.000862,-0.000018,0.000124,-0.000001,0.000154,-0.000102,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.240440,0.000000,0.000000,0.000000,0.016441,-0.017681,0.008139,-0.001484,0.242900,0.000000,0.000000,0.000000,0.018591,-0.019992,0.009204,-0.001678,1.315000,0.000000,0.000000,0.000000,-0.015651,0.016832,-0.007749,0.001413,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.235024,0.015810,0.012769,-0.000191,-0.001808,0.001497,-0.000629,0.000112,0.249024,0.017878,0.014439,-0.000216,-0.002045,0.001693,-0.000711,0.000126,1.309844,-0.015050,-0.012155,0.000182,0.001722,-0.001425,0.000599,-0.000106,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.207466,0.038030,0.009220,-0.001132,0.000145,-0.000101,0.000039,-0.000007,0.280188,0.043008,0.010428,-0.001280,0.000164,-0.000114,0.000044,-0.000008,1.283610,-0.036203,-0.008777,0.001078,-0.000138,0.000096,-0.000037,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.161272,0.053337,0.006131,-0.001014,-0.000009,0.000005,-0.000002,0.000000,0.332431,0.060322,0.006936,-0.001146,-0.000010,0.000006,-0.000002,0.000000,1.239636,-0.050774,-0.005837,0.000965,0.000009,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.102822,0.062540,0.003067,-0.001023,0.000001,-0.000000,0.000000,-0.000000,0.398535,0.070732,0.003470,-0.001158,0.000001,-0.000000,0.000000,-0.000000,1.183995,-0.059535,-0.002920,0.000974,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.038238,0.065606,-0.000001,-0.001023,-0.000000,-0.000000,0.000000,-0.000000,0.471580,0.074200,-0.000001,-0.001157,0.000000,-0.000000,0.000000,-0.000000,1.122514,-0.062453,0.000001,0.000974,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.026345,0.062536,-0.003069,-0.001023,-0.000000,0.000001,-0.000000,0.000000,0.544621,0.070726,-0.003472,-0.001157,-0.000000,0.000001,-0.000000,0.000000,1.061036,-0.059530,0.002922,0.000974,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.084789,0.053330,-0.006133,-0.001013,0.000009,-0.000009,0.000008,-0.000007,0.610718,0.060312,-0.006937,-0.001146,0.000011,-0.000010,0.000010,-0.000008,1.005402,-0.050765,0.005838,0.000964,-0.000009,0.000008,-0.000008,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.130975,0.038022,-0.009219,-0.001132,-0.000145,0.000066,-0.000152,0.000112,0.662951,0.042998,-0.010427,-0.001279,-0.000164,0.000074,-0.000172,0.000126,0.961438,-0.036192,0.008776,0.001077,0.000138,-0.000062,0.000145,-0.000106,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.158526,0.015805,-0.012765,-0.000191,0.001808,-0.000007,0.002247,-0.001483,0.694107,0.017873,-0.014436,-0.000215,0.002044,-0.000008,0.002541,-0.001677,0.935213,-0.015044,0.012151,0.000181,-0.001721,0.000006,-0.002139,0.001412,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.163940,0.000000,0.000000,0.000000,0.000723,-0.000777,0.000358,-0.000065,0.700230,0.000000,0.000000,0.000000,-0.020779,0.022346,-0.010287,0.001875,0.930060,0.000000,0.000000,0.000000,0.007170,-0.007711,0.003550,-0.000647,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.164178,0.000695,0.000561,-0.000008,-0.000080,0.000066,-0.000028,0.000005,0.693385,-0.019983,-0.016140,0.000241,0.002286,-0.001892,0.000795,-0.000141,0.932422,0.006896,0.005569,-0.000083,-0.000789,0.000653,-0.000274,0.000049,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.165390,0.001672,0.000405,-0.000050,0.000006,-0.000004,0.000002,-0.000000,0.658550,-0.048074,-0.011658,0.001430,-0.000183,0.000127,-0.000049,0.000009,0.944442,0.016589,0.004023,-0.000494,0.000063,-0.000044,0.000017,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.167420,0.002344,0.000269,-0.000045,-0.000000,0.000000,-0.000000,0.000000,0.600152,-0.067432,-0.007756,0.001281,0.000012,-0.000007,0.000002,-0.000000,0.964594,0.023269,0.002676,-0.000442,-0.000004,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.169989,0.002748,0.000134,-0.000045,0.000000,-0.000000,0.000000,-0.000000,0.526251,-0.079076,-0.003882,0.001294,-0.000001,0.000000,-0.000000,0.000000,0.990095,0.027287,0.001340,-0.000447,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.172827,0.002882,-0.000001,-0.000045,0.000000,-0.000000,0.000000,-0.000000,0.444587,-0.082960,-0.000002,0.001293,0.000000,0.000000,-0.000000,0.000000,1.018275,0.028627,0.000001,-0.000446,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.175663,0.002746,-0.000135,-0.000045,0.000000,0.000000,-0.000000,0.000000,0.362918,-0.079083,0.003880,0.001294,0.000001,-0.000001,0.000000,-0.000000,1.046456,0.027289,-0.001339,-0.000447,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.178228,0.002340,-0.000270,-0.000044,0.000000,-0.000000,0.000000,-0.000000,0.289009,-0.067443,0.007755,0.001282,-0.000012,0.000011,-0.000011,0.000009,1.071959,0.023272,-0.002676,-0.000442,0.000004,-0.000004,0.000004,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.180254,0.001668,-0.000405,-0.000050,-0.000006,0.000003,-0.000007,0.000005,0.230600,-0.048085,0.011659,0.001431,0.000183,-0.000083,0.000192,-0.000141,1.092114,0.016592,-0.004023,-0.000494,-0.000063,0.000029,-0.000066,0.000049,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.181463,0.000693,-0.000560,-0.000008,0.000079,-0.000000,0.000098,-0.000065,0.195757,-0.019988,0.016144,0.000241,-0.002286,0.000008,-0.002842,0.001876,1.104137,0.006897,-0.005571,-0.000083,0.000789,-0.000003,0.000981,-0.000647,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.181700,0.000000,0.000000,0.000000,-0.023261,0.025195,-0.011636,0.002126,0.188910,0.000000,0.000000,0.000000,0.012121,-0.013477,0.006294,-0.001158,1.106500,0.000000,0.000000,0.000000,0.005567,-0.005909,0.002704,-0.000491,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.174124,-0.022002,-0.017510,0.000593,0.002579,-0.002146,0.000906,-0.000161,0.192691,0.010761,0.008056,-0.000930,-0.001383,0.001173,-0.000501,0.000090,1.108372,0.005513,0.004565,0.000075,-0.000604,0.000495,-0.000206,0.000036,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.136382,-0.051352,-0.011519,0.001919,-0.000208,0.000146,-0.000058,0.000010,0.209957,0.022039,0.003070,-0.001607,0.000113,-0.000078,0.000025,-0.000003,1.118246,0.013944,0.003784,-0.000246,0.000048,-0.000033,0.000014,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.075320,-0.069012,-0.006203,0.001751,0.000016,-0.000013,0.000011,-0.000004,0.233515,0.023546,-0.001549,-0.001550,-0.000015,-0.000010,0.000050,-0.000009,1.135753,0.020863,0.003152,-0.000203,-0.000002,0.000003,-0.000006,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.001867,-0.076127,-0.000898,0.001776,-0.000012,0.000027,-0.000068,0.000014,0.253978,0.015927,-0.005818,-0.001007,0.000388,-0.000116,0.000054,-0.000003,1.159561,0.026535,0.002487,-0.000275,-0.000051,0.000018,-0.000015,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.073421,-0.072817,0.003899,0.001119,-0.000418,0.000095,0.000029,-0.000014,0.263403,0.002541,-0.006937,0.000338,0.000492,-0.000129,-0.000021,0.000013,1.188262,0.030495,0.001355,-0.000526,-0.000113,0.000028,0.000006,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.141528,-0.062783,0.005841,0.000490,0.000006,0.000017,-0.000014,0.000003,0.259700,-0.009029,-0.004300,0.001055,-0.000009,-0.000019,0.000016,-0.000004,1.219504,0.031329,-0.000600,-0.000693,0.000002,0.000005,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.197967,-0.049582,0.007377,0.000518,-0.000005,0.000003,-0.000004,0.000005,0.247410,-0.014526,-0.001222,0.001008,-0.000007,0.000009,-0.000008,0.000004,1.249544,0.028065,-0.002656,-0.000678,0.000006,-0.000006,0.000006,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.239655,-0.033269,0.008970,0.000612,0.000115,-0.000049,0.000116,-0.000087,0.232669,-0.013946,0.001824,0.001067,0.000074,-0.000038,0.000085,-0.000059,1.274276,0.020718,-0.004716,-0.000745,-0.000083,0.000039,-0.000089,0.000064,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.263248,-0.013195,0.010909,-0.000158,-0.001449,-0.000006,-0.001764,0.001180,0.221676,-0.006892,0.005132,0.000630,-0.000893,0.000023,-0.001174,0.000748,1.289463,0.008828,-0.007044,-0.000215,0.001030,-0.000008,0.001294,-0.000849,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.267730,0.000000,0.000000,0.000000,0.031749,-0.034430,0.015909,-0.002907,0.219250,0.000000,0.000000,-0.000000,0.031908,-0.034597,0.015985,-0.002921,1.292500,0.000000,0.000000,-0.000000,0.022528,-0.024424,0.011285,-0.002062,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.257410,0.029946,0.023771,-0.000884,-0.003525,0.002936,-0.001240,0.000221,0.229625,0.030110,0.023911,-0.000877,-0.003542,0.002950,-0.001246,0.000222,1.299826,0.021261,0.016886,-0.000616,-0.002500,0.002082,-0.000879,0.000157,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.206184,0.069526,0.015371,-0.002692,0.000285,-0.000200,0.000079,-0.000014,0.281154,0.069964,0.015503,-0.002694,0.000287,-0.000201,0.000081,-0.000014,1.336215,0.049414,0.010957,-0.001899,0.000202,-0.000142,0.000057,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.123828,0.092710,0.007900,-0.002458,-0.000018,0.000013,-0.000011,0.000002,0.364079,0.093411,0.008033,-0.002456,-0.000017,0.000015,-0.000017,0.000003,1.394794,0.065998,0.005689,-0.001732,-0.000012,0.000010,-0.000011,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.025689,0.101079,0.000427,-0.002548,-0.000046,0.000013,-0.000002,0.000000,0.463052,0.102037,0.000528,-0.002595,-0.000078,0.000019,0.000005,-0.000002,1.464737,0.072130,0.000401,-0.001825,-0.000052,0.000013,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.073233,0.094158,-0.007391,-0.002636,-0.000003,-0.000010,0.000018,-0.000015,0.562966,0.095107,-0.007502,-0.002686,0.000023,-0.000016,0.000016,-0.000014,1.535405,0.067317,-0.005251,-0.001903,0.000006,-0.000009,0.000012,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.157355,0.071410,-0.015458,-0.002904,-0.000296,0.000140,-0.000320,0.000231,0.647894,0.072058,-0.015630,-0.002916,-0.000299,0.000139,-0.000321,0.000232,1.595566,0.051086,-0.011046,-0.002082,-0.000212,0.000100,-0.000229,0.000165,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.210157,0.030990,-0.024511,-0.001026,0.003669,-0.000037,0.004637,-0.003029,0.701159,0.031250,-0.024724,-0.001025,0.003698,-0.000036,0.004673,-0.003053,1.633347,0.022178,-0.017538,-0.000739,0.002626,-0.000026,0.003320,-0.002169,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.220850,0.000000,0.000000,0.000000,-0.025545,0.027910,-0.012938,0.002369,0.711940,0.000000,0.000000,-0.000000,-0.033860,0.036994,-0.017150,0.003141,1.641000,0.000000,0.000000,0.000000,-0.013498,0.014748,-0.006837,0.001252,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.212645,-0.023677,-0.018492,0.001080,0.002859,-0.002395,0.001015,-0.000181,0.701065,-0.031384,-0.024511,0.001431,0.003790,-0.003175,0.001346,-0.000240,1.636665,-0.012511,-0.009771,0.000571,0.001511,-0.001266,0.000536,-0.000096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.172855,-0.053135,-0.010624,0.002527,-0.000232,0.000164,-0.000065,0.000011,0.648323,-0.070431,-0.014082,0.003350,-0.000308,0.000218,-0.000086,0.000015,1.615639,-0.028077,-0.005614,0.001335,-0.000123,0.000087,-0.000034,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.111502,-0.067219,-0.003528,0.002342,0.000016,-0.000011,0.000004,-0.000001,0.566998,-0.089100,-0.004676,0.003105,0.000021,-0.000014,0.000006,-0.000002,1.583220,-0.035519,-0.001864,0.001238,0.000008,-0.000006,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.043107,-0.067219,0.003527,0.002342,-0.000016,0.000015,-0.000015,0.000011,0.476337,-0.089101,0.004675,0.003105,-0.000021,0.000020,-0.000020,0.000015,1.547080,-0.035519,0.001864,0.001238,-0.000008,0.000008,-0.000008,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.018247,-0.053135,0.010624,0.002527,0.000232,-0.000111,0.000254,-0.000181,0.395010,-0.070434,0.014082,0.003350,0.000308,-0.000147,0.000337,-0.000240,1.514660,-0.028077,0.005614,0.001335,0.000123,-0.000059,0.000134,-0.000096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.058037,-0.023677,0.018492,0.001080,-0.002859,0.000038,-0.003648,0.002370,0.342266,-0.031386,0.024512,0.001432,-0.003790,0.000051,-0.004836,0.003141,1.493635,-0.012511,0.009771,0.000571,-0.001511,0.000020,-0.001928,0.001252,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.066242,0.000000,0.000000,-0.000000,-0.012234,0.013029,-0.005972,0.001086,0.331390,0.000000,0.000000,-0.000000,0.005700,-0.006355,0.002972,-0.000547,1.489300,0.000000,0.000000,0.000000,-0.018053,0.019185,-0.008785,0.001596,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.070334,-0.012024,-0.009895,-0.000086,0.001331,-0.001094,0.000457,-0.000081,0.333159,0.005023,0.003732,-0.000470,-0.000652,0.000555,-0.000238,0.000043,1.483243,-0.017825,-0.014726,-0.000200,0.001960,-0.001608,0.000671,-0.000118,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.091725,-0.030039,-0.007942,0.000619,-0.000106,0.000073,-0.000028,0.000005,0.341152,0.010116,0.001289,-0.000788,0.000054,-0.000040,0.000017,-0.000003,1.451397,-0.044877,-0.012062,0.000842,-0.000156,0.000107,-0.000041,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.129144,-0.044262,-0.006314,0.000531,0.000007,-0.000005,0.000004,-0.000001,0.351797,0.010426,-0.000963,-0.000745,-0.000005,0.000007,-0.000010,0.000003,1.395217,-0.066762,-0.009871,0.000713,0.000010,-0.000007,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.179184,-0.055278,-0.004695,0.000546,0.000001,0.000005,-0.000015,0.000003,0.360510,0.006243,-0.003239,-0.000779,-0.000005,-0.000019,0.000058,-0.000012,1.319303,-0.084342,-0.007699,0.000732,0.000001,0.000005,-0.000016,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.238616,-0.063068,-0.003161,0.000406,-0.000093,0.000021,0.000006,-0.000003,0.362757,-0.002423,-0.005177,-0.000246,0.000354,-0.000080,-0.000025,0.000012,1.227987,-0.097586,-0.005613,0.000587,-0.000096,0.000022,0.000007,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.304509,-0.068423,-0.002261,0.000262,-0.000001,0.000004,-0.000003,0.000001,0.355172,-0.012562,-0.004709,0.000294,-0.000001,-0.000015,0.000012,-0.000003,1.125304,-0.107311,-0.004181,0.000440,0.000000,0.000004,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.374930,-0.072155,-0.001469,0.000264,-0.000000,-0.000001,0.000000,-0.000000,0.338187,-0.021128,-0.003870,0.000272,-0.000001,0.000003,-0.000002,0.000000,1.014255,-0.114343,-0.002848,0.000446,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.448290,-0.074302,-0.000679,0.000263,-0.000000,0.000000,-0.000000,0.000000,0.313463,-0.028049,-0.003051,0.000274,0.000000,-0.000000,0.000000,-0.000000,0.897510,-0.118702,-0.001511,0.000446,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.523009,-0.074872,0.000109,0.000262,-0.000000,-0.000000,0.000000,-0.000000,0.282637,-0.033328,-0.002228,0.000274,-0.000000,0.000000,-0.000000,0.000000,0.777743,-0.120387,-0.000174,0.000445,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.597510,-0.073869,0.000895,0.000262,-0.000000,0.000000,0.000000,-0.000000,0.247354,-0.036962,-0.001406,0.000274,0.000000,-0.000000,0.000000,-0.000000,0.657626,-0.119400,0.001162,0.000445,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.670222,-0.071293,0.001681,0.000262,-0.000000,0.000000,0.000000,-0.000000,0.209260,-0.038951,-0.000583,0.000274,0.000000,0.000000,0.000000,-0.000000,0.539834,-0.115740,0.002498,0.000445,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.739572,-0.067146,0.002466,0.000262,-0.000000,0.000000,0.000000,-0.000000,0.170000,-0.039294,0.000240,0.000274,0.000000,-0.000000,0.000000,-0.000000,0.427037,-0.109408,0.003834,0.000445,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.803990,-0.061427,0.003252,0.000262,0.000000,-0.000000,0.000000,-0.000000,0.131220,-0.037992,0.001063,0.000274,0.000000,-0.000000,0.000000,-0.000000,0.321909,-0.100404,0.005170,0.000445,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.861903,-0.054138,0.004038,0.000262,0.000000,0.000000,0.000000,0.000000,0.094566,-0.035043,0.001886,0.000274,0.000000,0.000000,-0.000000,0.000000,0.227120,-0.088728,0.006506,0.000445,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.911742,-0.045277,0.004823,0.000262,0.000000,-0.000000,0.000000,-0.000000,0.061684,-0.030447,0.002709,0.000275,0.000000,-0.000000,0.000000,-0.000000,0.145344,-0.074380,0.007842,0.000446,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.951933,-0.034845,0.005607,0.000257,-0.000005,0.000004,-0.000004,0.000003,0.034220,-0.024205,0.003531,0.000271,-0.000004,0.000003,-0.000003,0.000003,0.079252,-0.057360,0.009174,0.000437,-0.000008,0.000007,-0.000006,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.980915,-0.022858,0.006403,0.000320,0.000076,-0.000032,0.000076,-0.000057,0.013816,-0.016330,0.004362,0.000318,0.000057,-0.000025,0.000058,-0.000043,0.031502,-0.037697,0.010528,0.000541,0.000126,-0.000053,0.000125,-0.000095,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.996988,-0.008897,0.007426,-0.000195,-0.000960,-0.000007,-0.001158,0.000779,0.002212,-0.006506,0.005367,-0.000063,-0.000717,-0.000002,-0.000875,0.000584,0.004976,-0.014695,0.012256,-0.000310,-0.001588,-0.000011,-0.001917,0.001289,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.115960,0.000000,0.000000,0.000000,0.001374,-0.001464,0.000671,-0.000122,-0.356680,0.000000,0.000000,-0.000000,-0.006499,0.006902,-0.003159,0.000574,1.335300,0.000000,0.000000,0.000000,-0.001428,0.001518,-0.000695,0.000126,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.115500,0.001351,0.001112,0.000010,-0.000150,0.000123,-0.000051,0.000009,-0.358863,-0.006428,-0.005317,-0.000081,0.000705,-0.000578,0.000241,-0.000043,1.334821,-0.001410,-0.001165,-0.000016,0.000155,-0.000127,0.000053,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.113097,0.003374,0.000892,-0.000070,0.000012,-0.000008,0.000003,-0.000001,-0.370363,-0.016225,-0.004385,0.000294,-0.000056,0.000038,-0.000015,0.000003,1.332301,-0.003551,-0.000954,0.000067,-0.000012,0.000008,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.108894,0.004971,0.000709,-0.000060,-0.000001,0.000000,-0.000000,0.000000,-0.390710,-0.024217,-0.003624,0.000248,0.000003,-0.000002,0.000001,-0.000000,1.327856,-0.005283,-0.000781,0.000056,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.103274,0.006208,0.000527,-0.000061,0.000000,-0.000000,0.000000,-0.000000,-0.418301,-0.030714,-0.002872,0.000251,-0.000000,0.000000,-0.000000,0.000000,1.321849,-0.006674,-0.000610,0.000057,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.096600,0.007081,0.000346,-0.000060,0.000000,0.000000,-0.000000,0.000000,-0.451635,-0.035704,-0.002118,0.000251,-0.000000,-0.000000,0.000000,-0.000000,1.314622,-0.007722,-0.000438,0.000057,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.089234,0.007591,0.000165,-0.000060,0.000000,0.000000,-0.000000,0.000000,-0.489206,-0.039188,-0.001366,0.000251,-0.000000,-0.000000,0.000000,-0.000000,1.306519,-0.008427,-0.000267,0.000057,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.081538,0.007741,-0.000014,-0.000059,0.000000,0.000000,-0.000000,0.000000,-0.529509,-0.041168,-0.000615,0.000250,-0.000000,-0.000000,0.000000,-0.000000,1.297882,-0.008789,-0.000095,0.000057,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.073871,0.007536,-0.000189,-0.000057,0.000001,0.000000,-0.000000,0.000000,-0.571043,-0.041649,0.000133,0.000248,-0.000001,-0.000000,0.000000,-0.000000,1.289055,-0.008808,0.000076,0.000057,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.066579,0.006992,-0.000352,-0.000051,0.000002,0.000000,-0.000000,0.000000,-0.612312,-0.040642,0.000872,0.000244,-0.000002,-0.000000,0.000000,-0.000000,1.280379,-0.008486,0.000246,0.000056,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.059988,0.006147,-0.000487,-0.000038,0.000004,0.000001,-0.000000,0.000000,-0.651840,-0.038174,0.001592,0.000236,-0.000003,-0.000001,0.000000,-0.000000,1.272193,-0.007830,0.000409,0.000053,-0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.054362,0.005077,-0.000573,-0.000019,0.000005,0.000000,-0.000000,0.000000,-0.688189,-0.034295,0.002279,0.000222,-0.000004,-0.000000,0.000000,-0.000000,1.264824,-0.006861,0.000556,0.000044,-0.000003,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.049872,0.003894,-0.000600,0.000000,0.000004,-0.000000,-0.000000,0.000000,-0.719986,-0.029085,0.002924,0.000209,-0.000003,-0.000000,0.000000,-0.000000,1.258560,-0.005628,0.000670,0.000032,-0.000003,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.046574,0.002708,-0.000579,0.000012,0.000002,-0.000000,0.000000,-0.000000,-0.745940,-0.022620,0.003534,0.000196,-0.000005,0.000003,-0.000002,0.000002,1.253631,-0.004206,0.000746,0.000019,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.044431,0.001593,-0.000534,0.000014,-0.000004,0.000001,-0.000004,0.000003,-0.764832,-0.014967,0.004133,0.000234,0.000050,-0.000021,0.000050,-0.000038,1.250187,-0.002667,0.000793,0.000019,0.000007,-0.000003,0.000008,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.043361,0.000558,-0.000492,0.000045,0.000054,0.000002,0.000061,-0.000043,-0.775391,-0.005868,0.004880,-0.000106,-0.000637,-0.000004,-0.000772,0.000518,1.248338,-0.001005,0.000853,-0.000040,-0.000105,-0.000001,-0.000125,0.000085,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.043176,0.000000,0.000000,0.000000,-0.021155,0.022842,-0.010534,0.001923,-0.777380,0.000000,0.000000,0.000000,0.049209,-0.053132,0.024503,-0.004472,1.248000,0.000000,0.000000,0.000000,0.002910,-0.003141,0.001448,-0.000264,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.050100,-0.020156,-0.016146,0.000411,0.002337,-0.001941,0.000817,-0.000145,-0.761272,0.046890,0.037564,-0.000952,-0.005437,0.004514,-0.001901,0.000338,1.248953,0.002776,0.002226,-0.000054,-0.000321,0.000267,-0.000112,0.000020,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.084922,-0.047681,-0.011085,0.001619,-0.000188,0.000131,-0.000051,0.000009,-0.680257,0.110940,0.025800,-0.003762,0.000438,-0.000305,0.000119,-0.000021,1.253755,0.006582,0.001538,-0.000220,0.000026,-0.000018,0.000007,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.142169,-0.065337,-0.006628,0.001465,0.000011,-0.000007,0.000003,-0.000000,-0.547047,0.152049,0.015440,-0.003407,-0.000028,0.000016,-0.000006,0.000001,1.261668,0.009043,0.000930,-0.000202,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.212662,-0.074175,-0.002206,0.001476,-0.000001,0.000000,-0.000000,0.000000,-0.382981,0.172651,0.005149,-0.003436,0.000002,-0.000001,0.000000,-0.000000,1.271438,0.010291,0.000316,-0.000206,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.287568,-0.074162,0.002219,0.001475,0.000001,-0.000001,0.000001,-0.000000,-0.208617,0.172644,-0.005156,-0.003436,-0.000001,0.000003,-0.000001,0.000001,1.281838,0.010305,-0.000302,-0.000206,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.358037,-0.065302,0.006636,0.001462,-0.000012,0.000011,-0.000011,0.000009,-0.044563,0.152032,-0.015443,-0.003405,0.000028,-0.000027,0.000026,-0.000021,1.291635,0.009082,-0.000919,-0.000204,0.000002,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.415244,-0.047641,0.011082,0.001615,0.000188,-0.000086,0.000199,-0.000145,0.088626,0.110920,-0.025799,-0.003760,-0.000438,0.000201,-0.000464,0.000338,1.299594,0.006630,-0.001540,-0.000226,-0.000026,0.000012,-0.000028,0.000020,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.450033,-0.020134,0.016130,0.000408,-0.002334,0.000014,-0.002921,0.001920,0.169626,0.046880,-0.037556,-0.000951,0.005435,-0.000034,0.006802,-0.004471,1.304437,0.002804,-0.002246,-0.000057,0.000325,-0.000002,0.000407,-0.000268,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.456950,0.000000,0.000000,-0.000000,-0.030734,0.033050,-0.015215,0.002774,0.185730,0.000000,0.000000,0.000000,-0.018966,0.020395,-0.009389,0.001712,1.305400,0.000000,0.000000,0.000000,0.019376,-0.020836,0.009592,-0.001749,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.467074,-0.029556,-0.023871,0.000357,0.003380,-0.002798,0.001176,-0.000209,0.179482,-0.018238,-0.014731,0.000220,0.002086,-0.001727,0.000726,-0.000129,1.311783,0.018633,0.015049,-0.000225,-0.002131,0.001764,-0.000741,0.000132,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.518595,-0.071101,-0.017241,0.002116,-0.000271,0.000188,-0.000073,0.000013,0.147690,-0.043876,-0.010639,0.001306,-0.000167,0.000116,-0.000045,0.000008,1.344263,0.044824,0.010869,-0.001334,0.000171,-0.000119,0.000046,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.604964,-0.099728,-0.011468,0.001895,0.000017,-0.000010,0.000004,-0.000001,0.094392,-0.061541,-0.007077,0.001169,0.000011,-0.000006,0.000002,-0.000000,1.398713,0.062872,0.007230,-0.001195,-0.000011,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.714255,-0.116943,-0.005739,0.001914,-0.000001,0.000000,-0.000000,0.000000,0.026950,-0.072164,-0.003541,0.001181,-0.000001,0.000000,-0.000000,0.000000,1.467613,0.073725,0.003618,-0.001207,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.835024,-0.122682,-0.000000,0.001913,0.000000,0.000000,-0.000000,0.000000,-0.047575,-0.075705,0.000000,0.001180,-0.000000,0.000000,-0.000000,0.000000,1.543750,0.077342,0.000000,-0.001206,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.955793,-0.116944,0.005739,0.001914,0.000001,-0.000002,0.000001,-0.000001,-0.122100,-0.072164,0.003541,0.001181,0.000001,-0.000001,0.000000,-0.000000,1.619887,0.073725,-0.003618,-0.001207,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.065084,-0.099729,0.011468,0.001895,-0.000017,0.000016,-0.000016,0.000013,-0.189542,-0.061541,0.007077,0.001169,-0.000011,0.000010,-0.000010,0.000008,1.688787,0.062872,-0.007230,-0.001195,0.000011,-0.000010,0.000010,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.151454,-0.071102,0.017241,0.002116,0.000271,-0.000123,0.000284,-0.000209,-0.242840,-0.043876,0.010639,0.001306,0.000167,-0.000076,0.000175,-0.000129,1.743237,0.044824,-0.010869,-0.001334,-0.000171,0.000077,-0.000179,0.000132,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.202975,-0.029556,0.023871,0.000357,-0.003381,0.000012,-0.004202,0.002774,-0.274632,-0.018238,0.014731,0.000220,-0.002086,0.000008,-0.002593,0.001712,1.775717,0.018633,-0.015049,-0.000225,0.002131,-0.000008,0.002649,-0.001749,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-1.213100,0.000000,0.000000,0.000000,0.013506,-0.014658,0.006775,-0.001238,-0.280880,0.000000,0.000000,0.000000,0.030053,-0.032615,0.015075,-0.002756,1.782100,0.000000,0.000000,0.000000,-0.034723,0.037683,-0.017418,0.003184,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.208715,0.012718,0.010080,-0.000395,-0.001501,0.001251,-0.000528,0.000094,-0.271122,0.028300,0.022430,-0.000878,-0.003339,0.002783,-0.001176,0.000209,1.770826,-0.032697,-0.025916,0.001015,0.003858,-0.003215,0.001358,-0.000242,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.186995,0.029434,0.006450,-0.001163,0.000121,-0.000085,0.000033,-0.000006,-0.222793,0.065496,0.014354,-0.002588,0.000270,-0.000189,0.000074,-0.000013,1.714986,-0.075674,-0.016585,0.002991,-0.000312,0.000219,-0.000086,0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.152210,0.039065,0.003216,-0.001065,-0.000008,0.000005,-0.000002,0.000000,-0.145389,0.086928,0.007157,-0.002371,-0.000017,0.000010,-0.000004,0.000001,1.625554,-0.100436,-0.008270,0.002739,0.000020,-0.000012,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.110999,0.042285,-0.000000,-0.001074,-0.000000,0.000001,-0.000000,0.000000,-0.053685,0.094094,-0.000000,-0.002391,0.000000,0.000001,-0.000001,0.000001,1.519600,-0.108715,0.000000,0.002762,-0.000000,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.069788,0.039064,-0.003216,-0.001065,0.000008,-0.000008,0.000008,-0.000006,0.038019,0.086928,-0.007157,-0.002371,0.000017,-0.000017,0.000017,-0.000013,1.413646,-0.100436,0.008270,0.002739,-0.000020,0.000019,-0.000019,0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.035004,0.029433,-0.006451,-0.001163,-0.000121,0.000057,-0.000130,0.000094,0.115423,0.065496,-0.014354,-0.002588,-0.000270,0.000126,-0.000290,0.000209,1.324214,-0.075674,0.016585,0.002991,0.000312,-0.000146,0.000335,-0.000242,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.013285,0.012718,-0.010080,-0.000395,0.001501,-0.000014,0.001894,-0.001238,0.163752,0.028300,-0.022430,-0.000878,0.003339,-0.000031,0.004214,-0.002756,1.268374,-0.032697,0.025916,0.001015,-0.003858,0.000036,-0.004869,0.003184,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-1.008900,0.000000,0.000000,0.000000,0.020267,-0.021794,0.010033,-0.001829,0.173510,0.000000,0.000000,0.000000,0.017204,-0.018500,0.008517,-0.001553,1.257100,0.000000,0.000000,-0.000000,-0.023203,0.024952,-0.011487,0.002094,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.002224,0.019490,0.015741,-0.000235,-0.002229,0.001845,-0.000775,0.000138,0.179177,0.016544,0.013362,-0.000200,-0.001892,0.001566,-0.000658,0.000117,1.249456,-0.022313,-0.018022,0.000269,0.002552,-0.002112,0.000888,-0.000157,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.968250,0.046886,0.011369,-0.001395,0.000179,-0.000124,0.000048,-0.000008,0.208016,0.039799,0.009650,-0.001184,0.000152,-0.000105,0.000041,-0.000007,1.210561,-0.053678,-0.013016,0.001597,-0.000205,0.000142,-0.000055,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.911296,0.065764,0.007563,-0.001250,-0.000011,0.000007,-0.000002,0.000000,0.256361,0.055822,0.006419,-0.001061,-0.000010,0.000006,-0.000002,0.000000,1.145356,-0.075290,-0.008658,0.001431,0.000013,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.839225,0.077117,0.003785,-0.001262,0.000001,-0.000000,0.000000,-0.000000,0.317535,0.065458,0.003212,-0.001071,0.000000,-0.000000,0.000000,-0.000000,1.062846,-0.088286,-0.004332,0.001445,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.759584,0.080903,0.000001,-0.001261,-0.000000,-0.000000,0.000000,-0.000000,0.385134,0.068669,-0.000000,-0.001071,0.000000,-0.000000,0.000000,-0.000000,0.971672,-0.092618,0.000000,0.001444,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.679941,0.077121,-0.003784,-0.001262,-0.000001,0.000001,-0.000000,0.000000,0.452732,0.065456,-0.003213,-0.001071,-0.000000,0.000001,-0.000000,0.000000,0.880498,-0.088285,0.004333,0.001445,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.607866,0.065770,-0.007562,-0.001250,0.000011,-0.000011,0.000010,-0.000008,0.513904,0.055820,-0.006419,-0.001061,0.000010,-0.000009,0.000009,-0.000007,0.797990,-0.075288,0.008658,0.001431,-0.000013,0.000012,-0.000012,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.550906,0.046892,-0.011370,-0.001396,-0.000179,0.000081,-0.000187,0.000138,0.562247,0.039796,-0.009650,-0.001184,-0.000152,0.000069,-0.000159,0.000117,0.732787,-0.053676,0.013016,0.001597,0.000205,-0.000093,0.000215,-0.000157,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.516927,0.019493,-0.015743,-0.000235,0.002230,-0.000008,0.002772,-0.001829,0.591083,0.016543,-0.013361,-0.000200,0.001892,-0.000007,0.002352,-0.001553,0.693893,-0.022312,0.018021,0.000269,-0.002552,0.000009,-0.003172,0.002094,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.510250,0.000000,0.000000,0.000000,0.027717,-0.029710,0.013657,-0.002488,0.596750,0.000000,0.000000,0.000000,-0.017125,0.018357,-0.008438,0.001537,0.686250,0.000000,0.000000,-0.000000,0.014073,-0.015085,0.006934,-0.001263,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.501073,0.026849,0.021823,-0.000150,-0.003038,0.002508,-0.001052,0.000186,0.591080,-0.016589,-0.013483,0.000093,0.001877,-0.001550,0.000650,-0.000115,0.690910,0.013634,0.011082,-0.000075,-0.001542,0.001274,-0.000534,0.000095,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.453946,0.065427,0.016360,-0.001740,0.000243,-0.000168,0.000065,-0.000011,0.561963,-0.040423,-0.010107,0.001075,-0.000150,0.000104,-0.000040,0.000007,0.714842,0.033227,0.008311,-0.000883,0.000123,-0.000085,0.000033,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.373771,0.093371,0.011658,-0.001541,-0.000015,0.000009,-0.000003,0.000001,0.512428,-0.057687,-0.007202,0.000952,0.000009,-0.000006,0.000002,-0.000000,0.755563,0.047427,0.005926,-0.000782,-0.000008,0.000004,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.270292,0.112031,0.006995,-0.001557,0.000001,-0.000000,0.000000,0.000000,0.448497,-0.069214,-0.004322,0.000962,-0.000001,0.000000,-0.000000,-0.000000,0.808129,0.056917,0.003560,-0.000791,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.152823,0.121352,0.002327,-0.001555,0.000000,-0.000000,-0.000000,0.000000,0.375923,-0.074974,-0.001439,0.000961,-0.000000,0.000000,-0.000000,0.000000,0.867815,0.061665,0.001188,-0.000791,-0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.030700,0.121340,-0.002338,-0.001555,0.000000,-0.000000,0.000000,-0.000000,0.300471,-0.074969,0.001443,0.000961,0.000000,0.000000,-0.000000,0.000000,0.929878,0.061669,-0.001184,-0.000791,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.086747,0.111999,-0.007003,-0.001556,-0.000001,0.000001,-0.000001,0.000001,0.227906,-0.069200,0.004326,0.000961,0.000000,-0.000001,0.000000,-0.000000,0.989572,0.056929,-0.003556,-0.000791,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.190187,0.093329,-0.011659,-0.001539,0.000016,-0.000014,0.000014,-0.000011,0.163993,-0.057667,0.007203,0.000951,-0.000010,0.000009,-0.000009,0.000007,1.042154,0.047444,-0.005925,-0.000783,0.000008,-0.000007,0.000007,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.270322,0.065389,-0.016354,-0.001737,-0.000243,0.000109,-0.000252,0.000186,0.114478,-0.040404,0.010105,0.001074,0.000150,-0.000067,0.000156,-0.000115,1.082893,0.033244,-0.008313,-0.000884,-0.000124,0.000055,-0.000128,0.000095,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.317420,0.026831,-0.021809,-0.000148,0.003035,-0.000005,0.003753,-0.002486,0.085376,-0.016579,0.013476,0.000092,-0.001876,0.000003,-0.002319,0.001536,1.106838,0.013642,-0.011088,-0.000076,0.001543,-0.000003,0.001908,-0.001264,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.326590,0.000000,0.000000,-0.000000,-0.012302,0.011952,-0.005241,0.000925,0.079709,0.000000,0.000000,0.000000,0.092652,-0.102569,0.047819,-0.008789,1.111500,0.000000,0.000000,-0.000000,-0.008252,0.009144,-0.004265,0.000784,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.321924,-0.014421,-0.013486,-0.002139,0.001211,-0.000925,0.000370,-0.000064,0.108822,0.083154,0.062939,-0.006314,-0.010519,0.008889,-0.003785,0.000677,1.108911,-0.007390,-0.005581,0.000577,0.000938,-0.000793,0.000338,-0.000060,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.292469,-0.045819,-0.017679,-0.001382,-0.000102,0.000093,-0.000091,0.000028,0.243862,0.174487,0.027215,-0.011505,0.000845,-0.000563,0.000142,-0.000008,1.096939,-0.015431,-0.002356,0.001039,-0.000075,0.000050,-0.000013,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.227517,-0.085619,-0.022292,-0.001711,-0.000033,-0.000162,0.000478,-0.000099,0.434475,0.195766,-0.005894,-0.011194,-0.000124,-0.000184,0.000664,-0.000133,1.080154,-0.017148,0.000634,0.001009,0.000009,0.000015,-0.000058,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.118077,-0.134108,-0.024161,0.002622,0.002855,-0.000617,-0.000271,0.000110,0.613377,0.152040,-0.034875,-0.004879,0.004283,-0.001022,-0.000135,0.000109,1.064626,-0.013010,0.003236,0.000439,-0.000379,0.000092,0.000008,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.035493,-0.167089,-0.007101,0.006287,-0.000458,-0.000032,0.000132,-0.000040,0.728899,0.079632,-0.033759,0.003165,0.000980,-0.000420,0.000078,-0.000003,1.055004,-0.006288,0.003138,-0.000302,-0.000106,0.000041,-0.000006,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.203794,-0.163913,0.009826,0.005368,-0.000044,0.000078,-0.000066,0.000034,0.778572,0.023877,-0.021472,0.004349,-0.000046,0.000006,-0.000003,0.000006,1.051481,-0.001172,0.001919,-0.000436,0.000004,0.000000,-0.000000,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.352510,-0.128097,0.026179,0.005855,0.000557,-0.000270,0.000606,-0.000432,0.785289,-0.006146,-0.008552,0.004383,0.000154,-0.000092,0.000207,-0.000130,1.051796,0.001371,0.000624,-0.000441,-0.000018,0.000010,-0.000023,0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.448111,-0.056679,0.044415,0.002398,-0.006810,0.000086,-0.008667,0.005638,0.775112,-0.009618,0.004962,0.003647,-0.001772,0.000130,-0.002619,0.001558,1.053335,0.001243,-0.000736,-0.000351,0.000206,-0.000013,0.000296,-0.000179,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/2/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.467730,0.000000,0.000000,0.000000,0.020090,-0.021691,0.010003,-0.001826,0.771400,0.000000,0.000000,0.000000,-0.017141,0.018508,-0.008535,0.001558,1.053800,0.000000,0.000000,0.000000,0.011769,-0.012707,0.005860,-0.001070,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.461154,0.019143,0.015336,-0.000389,-0.002220,0.001843,-0.000776,0.000138,0.765789,-0.016334,-0.013085,0.000332,0.001894,-0.001572,0.000662,-0.000118,1.057653,0.011215,0.008984,-0.000228,-0.001300,0.001080,-0.000455,0.000081,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.428078,0.045294,0.010534,-0.001536,0.000179,-0.000125,0.000049,-0.000008,0.737568,-0.038646,-0.008988,0.001310,-0.000152,0.000106,-0.000041,0.000007,1.077029,0.026535,0.006172,-0.000900,0.000105,-0.000073,0.000028,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.373691,0.062080,0.006306,-0.001391,-0.000012,0.000007,-0.000002,0.000000,0.691163,-0.052968,-0.005380,0.001187,0.000010,-0.000006,0.000002,-0.000000,1.108892,0.036370,0.003694,-0.000815,-0.000007,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.306702,0.070495,0.002104,-0.001403,0.000001,-0.000000,0.000000,-0.000000,0.634008,-0.060147,-0.001795,0.001197,-0.000001,0.000000,-0.000000,0.000000,1.148137,0.041300,0.001233,-0.000822,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.235505,0.070496,-0.002104,-0.001403,-0.000001,0.000001,-0.000001,0.000000,0.573263,-0.060146,0.001796,0.001197,0.000000,-0.000001,0.000000,-0.000000,1.189849,0.041302,-0.001232,-0.000822,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.168517,0.062081,-0.006306,-0.001391,0.000012,-0.000011,0.000011,-0.000008,0.516109,-0.052965,0.005380,0.001186,-0.000010,0.000009,-0.000009,0.000007,1.229098,0.036374,-0.003693,-0.000815,0.000007,-0.000006,0.000006,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.114129,0.045294,-0.010535,-0.001536,-0.000179,0.000082,-0.000189,0.000138,0.469709,-0.038642,0.008988,0.001310,0.000152,-0.000070,0.000161,-0.000118,1.260965,0.026540,-0.006172,-0.000900,-0.000105,0.000048,-0.000111,0.000081,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.081053,0.019143,-0.015336,-0.000388,0.002220,-0.000014,0.002778,-0.001826,0.441490,-0.016332,0.013084,0.000331,-0.001894,0.000012,-0.002370,0.001558,1.280346,0.011218,-0.008987,-0.000228,0.001301,-0.000008,0.001628,-0.001070,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.500000,0.000000,0.000000,0.000000,0.030855,-0.033073,0.015203,-0.002769,0.000000,0.000000,0.000000,0.000000,0.002072,-0.002221,0.001021,-0.000186,1.500000,0.000000,0.000000,0.000000,-0.016752,0.017956,-0.008254,0.001503,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.489784,0.029890,0.024296,-0.000166,-0.003382,0.002792,-0.001171,0.000207,0.000686,0.002008,0.001632,-0.000011,-0.000227,0.000187,-0.000079,0.000014,1.494454,-0.016228,-0.013191,0.000090,0.001836,-0.001516,0.000636,-0.000113,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.437316,0.072844,0.018218,-0.001936,0.000271,-0.000187,0.000072,-0.000013,0.004210,0.004893,0.001224,-0.000130,0.000018,-0.000013,0.000005,-0.000001,1.465969,-0.039547,-0.009890,0.001051,-0.000147,0.000102,-0.000039,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.348047,0.103966,0.012986,-0.001714,-0.000017,0.000010,-0.000003,0.000001,0.010208,0.006986,0.000874,-0.000115,-0.000001,0.000001,-0.000000,0.000000,1.417504,-0.056443,-0.007050,0.000931,0.000009,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.232819,0.124759,0.007799,-0.001733,0.000001,-0.000000,0.000000,-0.000000,0.017952,0.008386,0.000526,-0.000116,0.000000,-0.000000,-0.000000,0.000000,1.354949,-0.067729,-0.004233,0.000941,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.101994,0.135158,0.002601,-0.001732,-0.000000,0.000000,-0.000000,0.000000,0.026749,0.009090,0.000177,-0.000116,-0.000000,0.000000,-0.000000,0.000000,1.283927,-0.073373,-0.001411,0.000940,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.034033,0.135162,-0.002597,-0.001733,-0.000000,-0.000000,0.000000,-0.000000,0.035899,0.009095,-0.000173,-0.000117,-0.000000,0.000000,-0.000000,-0.000000,1.210084,-0.073373,0.001411,0.000940,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.164865,0.124769,-0.007796,-0.001734,-0.000001,0.000001,-0.000001,0.000001,0.044705,0.008399,-0.000523,-0.000117,-0.000000,0.000000,-0.000000,0.000000,1.139062,-0.067730,0.004233,0.000941,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.280105,0.103979,-0.012986,-0.001715,0.000017,-0.000016,0.000015,-0.000013,0.052464,0.007002,-0.000873,-0.000116,0.000001,-0.000001,0.000001,-0.000001,1.076506,-0.056443,0.007050,0.000931,-0.000009,0.000009,-0.000008,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.369386,0.072855,-0.018220,-0.001936,-0.000271,0.000121,-0.000281,0.000208,0.058477,0.004907,-0.001227,-0.000131,-0.000018,0.000008,-0.000019,0.000014,1.028042,-0.039548,0.009890,0.001051,0.000147,-0.000066,0.000153,-0.000113,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.421862,0.029895,-0.024300,-0.000166,0.003382,-0.000006,0.004182,-0.002770,0.062012,0.002014,-0.001637,-0.000011,0.000228,-0.000000,0.000282,-0.000187,0.999556,-0.016228,0.013191,0.000090,-0.001836,0.000003,-0.002270,0.001503,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.592600,0.000000,0.000000,0.000000,-0.044891,0.048462,-0.022348,0.004079,0.327910,0.000000,0.000000,0.000000,0.007363,-0.007971,0.003680,-0.000672,1.494700,0.000000,0.000000,0.000000,-0.002701,0.002926,-0.001351,0.000247,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.577902,-0.042789,-0.034289,0.000856,0.004959,-0.004117,0.001734,-0.000308,0.330310,0.006972,0.005554,-0.000181,-0.000816,0.000679,-0.000286,0.000051,1.493821,-0.002554,-0.002031,0.000070,0.000299,-0.000249,0.000105,-0.000019,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.503950,-0.101296,-0.023592,0.003422,-0.000398,0.000278,-0.000109,0.000019,0.342283,0.016311,0.003687,-0.000592,0.000070,-0.000045,0.000018,-0.000003,1.489441,-0.005958,-0.001338,0.000219,-0.000027,0.000016,-0.000007,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.382275,-0.138932,-0.014161,0.003104,0.000027,-0.000015,0.000005,-0.000001,0.361729,0.022050,0.002084,-0.000514,0.000003,0.000003,-0.000001,0.000000,1.482348,-0.008035,-0.000752,0.000186,-0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.232303,-0.157880,-0.004773,0.003139,0.000000,0.000001,0.000000,-0.000000,0.385355,0.024699,0.000577,-0.000490,0.000006,-0.000001,0.000000,-0.000000,1.473744,-0.008992,-0.000210,0.000176,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.072790,-0.158005,0.004652,0.003147,0.000004,-0.000003,0.000001,-0.000001,0.410146,0.024404,-0.000863,-0.000471,0.000003,-0.000000,0.000000,0.000000,1.464717,-0.008891,0.000308,0.000170,-0.000001,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.077414,-0.139256,0.014089,0.003128,-0.000024,0.000024,-0.000024,0.000019,0.433219,0.021277,-0.002257,-0.000456,0.000006,-0.000004,0.000004,-0.000003,1.456304,-0.007766,0.000815,0.000167,-0.000002,0.000001,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.199457,-0.101677,0.023613,0.003460,0.000403,-0.000185,0.000426,-0.000310,0.451786,0.015400,-0.003636,-0.000500,-0.000059,0.000027,-0.000063,0.000046,1.449520,-0.005633,0.001324,0.000185,0.000022,-0.000010,0.000023,-0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.273727,-0.042999,0.034437,0.000886,-0.004988,0.000031,-0.006244,0.004104,0.463000,0.006470,-0.005198,-0.000112,0.000746,-0.000004,0.000932,-0.000613,1.445414,-0.002371,0.001903,0.000043,-0.000274,0.000002,-0.000342,0.000225,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.288500,0.000000,0.000000,0.000000,0.017584,-0.018909,0.008705,-0.001587,0.465220,0.000000,0.000000,0.000000,-0.000032,-0.000017,0.000018,-0.000005,1.444600,0.000000,0.000000,-0.000000,0.003087,-0.003282,0.001503,-0.000273,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.282707,0.016910,0.013658,-0.000204,-0.001934,0.001601,-0.000673,0.000119,0.465185,-0.000135,-0.000183,-0.000091,-0.000002,0.000005,-0.000003,0.000001,1.445635,0.003043,0.002511,0.000030,-0.000335,0.000275,-0.000115,0.000020,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.253229,0.040683,0.009867,-0.001209,0.000156,-0.000108,0.000042,-0.000007,0.464777,-0.000771,-0.000450,-0.000087,0.000001,-0.000001,0.000000,-0.000000,1.451064,0.007643,0.002043,-0.000148,0.000027,-0.000018,0.000007,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.203806,0.057073,0.006570,-0.001081,-0.000009,0.000005,-0.000001,0.000000,0.463469,-0.001932,-0.000710,-0.000086,0.000000,-0.000000,0.000000,-0.000000,1.460617,0.011335,0.001658,-0.000126,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.141249,0.066952,0.003307,-0.001089,-0.000000,0.000003,-0.000007,0.000002,0.460741,-0.003610,-0.000967,-0.000085,-0.000000,0.000002,-0.000003,0.000001,1.473483,0.014270,0.001276,-0.000127,0.000000,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.072081,0.070290,0.000020,-0.001110,-0.000003,-0.000014,0.000044,-0.000009,0.456079,-0.005802,-0.001231,-0.000094,-0.000001,-0.000007,0.000020,-0.000004,1.488903,0.016443,0.000898,-0.000124,0.000001,0.000002,-0.000007,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.002863,0.067114,-0.003008,-0.000709,0.000266,-0.000060,-0.000019,0.000009,0.448960,-0.008494,-0.001377,0.000088,0.000121,-0.000027,-0.000009,0.000004,1.506117,0.017850,0.000479,-0.000187,-0.000042,0.000009,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.060731,0.059687,-0.004232,-0.000307,-0.000003,-0.000011,0.000009,-0.000002,0.439266,-0.010659,-0.000702,0.000271,-0.000001,-0.000005,0.000004,-0.000001,1.524229,0.018135,-0.000224,-0.000250,0.000000,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.115871,0.050272,-0.005195,-0.000327,-0.000000,0.000003,-0.000002,0.000001,0.428172,-0.011264,0.000093,0.000263,0.000001,0.000001,-0.000001,0.000000,1.541891,0.016940,-0.000970,-0.000248,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.160622,0.038907,-0.006164,-0.000315,0.000007,-0.000005,0.000005,-0.000004,0.417265,-0.010286,0.000887,0.000266,-0.000001,0.000002,-0.000002,0.000002,1.557612,0.014254,-0.001717,-0.000249,0.000002,-0.000002,0.000002,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.193053,0.025637,-0.007131,-0.000382,-0.000085,0.000036,-0.000086,0.000065,0.408134,-0.007707,0.001704,0.000297,0.000033,-0.000015,0.000034,-0.000024,1.569901,0.010070,-0.002480,-0.000283,-0.000039,0.000017,-0.000040,0.000029,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.211108,0.010013,-0.008343,0.000201,0.001084,0.000007,0.001310,-0.000880,0.402455,-0.003321,0.002635,0.000099,-0.000391,0.000003,-0.000493,0.000323,1.577176,0.004160,-0.003370,-0.000037,0.000473,-0.000001,0.000587,-0.000388,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.214500,0.000000,0.000000,0.000000,0.010067,-0.010835,0.004990,-0.000910,0.401310,0.000000,0.000000,-0.000000,0.012216,-0.013138,0.006049,-0.001103,1.578600,0.000000,0.000000,0.000000,-0.015462,0.016632,-0.007658,0.001396,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.217812,0.009663,0.007791,-0.000133,-0.001108,0.000918,-0.000385,0.000068,0.405334,0.011745,0.009484,-0.000144,-0.001344,0.001112,-0.000467,0.000083,1.573509,-0.014859,-0.011994,0.000188,0.001701,-0.001408,0.000592,-0.000105,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.234626,0.023168,0.005575,-0.000702,0.000094,-0.000062,0.000023,-0.000004,0.425804,0.028245,0.006843,-0.000842,0.000109,-0.000075,0.000029,-0.000005,1.547624,-0.035703,-0.008634,0.001069,-0.000140,0.000095,-0.000036,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.262719,0.032391,0.003681,-0.000616,-0.000004,0.000003,-0.000001,0.000000,0.460108,0.039606,0.004551,-0.000752,-0.000007,0.000004,-0.000001,0.000000,1.504281,-0.050023,-0.005731,0.000950,0.000008,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.298173,0.037900,0.001827,-0.000617,0.000001,-0.000000,0.000000,-0.000000,0.503509,0.046437,0.002277,-0.000760,0.000000,-0.000000,0.000000,-0.000000,1.449482,-0.058618,-0.002861,0.000958,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.337284,0.039704,-0.000022,-0.000616,0.000000,-0.000000,0.000000,-0.000000,0.551463,0.048712,-0.000002,-0.000759,0.000000,-0.000000,0.000000,-0.000000,1.388960,-0.061469,0.000010,0.000957,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.376349,0.037812,-0.001870,-0.000616,-0.000000,0.000000,-0.000000,0.000000,0.599415,0.046431,-0.002280,-0.000760,-0.000000,0.000001,-0.000000,0.000000,1.328458,-0.058578,0.002881,0.000957,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.411675,0.032224,-0.003715,-0.000610,0.000006,-0.000005,0.000005,-0.000004,0.642807,0.039594,-0.004554,-0.000752,0.000007,-0.000006,0.000006,-0.000005,1.273718,-0.049945,0.005748,0.000948,-0.000009,0.000008,-0.000008,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.439575,0.022963,-0.005573,-0.000681,-0.000088,0.000040,-0.000092,0.000067,0.677097,0.028228,-0.006845,-0.000840,-0.000108,0.000049,-0.000113,0.000083,1.230466,-0.035603,0.008635,0.001059,0.000136,-0.000061,0.000142,-0.000104,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.456212,0.009542,-0.007708,-0.000113,0.001091,-0.000004,0.001356,-0.000895,0.697551,0.011734,-0.009477,-0.000141,0.001342,-0.000005,0.001668,-0.001101,1.204669,-0.014798,0.011953,0.000178,-0.001692,0.000006,-0.002104,0.001389,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.459480,0.000000,0.000000,-0.000000,-0.006753,0.007262,-0.003343,0.000609,0.701570,0.000000,0.000000,-0.000000,-0.009620,0.010345,-0.004762,0.000868,1.199600,0.000000,0.000000,0.000000,0.021282,-0.022886,0.010536,-0.001921,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.457255,-0.006494,-0.005245,0.000078,0.000743,-0.000615,0.000258,-0.000046,0.698401,-0.009252,-0.007472,0.000111,0.001058,-0.000876,0.000368,-0.000065,1.206611,0.020466,0.016530,-0.000247,-0.002341,0.001938,-0.000814,0.000144,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.445934,-0.015624,-0.003789,0.000465,-0.000060,0.000041,-0.000016,0.000003,0.682273,-0.022258,-0.005398,0.000662,-0.000085,0.000059,-0.000023,0.000004,1.242286,0.049234,0.011938,-0.001465,0.000188,-0.000130,0.000051,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.426954,-0.021917,-0.002521,0.000416,0.000004,-0.000002,0.000001,-0.000000,0.655234,-0.031223,-0.003592,0.000593,0.000005,-0.000003,0.000001,-0.000000,1.302093,0.069057,0.007941,-0.001312,-0.000012,0.000007,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.402935,-0.025702,-0.001262,0.000421,-0.000000,0.000000,-0.000000,0.000000,0.621015,-0.036617,-0.001800,0.000599,-0.000000,0.000000,-0.000000,0.000000,1.377773,0.080978,0.003974,-0.001325,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.376391,-0.026965,-0.000001,0.000420,0.000000,0.000000,-0.000000,0.000000,0.583198,-0.038420,-0.000003,0.000599,0.000000,0.000000,0.000000,0.000000,1.461400,0.084952,0.000000,-0.001324,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.349845,-0.025706,0.001260,0.000421,0.000000,-0.000000,0.000000,-0.000000,0.545374,-0.036629,0.001794,0.000600,0.000000,-0.000000,0.000000,-0.000000,1.545027,0.080978,-0.003974,-0.001325,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.325821,-0.021924,0.002520,0.000417,-0.000004,0.000004,-0.000003,0.000003,0.511138,-0.031243,0.003590,0.000594,-0.000005,0.000005,-0.000005,0.000004,1.620707,0.069057,-0.007941,-0.001312,0.000012,-0.000011,0.000011,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.306833,-0.015632,0.003790,0.000465,0.000060,-0.000027,0.000062,-0.000046,0.484078,-0.022279,0.005400,0.000664,0.000085,-0.000038,0.000089,-0.000065,1.680514,0.049234,-0.011938,-0.001465,-0.000188,0.000085,-0.000197,0.000144,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.295506,-0.006498,0.005248,0.000079,-0.000743,0.000003,-0.000924,0.000610,0.467933,-0.009262,0.007480,0.000112,-0.001060,0.000004,-0.001317,0.000869,1.716189,0.020466,-0.016530,-0.000247,0.002341,-0.000009,0.002910,-0.001921,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.293280,0.000000,0.000000,0.000000,-0.011264,0.012113,-0.005576,0.001017,0.464760,0.000000,0.000000,-0.000000,0.026131,-0.028101,0.012937,-0.002359,1.723200,0.000000,0.000000,0.000000,-0.009511,0.010228,-0.004708,0.000858,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.289569,-0.010834,-0.008751,0.000129,0.001239,-0.001025,0.000431,-0.000076,0.473368,0.025127,0.020292,-0.000305,-0.002874,0.002379,-0.001000,0.000177,1.720067,-0.009147,-0.007388,0.000110,0.001046,-0.000866,0.000364,-0.000065,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.270681,-0.026070,-0.006325,0.000774,-0.000099,0.000069,-0.000027,0.000005,0.517164,0.060437,0.014650,-0.001801,0.000231,-0.000160,0.000062,-0.000011,1.704121,-0.022007,-0.005338,0.000654,-0.000084,0.000058,-0.000023,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.239007,-0.036579,-0.004214,0.000693,0.000006,-0.000004,0.000001,-0.000000,0.590572,0.084754,0.009737,-0.001613,-0.000015,0.000009,-0.000003,0.000001,1.677385,-0.030873,-0.003553,0.000586,0.000005,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.198911,-0.042912,-0.002116,0.000701,0.000000,0.000000,-0.000000,0.000000,0.683442,0.099360,0.004862,-0.001628,0.000001,-0.000000,0.000000,-0.000000,1.643548,-0.036210,-0.001781,0.000592,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.154585,-0.045039,-0.000011,0.000702,0.000000,0.000000,-0.000000,0.000000,0.786037,0.104203,-0.000017,-0.001625,0.000001,-0.000000,-0.000000,0.000000,1.606149,-0.037997,-0.000005,0.000592,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.110238,-0.042951,0.002100,0.000704,0.000000,-0.000001,0.000000,-0.000000,0.888599,0.099297,-0.004889,-0.001623,-0.000000,0.000001,-0.000001,0.000001,1.568739,-0.036230,0.001773,0.000593,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.070091,-0.036640,0.004208,0.000698,-0.000006,0.000006,-0.000006,0.000005,0.981384,0.084654,-0.009746,-0.001606,0.000015,-0.000014,0.000013,-0.000011,1.534875,-0.030904,0.003550,0.000588,-0.000005,0.000005,-0.000005,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.038355,-0.026129,0.006333,0.000779,0.000100,-0.000045,0.000104,-0.000077,1.054690,0.060340,-0.014637,-0.001793,-0.000230,0.000104,-0.000241,0.000177,1.508108,-0.022037,0.005342,0.000657,0.000084,-0.000038,0.000088,-0.000065,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.019419,-0.010864,0.008773,0.000132,-0.001243,0.000005,-0.001545,0.001020,1.098410,0.025078,-0.020256,-0.000300,0.002868,-0.000010,0.003565,-0.002353,1.492139,-0.009162,0.007399,0.000111,-0.001048,0.000004,-0.001303,0.000860,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.015698,0.000000,0.000000,0.000000,-0.016377,0.017620,-0.008113,0.001479,1.107000,0.000000,0.000000,0.000000,-0.026136,0.028078,-0.012920,0.002355,1.489000,0.000000,0.000000,0.000000,-0.001705,0.001830,-0.000842,0.000153,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.010307,-0.015731,-0.012693,0.000206,0.001802,-0.001492,0.000627,-0.000111,1.098377,-0.025191,-0.020386,0.000254,0.002872,-0.002375,0.000998,-0.000177,1.488437,-0.001646,-0.001335,0.000014,0.000187,-0.000155,0.000065,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.017086,-0.037769,-0.009114,0.001141,-0.000145,0.000100,-0.000039,0.000007,1.054370,-0.060841,-0.014891,0.001756,-0.000228,0.000160,-0.000062,0.000011,1.485556,-0.003989,-0.000984,0.000113,-0.000015,0.000010,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.062905,-0.052841,-0.006004,0.001018,0.000007,-0.000006,0.000002,-0.000000,0.980276,-0.085761,-0.010091,0.001584,0.000020,-0.000008,0.000003,-0.000001,1.480688,-0.005644,-0.000674,0.000103,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.120729,-0.061787,-0.002944,0.001017,-0.000003,0.000000,0.000000,-0.000000,0.886022,-0.101137,-0.005265,0.001626,0.000007,-0.000000,0.000001,-0.000000,1.474475,-0.006677,-0.000357,0.000108,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.184446,-0.064637,0.000089,0.001006,-0.000002,-0.000000,0.000000,-0.000000,0.781254,-0.106758,-0.000342,0.001657,0.000009,-0.000001,0.000001,-0.000000,1.467550,-0.007062,-0.000026,0.000112,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.247989,-0.061447,0.003098,0.001000,-0.000001,-0.000001,0.000000,-0.000000,0.675819,-0.102435,0.004685,0.001697,0.000012,-0.000002,0.000002,-0.000001,1.460574,-0.006775,0.000315,0.000114,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.305341,-0.052262,0.006079,0.000982,-0.000011,0.000009,-0.000008,0.000007,0.579777,-0.087936,0.009827,0.001721,-0.000006,0.000013,-0.000014,0.000011,1.454229,-0.005802,0.000658,0.000113,-0.000001,0.000001,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.350547,-0.037165,0.009057,0.001089,0.000140,-0.000063,0.000148,-0.000109,0.503393,-0.063082,0.015114,0.001947,0.000248,-0.000112,0.000256,-0.000187,1.449198,-0.004146,0.001002,0.000125,0.000016,-0.000007,0.000017,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.377451,-0.015416,0.012464,0.000169,-0.001760,0.000006,-0.002186,0.001444,0.457576,-0.026355,0.021232,0.000386,-0.003027,0.000013,-0.003772,0.002486,1.446191,-0.001726,0.001393,0.000022,-0.000198,0.000001,-0.000246,0.000162,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.382730,0.000000,0.000000,-0.000000,0.001781,-0.001915,0.000881,-0.000161,0.448540,0.000000,0.000000,0.000000,0.004218,-0.004537,0.002089,-0.000381,1.445600,0.000000,0.000000,0.000000,0.019076,-0.020514,0.009444,-0.001722,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.382143,0.001715,0.001386,-0.000019,-0.000196,0.000162,-0.000068,0.000012,0.449929,0.004055,0.003274,-0.000050,-0.000464,0.000384,-0.000161,0.000029,1.451884,0.018344,0.014816,-0.000222,-0.002098,0.001737,-0.000730,0.000129,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.379152,0.004131,0.001005,-0.000121,0.000016,-0.000011,0.000004,-0.000001,0.456995,0.009747,0.002359,-0.000292,0.000037,-0.000026,0.000010,-0.000002,1.483860,0.044128,0.010699,-0.001314,0.000168,-0.000117,0.000045,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.374128,0.005806,0.000674,-0.000109,-0.000001,0.000001,-0.000000,0.000000,0.468829,0.013659,0.001564,-0.000261,-0.000002,0.000001,-0.000000,0.000000,1.537463,0.061892,0.007116,-0.001176,-0.000011,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.367758,0.006825,0.000344,-0.000111,-0.000000,-0.000000,0.000000,-0.000000,0.483789,0.015998,0.000775,-0.000263,0.000000,-0.000000,0.000000,0.000000,1.605288,0.072572,0.003559,-0.001188,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.360699,0.007181,0.000011,-0.000112,-0.000000,-0.000000,0.000000,-0.000000,0.500299,0.016759,-0.000013,-0.000262,0.000000,0.000000,-0.000000,0.000000,1.680231,0.076127,-0.000003,-0.001187,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.353619,0.006867,-0.000327,-0.000113,-0.000000,0.000000,-0.000000,0.000000,0.516784,0.015950,-0.000796,-0.000260,0.000000,0.000000,-0.000000,0.000000,1.755168,0.072560,-0.003564,-0.001187,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.347193,0.005872,-0.000668,-0.000113,0.000001,-0.000001,0.000001,-0.000001,0.531679,0.013580,-0.001572,-0.000256,0.000003,-0.000002,0.000002,-0.000002,1.822977,0.061873,-0.007118,-0.001175,0.000011,-0.000010,0.000010,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.342101,0.004196,-0.001013,-0.000127,-0.000016,0.000007,-0.000017,0.000012,0.543432,0.009669,-0.002350,-0.000285,-0.000037,0.000017,-0.000039,0.000028,1.876559,0.044109,-0.010697,-0.001312,-0.000168,0.000076,-0.000176,0.000129,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.339059,0.001747,-0.001410,-0.000023,0.000200,-0.000001,0.000249,-0.000164,0.550435,0.004015,-0.003244,-0.000046,0.000459,-0.000002,0.000570,-0.000376,1.908520,0.018334,-0.014808,-0.000221,0.002097,-0.000008,0.002607,-0.001721,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.338460,0.000000,0.000000,0.000000,0.093860,-0.103662,0.048286,-0.008871,0.551810,0.000000,0.000000,0.000000,0.024154,-0.029168,0.014092,-0.002649,1.914800,0.000000,0.000000,0.000000,0.030940,-0.035559,0.016845,-0.003128,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.308847,0.084749,0.064539,-0.005944,-0.010643,0.009010,-0.003892,0.000709,0.558238,0.016779,0.008981,-0.005958,-0.003037,0.002762,-0.001311,0.000260,1.923897,0.025135,0.017026,-0.004426,-0.003674,0.003216,-0.001455,0.000277,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.170320,0.180080,0.029451,-0.011450,0.000835,-0.000762,0.000674,-0.000131,0.576712,0.012478,-0.013708,-0.007615,0.000202,-0.000444,0.000815,-0.000165,1.959995,0.040500,-0.002147,-0.006373,0.000268,-0.000387,0.000575,-0.000115,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.028377,0.207291,-0.000144,-0.006825,0.002559,-0.000561,-0.000178,0.000086,0.568275,-0.035462,-0.031028,-0.000735,0.004419,-0.000983,-0.000323,0.000151,1.992315,0.018864,-0.017330,-0.001714,0.002916,-0.000649,-0.000206,0.000098,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.230605,0.193495,-0.011733,-0.002743,0.000097,-0.000142,0.000082,-0.000017,0.504313,-0.087848,-0.018236,0.005916,-0.000074,-0.000192,0.000159,-0.000040,1.994294,-0.013069,-0.012497,0.002771,0.000012,-0.000140,0.000101,-0.000024,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.409645,0.161851,-0.019930,-0.002737,0.000013,-0.000008,0.000015,-0.000018,0.403999,-0.107153,-0.001307,0.005479,-0.000051,0.000069,-0.000056,0.000029,1.971447,-0.029968,-0.004512,0.002583,-0.000026,0.000036,-0.000027,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.548830,0.113755,-0.028294,-0.003088,-0.000423,0.000188,-0.000441,0.000325,0.301010,-0.093320,0.015281,0.005851,0.000456,-0.000229,0.000511,-0.000357,1.939545,-0.031246,0.003288,0.002724,0.000178,-0.000093,0.000206,-0.000140,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.630853,0.046786,-0.037986,-0.000314,0.005304,-0.000011,0.006563,-0.004345,0.229203,-0.043957,0.033451,0.003112,-0.005520,0.000112,-0.007165,0.004604,1.914460,-0.016004,0.011728,0.001700,-0.002118,0.000061,-0.002810,0.001781,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.646850,0.000000,0.000000,0.000000,-0.023283,0.025426,-0.011784,0.002158,0.213840,0.000000,0.000000,-0.000000,-0.010754,0.011743,-0.005443,0.000997,1.908800,0.000000,0.000000,-0.000000,0.006363,-0.006956,0.003225,-0.000591,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.639366,-0.021605,-0.016892,0.000963,0.002606,-0.002181,0.000925,-0.000165,0.210383,-0.009980,-0.007803,0.000444,0.001203,-0.001007,0.000427,-0.000076,1.910842,0.005890,0.004595,-0.000275,-0.000712,0.000597,-0.000253,0.000045,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.603016,-0.048589,-0.009774,0.002292,-0.000208,0.000150,-0.000059,0.000010,0.193592,-0.022448,-0.004519,0.001056,-0.000097,0.000069,-0.000027,0.000005,1.920730,0.013190,0.002621,-0.000633,0.000059,-0.000041,0.000016,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.546837,-0.061627,-0.003315,0.002142,0.000020,-0.000010,0.000004,-0.000001,0.167631,-0.028486,-0.001543,0.000987,0.000010,-0.000004,0.000002,-0.000001,1.935939,0.016642,0.000851,-0.000581,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.484050,-0.061786,0.003166,0.002162,-0.000010,0.000013,-0.000014,0.000011,0.138596,-0.028587,0.001449,0.001001,-0.000003,0.000006,-0.000006,0.000005,1.952850,0.016599,-0.000891,-0.000576,0.000005,-0.000004,0.000004,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.427592,-0.048952,0.009737,0.002346,0.000217,-0.000103,0.000235,-0.000168,0.112460,-0.022674,0.004499,0.001091,0.000101,-0.000048,0.000109,-0.000078,1.967984,0.013093,-0.002630,-0.000618,-0.000057,0.000027,-0.000062,0.000045,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.390904,-0.021851,0.017051,0.001015,-0.002642,0.000036,-0.003374,0.002191,0.095460,-0.010129,0.007901,0.000475,-0.001225,0.000017,-0.001566,0.001016,1.977782,0.005825,-0.004553,-0.000262,0.000703,-0.000009,0.000896,-0.000582,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.383330,0.000000,0.000000,0.000000,-0.003940,0.003930,-0.001745,0.000311,0.091948,0.000000,0.000000,0.000000,0.011068,-0.011957,0.005516,-0.001007,1.979800,0.000000,0.000000,-0.000000,-0.021059,0.022273,-0.010177,0.001846,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.381886,-0.004404,-0.003989,-0.000486,0.000408,-0.000308,0.000124,-0.000021,0.095568,0.010535,0.008433,-0.000221,-0.001221,0.001017,-0.000428,0.000076,1.972683,-0.021008,-0.017503,-0.000421,0.002275,-0.001858,0.000774,-0.000136,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.373212,-0.013146,-0.004655,-0.000188,-0.000010,0.000019,-0.000006,0.000001,0.113758,0.024899,0.005784,-0.000840,0.000103,-0.000068,0.000027,-0.000005,1.934806,-0.053779,-0.014953,0.000803,-0.000178,0.000123,-0.000047,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.355227,-0.022997,-0.005165,-0.000132,0.000023,-0.000001,0.000000,-0.000000,0.143658,0.034146,0.003502,-0.000739,-0.000000,0.000004,-0.000002,0.000000,1.866782,-0.081601,-0.012921,0.000660,0.000013,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.326955,-0.033634,-0.005428,-0.000044,0.000021,-0.000001,0.000001,-0.000000,0.180569,0.038943,0.001304,-0.000722,0.000006,-0.000000,-0.000000,0.000000,1.772928,-0.105433,-0.010902,0.000678,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.287871,-0.044535,-0.005431,0.000044,0.000024,0.000002,0.000000,-0.000000,0.220101,0.039411,-0.000824,-0.000695,0.000009,0.000002,-0.000001,0.000000,1.657271,-0.125201,-0.008863,0.000681,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.237975,-0.055159,-0.005137,0.000155,0.000029,-0.000001,0.000001,-0.000000,0.258004,0.035723,-0.002839,-0.000646,0.000015,0.000001,-0.000000,0.000000,1.523889,-0.140879,-0.006812,0.000686,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.177863,-0.064852,-0.004497,0.000272,0.000030,-0.000001,0.000001,-0.000000,0.290257,0.028171,-0.004678,-0.000575,0.000023,0.000003,-0.000001,0.000000,1.376885,-0.152441,-0.004748,0.000690,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.108816,-0.072910,-0.003500,0.000394,0.000030,-0.000003,0.000001,-0.000000,0.313201,0.017194,-0.006241,-0.000460,0.000036,0.000002,0.000001,0.000000,1.220387,-0.159865,-0.002676,0.000690,-0.000000,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.032828,-0.078616,-0.002153,0.000500,0.000023,-0.000003,0.000001,-0.000000,0.323733,0.003493,-0.007369,-0.000273,0.000064,0.000011,-0.000005,0.000001,1.058536,-0.163149,-0.000611,0.000684,-0.000004,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.047421,-0.081342,-0.000537,0.000570,0.000010,-0.000006,0.000001,-0.000000,0.319655,-0.011779,-0.007758,0.000012,0.000063,-0.000002,0.000009,-0.000003,0.895455,-0.162340,0.001407,0.000661,-0.000006,-0.000000,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.128726,-0.080692,0.001183,0.000560,-0.000017,-0.000008,0.000003,-0.000001,0.300197,-0.026979,-0.007280,0.000338,0.000100,-0.000001,-0.000003,0.000000,0.735177,-0.157570,0.003349,0.000633,-0.000007,0.000001,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.207695,-0.076734,0.002723,0.000459,-0.000028,-0.000000,0.000001,-0.000000,0.266373,-0.040143,-0.005707,0.000688,0.000067,-0.000014,0.000003,-0.000000,0.581583,-0.148998,0.005213,0.000613,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.281274,-0.070020,0.003938,0.000356,-0.000022,0.000003,-0.000000,0.000000,0.221267,-0.049282,-0.003350,0.000856,0.000024,-0.000007,0.000002,-0.000000,0.438409,-0.136740,0.007042,0.000608,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.347019,-0.061151,0.004898,0.000290,-0.000013,0.000001,-0.000000,0.000000,0.169509,-0.053344,-0.000686,0.000910,0.000008,-0.000002,0.000000,-0.000000,0.309319,-0.120835,0.008862,0.000606,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.402994,-0.050531,0.005703,0.000250,-0.000007,0.000001,0.000000,-0.000000,0.116396,-0.051960,0.002081,0.000931,0.000003,-0.000001,0.000000,-0.000000,0.197952,-0.101293,0.010680,0.000606,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.447579,-0.038400,0.006417,0.000226,-0.000007,0.000005,-0.000004,0.000004,0.067451,-0.044997,0.004881,0.000929,-0.000007,0.000007,-0.000007,0.000006,0.107944,-0.078118,0.012491,0.000595,-0.000011,0.000009,-0.000009,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.479339,-0.024891,0.007115,0.000289,0.000080,-0.000034,0.000080,-0.000061,0.028262,-0.032444,0.007710,0.001032,0.000126,-0.000057,0.000133,-0.000097,0.042911,-0.051345,0.014335,0.000738,0.000172,-0.000073,0.000171,-0.000129,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.496760,-0.009588,0.008045,-0.000263,-0.001024,-0.000009,-0.001229,0.000830,0.004664,-0.013596,0.010938,0.000219,-0.001566,0.000008,-0.001952,0.001286,0.006779,-0.020019,0.016694,-0.000420,-0.002163,-0.000015,-0.002612,0.001756,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.432080,0.000000,0.000000,0.000000,0.001632,-0.001731,0.000792,-0.000144,0.062700,0.000000,0.000000,0.000000,-0.002773,0.002943,-0.001347,0.000245,0.994010,0.000000,0.000000,0.000000,0.001836,-0.001949,0.000892,-0.000162,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.432629,0.001617,0.001340,0.000023,-0.000177,0.000145,-0.000060,0.000011,0.061768,-0.002745,-0.002273,-0.000037,0.000301,-0.000246,0.000103,-0.000018,0.994627,0.001818,0.001506,0.000025,-0.000199,0.000163,-0.000068,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.435528,0.004097,0.001115,-0.000071,0.000014,-0.000010,0.000004,-0.000001,0.056851,-0.006944,-0.001884,0.000123,-0.000024,0.000016,-0.000006,0.000001,0.997885,0.004600,0.001249,-0.000081,0.000016,-0.000011,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.440676,0.006140,0.000932,-0.000059,-0.000001,0.000000,-0.000000,0.000000,0.048133,-0.010389,-0.001568,0.000103,0.000002,-0.000001,0.000000,-0.000000,1.003661,0.006883,0.001039,-0.000068,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.447688,0.007824,0.000752,-0.000060,0.000000,-0.000000,0.000000,-0.000000,0.036280,-0.013213,-0.001255,0.000105,-0.000000,0.000000,-0.000000,0.000000,1.011515,0.008756,0.000833,-0.000069,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.456203,0.009146,0.000570,-0.000060,-0.000000,-0.000000,-0.000000,-0.000000,0.021916,-0.015410,-0.000942,0.000104,0.000000,0.000000,-0.000000,0.000000,1.021035,0.010214,0.000625,-0.000069,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.465859,0.010105,0.000389,-0.000061,-0.000000,-0.000000,-0.000000,-0.000000,0.005669,-0.016980,-0.000629,0.000104,-0.000000,-0.000000,0.000000,0.000000,1.031805,0.011258,0.000418,-0.000069,-0.000000,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.476293,0.010701,0.000207,-0.000061,-0.000000,-0.000000,0.000000,-0.000000,-0.011835,-0.017924,-0.000315,0.000104,0.000000,0.000000,-0.000000,0.000000,1.043413,0.011887,0.000211,-0.000069,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.487140,0.010932,0.000024,-0.000061,-0.000000,-0.000000,-0.000000,0.000000,-0.029969,-0.018241,-0.000002,0.000104,0.000000,0.000000,0.000000,-0.000000,1.055442,0.012102,0.000004,-0.000069,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.498034,0.010795,-0.000162,-0.000062,-0.000000,-0.000000,0.000000,0.000000,-0.048108,-0.017932,0.000311,0.000105,0.000000,0.000000,-0.000000,0.000000,1.067478,0.011902,-0.000204,-0.000069,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.508605,0.010283,-0.000351,-0.000064,-0.000000,0.000000,-0.000000,-0.000000,-0.065623,-0.016995,0.000625,0.000105,0.000000,0.000000,-0.000000,0.000000,1.079107,0.011286,-0.000412,-0.000069,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.518473,0.009389,-0.000544,-0.000065,-0.000000,0.000000,-0.000000,-0.000000,-0.081888,-0.015430,0.000939,0.000105,0.000000,0.000000,0.000000,0.000000,1.089910,0.010253,-0.000621,-0.000070,-0.000000,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.527252,0.008103,-0.000742,-0.000067,-0.000001,-0.000000,-0.000000,0.000000,-0.096274,-0.013237,0.001254,0.000105,0.000000,-0.000000,0.000000,-0.000000,1.099472,0.008801,-0.000831,-0.000070,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.534546,0.006417,-0.000945,-0.000068,0.000000,-0.000001,0.000001,-0.000001,-0.108152,-0.010413,0.001569,0.000104,-0.000001,0.000001,-0.000001,0.000001,1.107372,0.006929,-0.001041,-0.000070,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.539949,0.004319,-0.001157,-0.000082,-0.000015,0.000007,-0.000015,0.000011,-0.116893,-0.006964,0.001888,0.000124,0.000024,-0.000010,0.000024,-0.000018,1.113191,0.004637,-0.001256,-0.000083,-0.000016,0.000007,-0.000016,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.543016,0.001718,-0.001418,0.000018,0.000189,0.000001,0.000231,-0.000154,-0.121825,-0.002754,0.002280,-0.000037,-0.000302,-0.000001,-0.000367,0.000246,1.116477,0.001836,-0.001519,0.000024,0.000201,0.000001,0.000245,-0.000164,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.543600,0.000000,0.000000,0.000000,-0.004536,0.004900,-0.002260,0.000413,-0.122760,0.000000,0.000000,0.000000,0.036899,-0.039841,0.018374,-0.003354,1.117100,0.000000,0.000000,0.000000,0.000784,-0.000846,0.000390,-0.000071,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.542117,-0.004317,-0.003454,0.000092,0.000501,-0.000417,0.000175,-0.000031,-0.110682,0.035159,0.028165,-0.000715,-0.004077,0.003385,-0.001426,0.000253,1.117357,0.000749,0.000601,-0.000014,-0.000087,0.000072,-0.000030,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.534667,-0.010192,-0.002359,0.000349,-0.000041,0.000028,-0.000011,0.000002,-0.049937,0.083180,0.019342,-0.002821,0.000328,-0.000229,0.000089,-0.000016,1.118653,0.001777,0.000416,-0.000059,0.000007,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.522443,-0.013940,-0.001403,0.000312,0.000002,-0.000001,0.000001,-0.000000,0.049938,0.113998,0.011574,-0.002554,-0.000021,0.000012,-0.000004,0.000001,1.120790,0.002442,0.000251,-0.000055,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.507414,-0.015806,-0.000462,0.000314,-0.000000,0.000000,-0.000000,0.000000,0.172944,0.129441,0.003859,-0.002576,0.000001,-0.000001,0.000000,-0.000000,1.123428,0.002779,0.000085,-0.000056,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.491459,-0.015790,0.000478,0.000313,0.000000,-0.000000,0.000000,-0.000000,0.303668,0.129434,-0.003866,-0.002576,-0.000001,0.000002,-0.000001,0.000001,1.126237,0.002783,-0.000082,-0.000056,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.476459,-0.013896,0.001416,0.000310,-0.000003,0.000002,-0.000002,0.000002,0.426661,0.113979,-0.011579,-0.002553,0.000021,-0.000020,0.000020,-0.000016,1.128882,0.002453,-0.000248,-0.000055,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.464289,-0.010133,0.002359,0.000343,0.000040,-0.000018,0.000042,-0.000031,0.526513,0.083156,-0.019342,-0.002819,-0.000328,0.000151,-0.000348,0.000253,1.131032,0.001791,-0.000416,-0.000061,-0.000007,0.000003,-0.000007,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.456891,-0.004281,0.003430,0.000086,-0.000496,0.000003,-0.000621,0.000408,0.587237,0.035145,-0.028156,-0.000713,0.004075,-0.000025,0.005099,-0.003352,1.132340,0.000757,-0.000606,-0.000016,0.000088,-0.000001,0.000110,-0.000072,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.455420,0.000000,0.000000,0.000000,-0.033723,0.036265,-0.016695,0.003044,0.599310,0.000000,0.000000,0.000000,-0.021226,0.022826,-0.010508,0.001916,1.132600,0.000000,0.000000,0.000000,0.020713,-0.022274,0.010254,-0.001869,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.444311,-0.032430,-0.026192,0.000391,0.003709,-0.003070,0.001290,-0.000229,0.592318,-0.020412,-0.016486,0.000246,0.002335,-0.001933,0.000812,-0.000144,1.139423,0.019918,0.016087,-0.000240,-0.002278,0.001886,-0.000793,0.000141,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.387780,-0.078015,-0.018917,0.002322,-0.000298,0.000207,-0.000080,0.000014,0.556735,-0.049106,-0.011907,0.001461,-0.000187,0.000130,-0.000051,0.000009,1.174144,0.047917,0.011619,-0.001426,0.000183,-0.000127,0.000049,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.293012,-0.109426,-0.012583,0.002079,0.000019,-0.000011,0.000004,-0.000001,0.497085,-0.068877,-0.007921,0.001309,0.000012,-0.000007,0.000002,-0.000000,1.232351,0.067210,0.007729,-0.001277,-0.000012,0.000007,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.173094,-0.128314,-0.006296,0.002100,-0.000001,0.000000,-0.000000,0.000000,0.421602,-0.080768,-0.003964,0.001322,-0.000001,0.000000,-0.000000,0.000000,1.306007,0.078812,0.003868,-0.001290,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.040583,-0.134609,0.000001,0.002099,-0.000000,0.000000,-0.000000,0.000000,0.338191,-0.084733,-0.000001,0.001321,0.000000,0.000000,-0.000000,0.000000,1.387397,0.082680,0.000000,-0.001289,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.091926,-0.128311,0.006297,0.002100,0.000001,-0.000002,0.000001,-0.000001,0.254779,-0.080771,0.003963,0.001322,0.000001,-0.000001,0.000000,-0.000000,1.468789,0.078813,-0.003867,-0.001290,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.211841,-0.109422,0.012584,0.002079,-0.000019,0.000018,-0.000017,0.000014,0.179292,-0.068882,0.007921,0.001309,-0.000012,0.000011,-0.000011,0.000009,1.542445,0.067212,-0.007729,-0.001277,0.000012,-0.000011,0.000011,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.306604,-0.078011,0.018917,0.002321,0.000298,-0.000135,0.000312,-0.000229,0.119637,-0.049110,0.011908,0.001462,0.000187,-0.000085,0.000196,-0.000144,1.600654,0.047919,-0.011619,-0.001426,-0.000183,0.000083,-0.000192,0.000141,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.363132,-0.032428,0.026191,0.000391,-0.003709,0.000014,-0.004611,0.003043,0.084051,-0.020415,0.016488,0.000246,-0.002335,0.000009,-0.002903,0.001916,1.635376,0.019919,-0.016088,-0.000240,0.002278,-0.000008,0.002832,-0.001869,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.374240,0.000000,0.000000,0.000000,-0.009160,0.009940,-0.004594,0.000840,0.077058,0.000000,0.000000,0.000000,-0.037278,0.040455,-0.018699,0.003418,1.642200,0.000000,0.000000,0.000000,-0.031010,0.033653,-0.015555,0.002843,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.377214,-0.008626,-0.006838,0.000267,0.001018,-0.000848,0.000358,-0.000064,0.064954,-0.035104,-0.027824,0.001089,0.004142,-0.003452,0.001458,-0.000260,1.632132,-0.029200,-0.023143,0.000907,0.003445,-0.002872,0.001213,-0.000216,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.391948,-0.019970,-0.004380,0.000788,-0.000082,0.000058,-0.000023,0.000004,0.005004,-0.081247,-0.017807,0.003210,-0.000335,0.000235,-0.000092,0.000016,1.582266,-0.067576,-0.014808,0.002671,-0.000279,0.000195,-0.000077,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.415554,-0.026515,-0.002190,0.000722,0.000005,-0.000003,0.000001,-0.000000,-0.091016,-0.107836,-0.008882,0.002940,0.000022,-0.000013,0.000005,-0.000001,1.502407,-0.089681,-0.007380,0.002447,0.000018,-0.000010,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.443533,-0.028718,-0.000011,0.000728,0.000000,-0.000000,0.000000,-0.000000,-0.204782,-0.116734,-0.000005,0.002965,0.000000,-0.000001,0.000001,-0.000001,1.407804,-0.097063,0.000007,0.002467,-0.000000,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.471535,-0.026557,0.002172,0.000725,-0.000004,0.000005,-0.000005,0.000004,-0.318556,-0.107855,0.008875,0.002942,-0.000021,0.000021,-0.000021,0.000016,1.313214,-0.089654,0.007391,0.002444,-0.000019,0.000017,-0.000017,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.495195,-0.020032,0.004380,0.000796,0.000083,-0.000039,0.000089,-0.000064,-0.414599,-0.081272,0.017808,0.003213,0.000335,-0.000157,0.000360,-0.000260,1.233391,-0.067536,0.014807,0.002666,0.000278,-0.000130,0.000299,-0.000216,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.509983,-0.008663,0.006863,0.000272,-0.001023,0.000010,-0.001291,0.000844,-0.474571,-0.035118,0.027834,0.001091,-0.004144,0.000039,-0.005230,0.003420,1.183560,-0.029177,0.023127,0.000903,-0.003442,0.000032,-0.004344,0.002841,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.512970,0.000000,0.000000,0.000000,0.008436,-0.009087,0.004186,-0.000764,-0.486680,0.000000,0.000000,0.000000,0.054899,-0.059034,0.027176,-0.004954,1.173500,0.000000,0.000000,0.000000,0.008073,-0.008682,0.003997,-0.000729,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.510198,0.008082,0.006506,-0.000125,-0.000930,0.000770,-0.000324,0.000058,-0.468594,0.052800,0.042648,-0.000632,-0.006038,0.004998,-0.002100,0.000373,1.176159,0.007763,0.006269,-0.000094,-0.000888,0.000735,-0.000309,0.000055,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.496160,0.019313,0.004607,-0.000605,0.000076,-0.000052,0.000020,-0.000004,-0.376546,0.127041,0.030817,-0.003776,0.000484,-0.000336,0.000131,-0.000023,1.189690,0.018672,0.004525,-0.000557,0.000071,-0.000050,0.000019,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.472805,0.026853,0.002960,-0.000536,-0.000001,0.000003,-0.000001,0.000000,-0.222208,0.178228,0.020515,-0.003383,-0.000032,0.000018,-0.000006,0.000001,1.212367,0.026178,0.003002,-0.000502,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.443527,0.031171,0.001363,-0.000528,0.000002,-0.000001,0.000000,0.000000,-0.026868,0.209042,0.010283,-0.003419,0.000001,-0.000000,0.000000,-0.000000,1.241042,0.030664,0.001481,-0.000509,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.411520,0.032317,-0.000216,-0.000525,0.000001,0.000001,0.000001,-0.000000,0.189039,0.219355,0.000031,-0.003417,-0.000000,-0.000000,-0.000000,0.000000,1.272677,0.032097,-0.000048,-0.000510,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.379942,0.030324,-0.001762,-0.000497,0.000013,0.000003,-0.000002,0.000000,0.405007,0.209162,-0.010227,-0.003424,-0.000004,0.000002,-0.000001,0.000001,1.304217,0.030475,-0.001570,-0.000503,0.000004,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.351862,0.025369,-0.003161,-0.000434,0.000015,-0.000007,0.000004,-0.000003,0.600517,0.178434,-0.020492,-0.003399,0.000031,-0.000028,0.000028,-0.000023,1.332623,0.025846,-0.003047,-0.000478,0.000009,-0.000005,0.000004,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.330079,0.017772,-0.004449,-0.000471,-0.000065,0.000029,-0.000068,0.000051,0.755068,0.127245,-0.030842,-0.003793,-0.000485,0.000220,-0.000509,0.000373,1.354948,0.018327,-0.004489,-0.000527,-0.000069,0.000031,-0.000072,0.000053,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.317281,0.007289,-0.005926,-0.000039,0.000824,-0.000001,0.001019,-0.000675,0.847278,0.052902,-0.042724,-0.000642,0.006052,-0.000022,0.007523,-0.004966,1.368203,0.007587,-0.006140,-0.000076,0.000865,-0.000003,0.001073,-0.000709,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.314790,0.000000,0.000000,-0.000000,-0.012835,0.014124,-0.006568,0.001205,0.865400,0.000000,0.000000,-0.000000,-0.018531,0.019542,-0.008917,0.001616,1.370800,0.000000,0.000000,-0.000000,-0.004537,0.004746,-0.002158,0.000390,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.318863,-0.011690,-0.008978,0.000724,0.001448,-0.001220,0.000519,-0.000093,0.859110,-0.018604,-0.015582,-0.000475,0.001995,-0.001626,0.000676,-0.000119,1.369242,-0.004632,-0.003932,-0.000185,0.000484,-0.000392,0.000162,-0.000028,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.338152,-0.025315,-0.004479,0.001448,-0.000119,0.000086,-0.000036,0.000007,0.825373,-0.048124,-0.013661,0.000599,-0.000157,0.000106,-0.000039,0.000006,1.360718,-0.012301,-0.003667,0.000080,-0.000038,0.000025,-0.000009,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.366561,-0.030144,-0.000386,0.001352,0.000011,-0.000014,0.000019,-0.000006,0.764103,-0.073938,-0.012201,0.000469,0.000008,0.000002,-0.000011,0.000004,1.344809,-0.019466,-0.003509,0.000049,0.000001,0.000003,-0.000007,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.395729,-0.026815,0.003751,0.001419,0.000009,0.000037,-0.000112,0.000023,0.678435,-0.096933,-0.010812,0.000438,-0.000007,-0.000028,0.000083,-0.000017,1.321883,-0.026344,-0.003382,0.000027,-0.000004,-0.000016,0.000048,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.417417,-0.015347,0.007235,0.000391,-0.000681,0.000153,0.000049,-0.000023,0.571160,-0.117030,-0.008928,0.001199,0.000504,-0.000111,-0.000042,0.000019,1.292202,-0.032905,-0.002972,0.000467,0.000292,-0.000066,-0.000019,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.425640,-0.001530,0.006102,-0.000631,0.000011,0.000030,-0.000029,0.000006,0.446771,-0.129943,-0.003639,0.001939,-0.000011,-0.000033,0.000054,-0.000011,1.257007,-0.036663,-0.000576,0.000913,-0.000003,-0.000010,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.421681,0.008846,0.004274,-0.000644,-0.000053,0.000018,-0.000023,0.000004,0.315128,-0.131364,0.002362,0.002260,0.000248,-0.000065,0.000013,0.000001,1.220669,-0.035136,0.002046,0.000794,-0.000068,0.000024,-0.000016,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.409259,0.015230,0.001940,-0.001004,-0.000177,0.000038,0.000017,-0.000010,0.188584,-0.119103,0.010210,0.002918,0.000173,-0.000034,-0.000028,0.000022,1.188315,-0.028897,0.004058,0.000505,-0.000124,0.000034,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.393226,0.015611,-0.001710,-0.001343,-0.000084,0.000052,-0.000106,0.000071,0.082743,-0.089415,0.019716,0.003494,0.000363,-0.000177,0.000399,-0.000286,1.163893,-0.019578,0.005200,0.000387,0.000071,-0.000025,0.000066,-0.000051,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.380736,0.007941,-0.005838,-0.000820,0.001047,-0.000031,0.001387,-0.000880,0.016837,-0.038543,0.030585,0.001150,-0.004540,0.000042,-0.005724,0.003745,1.149962,-0.007824,0.006443,-0.000062,-0.000865,-0.000003,-0.001056,0.000705,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.377930,0.000000,0.000000,-0.000000,0.031343,-0.033928,0.015665,-0.002861,0.003553,0.000000,0.000000,-0.000000,0.034024,-0.036746,0.016949,-0.003094,1.147300,0.000000,0.000000,0.000000,0.001343,-0.001242,0.000530,-0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.367711,0.029692,0.023663,-0.000759,-0.003473,0.002890,-0.001221,0.000218,0.014686,0.032401,0.025942,-0.000676,-0.003760,0.003123,-0.001316,0.000234,1.147840,0.001701,0.001664,0.000345,-0.000124,0.000087,-0.000027,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.316702,0.069494,0.015700,-0.002556,0.000278,-0.000202,0.000095,-0.000017,0.070633,0.076572,0.017755,-0.002619,0.000303,-0.000212,0.000085,-0.000015,1.151489,0.005862,0.002483,0.000284,0.000012,0.000010,-0.000043,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.233909,0.093782,0.008750,-0.002159,0.000095,-0.000015,-0.000012,0.000004,0.162501,0.104779,0.010553,-0.002354,-0.000007,0.000008,-0.000005,0.000001,1.160105,0.011581,0.003046,-0.000120,-0.000273,0.000061,0.000019,-0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.133463,0.105071,0.002612,-0.002007,-0.000001,-0.000005,0.000004,-0.000001,0.275477,0.118818,0.003486,-0.002355,0.000001,-0.000001,0.000001,-0.000000,1.174410,0.016580,0.001759,-0.000532,0.000004,0.000012,-0.000010,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.027791,0.104260,-0.003428,-0.002017,-0.000001,0.000002,-0.000001,0.000001,0.395426,0.118724,-0.003580,-0.002356,-0.000001,0.000002,-0.000001,0.000001,1.192226,0.018535,0.000209,-0.000509,0.000001,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.071024,0.091356,-0.009468,-0.001999,0.000017,-0.000016,0.000016,-0.000012,0.508214,0.104499,-0.010636,-0.002335,0.000019,-0.000018,0.000018,-0.000014,1.210462,0.017428,-0.001315,-0.000506,0.000003,-0.000003,0.000003,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.150918,0.066419,-0.015547,-0.002210,-0.000261,0.000119,-0.000276,0.000201,0.599747,0.076216,-0.017738,-0.002579,-0.000301,0.000138,-0.000318,0.000232,1.226070,0.013280,-0.002850,-0.000550,-0.000056,0.000026,-0.000060,0.000043,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.199364,0.028002,-0.022460,-0.000534,0.003240,-0.000019,0.004051,-0.002664,0.655397,0.032204,-0.025803,-0.000650,0.003733,-0.000023,0.004671,-0.003071,1.235904,0.005781,-0.004566,-0.000200,0.000686,-0.000007,0.000868,-0.000567,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/3/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.208980,0.000000,0.000000,0.000000,0.019598,-0.021160,0.009758,-0.001781,0.666460,0.000000,0.000000,0.000000,-0.017295,0.018674,-0.008612,0.001572,1.237900,0.000000,0.000000,0.000000,0.013119,-0.014165,0.006532,-0.001192,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.215395,0.018674,0.014960,-0.000379,-0.002165,0.001798,-0.000757,0.000135,0.660799,-0.016480,-0.013203,0.000334,0.001911,-0.001586,0.000668,-0.000119,1.242194,0.012501,0.010015,-0.000254,-0.001449,0.001203,-0.000507,0.000090,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.247661,0.044184,0.010276,-0.001498,0.000174,-0.000122,0.000047,-0.000008,0.632324,-0.038993,-0.009069,0.001322,-0.000154,0.000107,-0.000042,0.000007,1.263793,0.029577,0.006879,-0.001003,0.000117,-0.000081,0.000032,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.300716,0.060560,0.006151,-0.001357,-0.000011,0.000007,-0.000002,0.000000,0.585503,-0.053444,-0.005428,0.001197,0.000010,-0.000006,0.000002,-0.000000,1.299309,0.040539,0.004118,-0.000908,-0.000008,0.000004,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.366063,0.068769,0.002053,-0.001369,0.000001,-0.000000,0.000000,-0.000000,0.527833,-0.060689,-0.001812,0.001208,-0.000001,0.000000,-0.000000,0.000000,1.343053,0.046034,0.001374,-0.000916,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.435516,0.068769,-0.002053,-0.001369,-0.000001,0.000001,-0.000001,0.000000,0.466541,-0.060689,0.001811,0.001208,0.000001,-0.000001,0.000000,-0.000000,1.389545,0.046035,-0.001374,-0.000916,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.500864,0.060560,-0.006151,-0.001357,0.000011,-0.000011,0.000010,-0.000008,0.408870,-0.053445,0.005428,0.001197,-0.000010,0.000009,-0.000009,0.000007,1.433290,0.040540,-0.004117,-0.000908,0.000007,-0.000007,0.000007,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.553919,0.044185,-0.010276,-0.001498,-0.000174,0.000080,-0.000185,0.000135,0.362048,-0.038994,0.009069,0.001322,0.000154,-0.000071,0.000163,-0.000119,1.468806,0.029578,-0.006879,-0.001003,-0.000117,0.000054,-0.000124,0.000090,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.586185,0.018675,-0.014961,-0.000379,0.002165,-0.000013,0.002710,-0.001781,0.333572,-0.016481,0.013203,0.000335,-0.001911,0.000012,-0.002391,0.001572,1.490405,0.012501,-0.010015,-0.000254,0.001449,-0.000009,0.001814,-0.001192,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.000000,0.000000,0.000000,0.000000,0.013231,-0.014184,0.006520,-0.001188,0.000000,0.000000,0.000000,0.000000,0.027638,-0.029626,0.013619,-0.002481,1.500000,0.000000,0.000000,0.000000,-0.028437,0.030481,-0.014012,0.002552,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.004380,0.012814,0.010414,-0.000074,-0.001450,0.001198,-0.000502,0.000089,0.009150,0.026771,0.021759,-0.000151,-0.003029,0.002501,-0.001049,0.000186,1.490585,-0.027547,-0.022392,0.000153,0.003117,-0.002573,0.001080,-0.000191,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.026868,0.031216,0.007799,-0.000833,0.000116,-0.000080,0.000031,-0.000005,0.056138,0.065231,0.016307,-0.001736,0.000242,-0.000168,0.000065,-0.000011,1.442230,-0.067133,-0.016789,0.001784,-0.000249,0.000173,-0.000067,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.065112,0.044529,0.005549,-0.000737,-0.000007,0.000004,-0.000002,0.000000,0.136069,0.093080,0.011615,-0.001538,-0.000015,0.000009,-0.000003,0.000001,1.359961,-0.095813,-0.011967,0.001580,0.000016,-0.000009,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.114449,0.053401,0.003322,-0.000743,0.000001,-0.000000,-0.000000,0.000000,0.239217,0.111665,0.006964,-0.001553,0.000002,-0.000000,-0.000000,0.000000,1.253771,-0.114972,-0.007185,0.001598,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.170430,0.057821,0.001099,-0.000740,0.000000,-0.000000,0.000000,-0.000000,0.356293,0.120938,0.002312,-0.001549,0.000000,-0.000000,-0.000000,0.000000,1.133211,-0.124551,-0.002394,0.001596,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.228610,0.057800,-0.001120,-0.000740,0.000000,-0.000000,0.000000,-0.000000,0.477994,0.120915,-0.002335,-0.001549,0.000000,-0.000000,0.000000,-0.000000,1.007862,-0.124550,0.002395,0.001596,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.284550,0.053340,-0.003339,-0.000740,-0.000000,0.000001,-0.000000,0.000000,0.595025,0.111599,-0.006981,-0.001550,-0.000001,0.000001,-0.000001,0.000001,0.887303,-0.114970,0.007185,0.001598,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.333811,0.044443,-0.005555,-0.000732,0.000007,-0.000007,0.000007,-0.000005,0.698094,0.092992,-0.011619,-0.001533,0.000015,-0.000014,0.000014,-0.000011,0.781115,-0.095811,0.011967,0.001580,-0.000016,0.000015,-0.000014,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.371969,0.031135,-0.007788,-0.000827,-0.000116,0.000052,-0.000120,0.000089,0.777938,0.065151,-0.016296,-0.001731,-0.000242,0.000108,-0.000251,0.000186,0.698848,-0.067131,0.016789,0.001784,0.000249,-0.000112,0.000259,-0.000191,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.394394,0.012775,-0.010384,-0.000070,0.001445,-0.000002,0.001787,-0.001183,0.824863,0.026732,-0.021730,-0.000148,0.003024,-0.000005,0.003739,-0.002476,0.650495,-0.027546,0.022391,0.000153,-0.003117,0.000005,-0.003853,0.002552,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.231270,0.000000,0.000000,0.000000,-0.045714,0.049375,-0.022774,0.004157,0.480390,0.000000,0.000000,-0.000000,0.003558,-0.003855,0.001781,-0.000325,1.974700,0.000000,0.000000,0.000000,-0.025473,0.027487,-0.012673,0.002313,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.246226,-0.043525,-0.034844,0.000914,0.005051,-0.004197,0.001768,-0.000314,0.481548,0.003364,0.002676,-0.000092,-0.000394,0.000329,-0.000139,0.000025,1.966354,-0.024306,-0.019496,0.000464,0.002813,-0.002333,0.000983,-0.000175,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.321372,-0.102840,-0.023840,0.003513,-0.000411,0.000284,-0.000111,0.000019,0.487316,0.007847,0.001762,-0.000289,0.000035,-0.000022,0.000009,-0.000001,1.924304,-0.057644,-0.013481,0.001930,-0.000222,0.000158,-0.000062,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.444758,-0.140738,-0.014187,0.003166,0.000021,-0.000016,0.000006,-0.000001,0.496656,0.010574,0.000982,-0.000249,0.000003,0.000002,-0.000001,0.000000,1.854993,-0.079209,-0.008142,0.001765,0.000020,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.596508,-0.159582,-0.004655,0.003175,-0.000005,0.000001,-0.000000,-0.000000,0.507966,0.011804,0.000257,-0.000234,0.000004,-0.000000,-0.000000,0.000000,1.769421,-0.090148,-0.002781,0.001799,0.000002,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.757574,-0.159383,0.004847,0.003163,-0.000001,-0.000002,0.000001,-0.000001,0.519797,0.011630,-0.000426,-0.000223,0.000002,0.000000,-0.000000,0.000000,1.678293,-0.090305,0.002628,0.001807,0.000002,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.908951,-0.140216,0.014305,0.003127,-0.000027,0.000025,-0.000024,0.000019,0.530780,0.010118,-0.001082,-0.000214,0.000003,-0.000002,0.000002,-0.000001,1.592423,-0.079628,0.008044,0.001794,-0.000014,0.000014,-0.000014,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.031742,-0.102221,0.023810,0.003451,0.000403,-0.000185,0.000427,-0.000311,0.539603,0.007313,-0.001731,-0.000236,-0.000028,0.000013,-0.000030,0.000022,1.522629,-0.058153,0.013501,0.001981,0.000230,-0.000106,0.000243,-0.000177,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.106368,-0.043178,0.034601,0.000864,-0.005004,0.000030,-0.006261,0.004116,0.544927,0.003070,-0.002468,-0.000052,0.000354,-0.000002,0.000442,-0.000291,1.480150,-0.024595,0.019697,0.000507,-0.002853,0.000018,-0.003572,0.002347,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-1.121200,0.000000,0.000000,0.000000,0.019920,-0.021278,0.009766,-0.001777,0.545980,0.000000,0.000000,0.000000,0.001037,-0.001103,0.000506,-0.000092,1.471700,0.000000,0.000000,0.000000,0.013680,-0.014627,0.006716,-0.001222,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.114569,0.019447,0.015913,0.000025,-0.002175,0.001791,-0.000750,0.000133,0.546327,0.001020,0.000841,0.000009,-0.000113,0.000093,-0.000039,0.000007,1.476247,0.013325,0.010883,-0.000009,-0.001495,0.001232,-0.000516,0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.080186,0.048031,0.012383,-0.001122,0.000173,-0.000120,0.000046,-0.000008,0.548145,0.002557,0.000681,-0.000050,0.000009,-0.000006,0.000002,-0.000000,1.499759,0.032789,0.008384,-0.000794,0.000120,-0.000082,0.000032,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-1.020802,0.069745,0.009381,-0.000985,-0.000013,0.000006,-0.000002,0.000000,0.551338,0.003785,0.000551,-0.000041,0.000000,0.000000,0.000000,-0.000000,1.540202,0.047395,0.006258,-0.000695,-0.000007,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.942670,0.085520,0.006383,-0.001008,-0.000003,-0.000000,-0.000000,0.000000,0.555634,0.004766,0.000431,-0.000039,0.000001,-0.000000,0.000000,-0.000000,1.593156,0.057812,0.004157,-0.000701,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.851778,0.095249,0.003338,-0.001023,-0.000004,0.000001,-0.000000,0.000000,0.560793,0.005515,0.000318,-0.000038,-0.000001,-0.000001,0.000000,-0.000000,1.654426,0.064028,0.002060,-0.000697,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.754218,0.098839,0.000243,-0.001041,-0.000005,0.000001,-0.000000,0.000000,0.566586,0.006031,0.000194,-0.000046,-0.000003,-0.000001,0.000000,-0.000000,1.719817,0.066059,-0.000028,-0.000695,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.656181,0.096186,-0.002906,-0.001059,-0.000005,0.000001,-0.000000,0.000000,0.572762,0.006269,0.000036,-0.000060,-0.000004,-0.000001,0.000000,-0.000000,1.785153,0.063919,-0.002110,-0.000693,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.563963,0.087182,-0.006107,-0.001076,-0.000005,0.000001,-0.000001,0.000000,0.579002,0.006140,-0.000175,-0.000082,-0.000007,-0.000001,-0.000000,0.000000,1.846269,0.057620,-0.004189,-0.000693,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.483968,0.071727,-0.009349,-0.001077,0.000009,-0.000010,0.000010,-0.000008,0.584877,0.005513,-0.000469,-0.000115,-0.000009,-0.000002,0.000002,-0.000001,1.899008,0.047166,-0.006261,-0.000684,0.000008,-0.000007,0.000007,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.422667,0.049783,-0.012655,-0.001235,-0.000184,0.000081,-0.000188,0.000140,0.589796,0.004188,-0.000881,-0.000169,-0.000026,0.000010,-0.000019,0.000014,1.939230,0.032588,-0.008353,-0.000781,-0.000118,0.000052,-0.000122,0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.386925,0.020286,-0.016546,-0.000041,0.002281,-0.000001,0.002813,-0.001866,0.592912,0.001843,-0.001446,-0.000076,0.000220,-0.000002,0.000281,-0.000183,1.962587,0.013229,-0.010811,-0.000001,0.001483,0.000000,0.001825,-0.001212,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.380000,0.000000,0.000000,-0.000000,-0.009646,0.010375,-0.004776,0.000871,0.593550,0.000000,0.000000,0.000000,-0.002559,0.002751,-0.001266,0.000231,1.967100,0.000000,0.000000,0.000000,-0.024258,0.026086,-0.012009,0.002189,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.383177,-0.009273,-0.007487,0.000115,0.001061,-0.000878,0.000369,-0.000066,0.592706,-0.002464,-0.001992,0.000027,0.000281,-0.000233,0.000098,-0.000017,1.959109,-0.023328,-0.018842,0.000281,0.002668,-0.002209,0.000928,-0.000165,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.399335,-0.022292,-0.005397,0.000667,-0.000085,0.000059,-0.000023,0.000004,0.588407,-0.005938,-0.001446,0.000174,-0.000022,0.000016,-0.000006,0.000001,1.918443,-0.056123,-0.013610,0.001670,-0.000214,0.000149,-0.000058,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.426402,-0.031241,-0.003578,0.000597,0.000005,-0.000003,0.000001,-0.000000,0.581185,-0.008349,-0.000971,0.000156,0.000002,-0.000001,0.000000,-0.000000,1.850267,-0.078723,-0.009055,0.001495,0.000014,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.460621,-0.036596,-0.001776,0.000601,-0.000001,0.000000,-0.000000,0.000000,0.572022,-0.009819,-0.000497,0.000159,0.000000,0.000000,-0.000000,0.000000,1.763992,-0.092319,-0.004534,0.001510,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.498393,-0.038348,0.000023,0.000599,-0.000001,-0.000000,0.000000,0.000000,0.561865,-0.010335,-0.000018,0.000161,0.000001,0.000000,-0.000000,-0.000000,1.668648,-0.096858,-0.000005,0.001510,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.536120,-0.036508,0.001815,0.000596,-0.000001,-0.000000,0.000000,-0.000000,0.551673,-0.009886,0.000469,0.000163,0.000001,-0.000000,0.000000,-0.000000,1.573295,-0.092338,0.004526,0.001512,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.570217,-0.031094,0.003595,0.000587,-0.000006,0.000005,-0.000005,0.000004,0.542420,-0.008457,0.000960,0.000163,-0.000001,0.000001,-0.000001,0.000001,1.486995,-0.078754,0.009052,0.001497,-0.000014,0.000013,-0.000013,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.597131,-0.022144,0.005380,0.000654,0.000084,-0.000038,0.000088,-0.000065,0.535086,-0.006045,0.001459,0.000183,0.000023,-0.000011,0.000024,-0.000018,1.418787,-0.056153,0.013613,0.001672,0.000214,-0.000097,0.000224,-0.000165,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.613170,-0.009197,0.007431,0.000107,-0.001051,0.000004,-0.001306,0.000862,0.530703,-0.002517,0.002031,0.000033,-0.000288,0.000001,-0.000359,0.000237,1.378097,-0.023344,0.018853,0.000282,-0.002670,0.000010,-0.003319,0.002191,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.616320,0.000000,0.000000,0.000000,0.012454,-0.013383,0.006159,-0.001123,0.529840,0.000000,0.000000,0.000000,-0.012008,0.012915,-0.005946,0.001084,1.370100,0.000000,0.000000,-0.000000,0.026806,-0.028830,0.013273,-0.002420,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.612213,0.011996,0.009702,-0.000128,-0.001369,0.001132,-0.000476,0.000084,0.525885,-0.011545,-0.009323,0.000142,0.001321,-0.001094,0.000460,-0.000082,1.378929,0.025770,0.020808,-0.000318,-0.002949,0.002441,-0.001026,0.000182,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.591271,0.028938,0.007065,-0.000841,0.000110,-0.000076,0.000030,-0.000005,0.505764,-0.027763,-0.006725,0.000829,-0.000106,0.000074,-0.000029,0.000005,1.423838,0.061962,0.015005,-0.001852,0.000237,-0.000164,0.000064,-0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.556051,0.040744,0.004773,-0.000753,-0.000007,0.000004,-0.000001,0.000000,0.472048,-0.038920,-0.004463,0.000743,0.000007,-0.000004,0.000001,-0.000000,1.499078,0.086847,0.009951,-0.001659,-0.000015,0.000009,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.511291,0.048016,0.002494,-0.000763,-0.000001,-0.000000,0.000000,-0.000000,0.429412,-0.045602,-0.002216,0.000751,0.000000,0.000000,0.000000,-0.000000,1.594208,0.101741,0.004936,-0.001675,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.461546,0.050710,0.000197,-0.000770,-0.000003,-0.000000,-0.000000,-0.000000,0.382345,-0.047780,0.000039,0.000752,-0.000000,-0.000000,0.000000,-0.000000,1.699211,0.106592,-0.000083,-0.001671,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.411413,0.048780,-0.002137,-0.000791,-0.000011,-0.000002,0.000001,0.000000,0.335355,-0.045448,0.002290,0.000747,-0.000003,-0.000002,0.000001,-0.000000,1.804049,0.101415,-0.005091,-0.001666,0.000003,0.000003,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.365574,0.042082,-0.004585,-0.000837,-0.000006,-0.000006,0.000008,-0.000006,0.292940,-0.038645,0.004501,0.000723,-0.000010,0.000007,-0.000006,0.000005,1.898712,0.086260,-0.010045,-0.001625,0.000022,-0.000013,0.000013,-0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.328925,0.030352,-0.007198,-0.000968,-0.000121,0.000055,-0.000125,0.000091,0.259516,-0.027478,0.006696,0.000804,0.000104,-0.000047,0.000109,-0.000080,1.973313,0.061318,-0.014955,-0.001792,-0.000230,0.000104,-0.000243,0.000179,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.306838,0.012732,-0.010237,-0.000212,0.001467,-0.000007,0.001831,-0.001206,0.239624,-0.011399,0.009216,0.000126,-0.001302,0.000004,-0.001617,0.001068,2.017694,0.025426,-0.020561,-0.000275,0.002902,-0.000010,0.003604,-0.002380,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.302470,0.000000,0.000000,0.000000,-0.001642,0.001752,-0.000804,0.000146,0.235720,0.000000,0.000000,0.000000,0.012996,-0.013983,0.006439,-0.001174,2.026400,0.000000,0.000000,0.000000,-0.010051,0.010798,-0.004969,0.000906,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.303018,-0.001607,-0.001318,-0.000005,0.000179,-0.000147,0.000062,-0.000011,0.239997,0.012480,0.010068,-0.000166,-0.001430,0.001184,-0.000498,0.000088,2.023084,-0.009687,-0.007839,0.000098,0.001104,-0.000913,0.000384,-0.000068,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.305865,-0.003986,-0.001038,0.000088,-0.000015,0.000010,-0.000004,0.000001,0.261724,0.029951,0.007219,-0.000909,0.000115,-0.000080,0.000031,-0.000005,2.006162,-0.023396,-0.005727,0.000675,-0.000088,0.000061,-0.000024,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.310809,-0.005825,-0.000806,0.000075,0.000001,-0.000000,0.000000,0.000000,0.298046,0.041871,0.004736,-0.000815,-0.000007,0.000004,-0.000002,0.000000,1.977668,-0.032985,-0.003888,0.000604,0.000006,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.317365,-0.007209,-0.000576,0.000079,0.000002,0.000001,-0.000001,0.000000,0.343835,0.048887,0.002278,-0.000818,0.000003,0.000001,-0.000000,0.000000,1.941402,-0.038936,-0.002059,0.000612,0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.325068,-0.008112,-0.000318,0.000096,0.000007,0.000003,-0.000000,-0.000000,0.394185,0.051004,-0.000153,-0.000802,0.000004,0.000000,0.000000,-0.000000,1.901021,-0.041209,-0.000208,0.000623,0.000005,0.000002,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.333393,-0.008422,0.000033,0.000145,0.000015,0.000000,0.000001,-0.000001,0.444238,0.048309,-0.002530,-0.000781,0.000006,0.000001,0.000000,-0.000000,1.860233,-0.039730,0.001704,0.000655,0.000010,-0.000000,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.341621,-0.007857,0.000565,0.000210,0.000013,-0.000003,0.000000,0.000001,0.489243,0.040934,-0.004829,-0.000748,0.000012,-0.000009,0.000007,-0.000005,1.822872,-0.034317,0.003728,0.000691,0.000003,0.000003,-0.000004,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.348692,-0.006055,0.001261,0.000264,0.000030,-0.000015,0.000029,-0.000020,0.524605,0.029038,-0.007101,-0.000838,-0.000112,0.000050,-0.000115,0.000085,1.792980,-0.024758,0.005870,0.000790,0.000099,-0.000045,0.000102,-0.000074,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.353199,-0.002664,0.002093,0.000106,-0.000319,0.000004,-0.000405,0.000264,0.545612,0.012029,-0.009732,-0.000124,0.001372,-0.000004,0.001703,-0.001125,1.774963,-0.010386,0.008351,0.000173,-0.001197,0.000006,-0.001493,0.000984,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.354120,0.000000,0.000000,0.000000,0.005222,-0.005618,0.002587,-0.000472,0.549730,0.000000,0.000000,0.000000,-0.024915,0.026793,-0.012334,0.002249,1.771400,0.000000,0.000000,-0.000000,0.005635,-0.006062,0.002791,-0.000509,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.352401,0.005018,0.004050,-0.000064,-0.000575,0.000476,-0.000200,0.000035,0.541522,-0.023960,-0.019351,0.000289,0.002740,-0.002268,0.000953,-0.000169,1.773255,0.005414,0.004370,-0.000069,-0.000620,0.000513,-0.000216,0.000038,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.343661,0.012053,0.002912,-0.000363,0.000046,-0.000032,0.000012,-0.000002,0.499756,-0.057639,-0.013976,0.001715,-0.000220,0.000153,-0.000059,0.000010,1.782686,0.013006,0.003143,-0.000391,0.000050,-0.000035,0.000013,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.329034,0.016874,0.001923,-0.000324,-0.000002,0.000002,-0.000001,0.000000,0.429739,-0.080848,-0.009298,0.001536,0.000014,-0.000008,0.000003,-0.000000,1.798470,0.018210,0.002076,-0.000349,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.310561,0.019747,0.000950,-0.000323,0.000001,-0.000000,0.000000,-0.000000,0.341137,-0.094808,-0.004655,0.001551,-0.000001,0.000000,-0.000000,0.000000,1.818406,0.021310,0.001025,-0.000349,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.290187,0.020679,-0.000017,-0.000321,0.000000,-0.000000,-0.000000,0.000000,0.243224,-0.099467,-0.000004,0.001550,0.000000,0.000000,-0.000000,0.000000,1.840393,0.022316,-0.000019,-0.000347,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.269846,0.019683,-0.000979,-0.000320,0.000000,0.000000,-0.000000,0.000000,0.145304,-0.094823,0.004649,0.001552,0.000001,-0.000001,0.000001,-0.000001,1.862344,0.021239,-0.001058,-0.000346,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.251462,0.016765,-0.001937,-0.000317,0.000003,-0.000003,0.000003,-0.000002,0.056681,-0.080873,0.009295,0.001537,-0.000014,0.000013,-0.000013,0.000010,1.882180,0.018089,-0.002091,-0.000341,0.000003,-0.000003,0.000003,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.236949,0.011941,-0.002901,-0.000353,-0.000045,0.000021,-0.000048,0.000035,-0.013363,-0.057665,0.013979,0.001717,0.000220,-0.000100,0.000231,-0.000169,1.897837,0.012882,-0.003130,-0.000381,-0.000049,0.000022,-0.000051,0.000038,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.228299,0.004960,-0.004008,-0.000058,0.000567,-0.000002,0.000705,-0.000465,-0.055150,-0.023973,0.019361,0.000290,-0.002742,0.000010,-0.003409,0.002250,1.907168,0.005350,-0.004323,-0.000062,0.000612,-0.000002,0.000760,-0.000502,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.226600,0.000000,0.000000,0.000000,0.002912,-0.003111,0.001428,-0.000260,-0.063362,0.000000,0.000000,0.000000,-0.002732,0.002941,-0.001354,0.000247,1.909000,0.000000,0.000000,-0.000000,0.003290,-0.003557,0.001641,-0.000300,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.225631,0.002842,0.002324,0.000003,-0.000318,0.000262,-0.000110,0.000019,-0.064261,-0.002622,-0.002114,0.000036,0.000301,-0.000249,0.000105,-0.000019,1.910075,0.003126,0.002498,-0.000071,-0.000364,0.000303,-0.000128,0.000023,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.220609,0.007013,0.001805,-0.000165,0.000025,-0.000017,0.000007,-0.000001,-0.068823,-0.006285,-0.001510,0.000193,-0.000024,0.000017,-0.000007,0.000001,1.915462,0.007359,0.001689,-0.000259,0.000030,-0.000020,0.000008,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.211942,0.010175,0.001362,-0.000149,-0.000006,-0.000002,0.000000,0.000000,-0.076437,-0.008766,-0.000977,0.000177,0.000002,-0.000001,0.000000,-0.000000,1.924267,0.010016,0.000981,-0.000228,0.000003,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.200562,0.012420,0.000865,-0.000185,-0.000010,0.000000,0.000000,-0.000000,-0.086001,-0.010183,-0.000440,0.000179,-0.000001,-0.000000,0.000000,-0.000000,1.935041,0.011317,0.000336,-0.000197,0.000009,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.187472,0.013559,0.000257,-0.000219,-0.000008,0.000000,-0.000000,0.000000,-0.096446,-0.010530,0.000090,0.000172,-0.000004,-0.000001,0.000000,0.000000,1.946506,0.011433,-0.000204,-0.000165,0.000006,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.173883,0.013383,-0.000448,-0.000249,-0.000005,0.000002,-0.000001,0.000000,-0.106719,-0.009852,0.000578,0.000153,-0.000004,0.000001,-0.000000,-0.000000,1.957576,0.010550,-0.000671,-0.000148,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.161200,0.011728,-0.001212,-0.000256,0.000001,-0.000002,0.000002,-0.000002,-0.115844,-0.008252,0.001017,0.000142,-0.000003,0.000002,-0.000001,0.000001,1.967308,0.008770,-0.001106,-0.000143,0.000002,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.150941,0.008532,-0.001994,-0.000285,-0.000034,0.000015,-0.000035,0.000026,-0.122938,-0.005796,0.001444,0.000157,0.000021,-0.000010,0.000022,-0.000017,1.974830,0.006131,-0.001540,-0.000160,-0.000023,0.000010,-0.000024,0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.144716,0.003599,-0.002886,-0.000070,0.000417,-0.000002,0.000521,-0.000343,-0.127116,-0.002382,0.001935,0.000015,-0.000270,0.000001,-0.000334,0.000221,1.979242,0.002511,-0.002043,-0.000011,0.000284,-0.000000,0.000350,-0.000232,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.143480,0.000000,0.000000,0.000000,0.006017,-0.006531,0.003019,-0.000552,-0.127930,0.000000,0.000000,0.000000,0.014871,-0.016139,0.007460,-0.001364,1.980100,0.000000,0.000000,0.000000,-0.002662,0.002888,-0.001335,0.000244,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.141526,0.005665,0.004490,-0.000177,-0.000669,0.000557,-0.000235,0.000042,-0.123101,0.014004,0.011100,-0.000434,-0.001652,0.001377,-0.000582,0.000104,1.979236,-0.002507,-0.001987,0.000077,0.000296,-0.000246,0.000104,-0.000019,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.131853,0.013108,0.002870,-0.000519,0.000054,-0.000038,0.000015,-0.000003,-0.099185,0.032412,0.007104,-0.001281,0.000134,-0.000094,0.000037,-0.000006,1.974954,-0.005803,-0.001273,0.000229,-0.000024,0.000017,-0.000007,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.116366,0.017389,0.001427,-0.000475,-0.000003,0.000002,-0.000001,0.000000,-0.060879,0.043020,0.003543,-0.001173,-0.000009,0.000005,-0.000002,0.000000,1.968094,-0.007706,-0.000636,0.000210,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.098027,0.018811,-0.000006,-0.000478,0.000000,0.000000,-0.000000,0.000000,-0.015494,0.046569,0.000001,-0.001183,-0.000000,0.000001,-0.000000,0.000000,1.959963,-0.008345,-0.000002,0.000212,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.079699,0.017368,-0.001435,-0.000473,0.000004,-0.000003,0.000003,-0.000003,0.029894,0.043025,-0.003541,-0.001174,0.000009,-0.000008,0.000008,-0.000006,1.951827,-0.007714,0.000633,0.000211,-0.000001,0.000001,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.064238,0.013080,-0.002869,-0.000516,-0.000054,0.000025,-0.000058,0.000042,0.068206,0.032419,-0.007104,-0.001281,-0.000134,0.000062,-0.000144,0.000104,1.944957,-0.005814,0.001273,0.000230,0.000024,-0.000011,0.000026,-0.000019,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.054588,0.005650,-0.004479,-0.000174,0.000666,-0.000006,0.000841,-0.000550,0.092129,0.014008,-0.011103,-0.000435,0.001653,-0.000015,0.002086,-0.001364,1.940667,-0.002513,0.001991,0.000078,-0.000297,0.000003,-0.000374,0.000245,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.052640,0.000000,0.000000,0.000000,-0.026678,0.029147,-0.013512,0.002474,0.096959,0.000000,0.000000,0.000000,-0.004730,0.005167,-0.002395,0.000439,1.939800,0.000000,0.000000,0.000000,0.011821,-0.012915,0.005987,-0.001096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.061208,-0.024727,-0.019312,0.001127,0.002986,-0.002501,0.001060,-0.000189,0.095440,-0.004384,-0.003424,0.000200,0.000529,-0.000443,0.000188,-0.000034,1.943597,0.010956,0.008556,-0.000500,-0.001323,0.001108,-0.000470,0.000084,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.102765,-0.055495,-0.011097,0.002639,-0.000243,0.000172,-0.000068,0.000012,0.088073,-0.009838,-0.001967,0.000468,-0.000043,0.000030,-0.000012,0.000002,1.962008,0.024585,0.004914,-0.001170,0.000108,-0.000076,0.000030,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.166845,-0.070210,-0.003688,0.002446,0.000017,-0.000011,0.000004,-0.000001,0.076714,-0.012445,-0.000653,0.000434,0.000003,-0.000002,0.000001,-0.000000,1.990393,0.031098,0.001630,-0.001084,-0.000007,0.000005,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.238288,-0.070218,0.003680,0.002447,-0.000016,0.000016,-0.000016,0.000012,0.064051,-0.012445,0.000653,0.000433,-0.000003,0.000003,-0.000003,0.000002,2.022033,0.031092,-0.001635,-0.001084,0.000008,-0.000007,0.000007,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.302383,-0.055514,0.011095,0.002642,0.000243,-0.000116,0.000265,-0.000189,0.052691,-0.009839,0.001966,0.000468,0.000043,-0.000021,0.000047,-0.000034,2.050408,0.024572,-0.004916,-0.001168,-0.000107,0.000051,-0.000117,0.000084,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.343957,-0.024740,0.019321,0.001130,-0.002988,0.000040,-0.003812,0.002476,0.045323,-0.004385,0.003424,0.000200,-0.000530,0.000007,-0.000676,0.000439,2.068807,0.010947,-0.008550,-0.000498,0.001322,-0.000018,0.001686,-0.001095,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.352530,0.000000,0.000000,0.000000,0.004957,-0.005269,0.002413,-0.000438,0.043803,0.000000,0.000000,-0.000000,0.001340,-0.001495,0.000699,-0.000129,2.072600,0.000000,0.000000,0.000000,-0.021258,0.022472,-0.010266,0.001862,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.350868,0.004890,0.004036,0.000050,-0.000539,0.000442,-0.000184,0.000033,0.044219,0.001180,0.000875,-0.000111,-0.000153,0.000131,-0.000056,0.000010,2.065411,-0.021227,-0.017702,-0.000445,0.002295,-0.001874,0.000780,-0.000137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.342140,0.012289,0.003290,-0.000236,0.000043,-0.000029,0.000011,-0.000002,0.046094,0.002373,0.000303,-0.000182,0.000014,-0.000009,0.000004,-0.000001,2.027100,-0.054439,-0.015194,0.000787,-0.000181,0.000124,-0.000047,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.326775,0.018239,0.002674,-0.000200,-0.000002,0.000002,-0.000001,0.000000,0.048597,0.002463,-0.000206,-0.000163,0.000003,0.000001,-0.000000,0.000000,1.958157,-0.082799,-0.013221,0.000639,0.000012,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.306061,0.022987,0.002073,-0.000200,0.000001,-0.000000,0.000000,0.000000,0.050694,0.001578,-0.000669,-0.000143,0.000007,0.000001,-0.000000,0.000000,1.862784,-0.107295,-0.011268,0.000656,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.281201,0.026536,0.001478,-0.000195,0.000002,0.000000,0.000000,-0.000000,0.051468,-0.000157,-0.001047,-0.000105,0.000014,0.000002,0.000001,-0.000000,1.744878,-0.127858,-0.009293,0.000661,0.000002,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.253379,0.028919,0.000915,-0.000176,0.000008,0.000001,-0.000001,0.000000,0.050177,-0.002492,-0.001243,-0.000013,0.000031,-0.000000,-0.000000,-0.000000,1.608390,-0.144452,-0.007296,0.000670,0.000002,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.223714,0.030250,0.000430,-0.000150,0.000004,-0.000001,-0.000000,0.000000,0.046459,-0.004896,-0.001105,0.000099,0.000021,-0.000007,0.000002,-0.000000,1.457314,-0.157026,-0.005273,0.000679,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.193182,0.030670,-0.000006,-0.000143,0.000001,0.000000,0.000000,-0.000000,0.040573,-0.006749,-0.000727,0.000143,0.000004,-0.000003,0.000001,-0.000000,1.295696,-0.165529,-0.003227,0.000684,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.162661,0.030231,-0.000430,-0.000139,0.000001,-0.000000,-0.000000,0.000000,0.033242,-0.007767,-0.000291,0.000144,-0.000001,0.000000,0.000000,-0.000000,1.127625,-0.169927,-0.001171,0.000686,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.132997,0.028960,-0.000839,-0.000134,0.000001,-0.000000,-0.000000,0.000000,0.025327,-0.007920,0.000136,0.000140,-0.000002,-0.000001,-0.000000,-0.000000,0.957214,-0.170208,0.000890,0.000688,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.105009,0.026884,-0.001235,-0.000129,0.000003,0.000001,0.000000,0.000000,0.017680,-0.007242,0.000532,0.000119,-0.000010,-0.000002,-0.000000,0.000000,0.788584,-0.166362,0.002956,0.000690,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.079485,0.024045,-0.001591,-0.000103,0.000012,0.000003,-0.000001,0.000000,0.011077,-0.005873,0.000806,0.000056,-0.000021,-0.000002,0.000001,-0.000000,0.625869,-0.158377,0.005031,0.000693,0.000001,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.057121,0.020608,-0.001818,-0.000048,0.000013,-0.000000,-0.000000,0.000000,0.006045,-0.004175,0.000852,-0.000021,-0.000014,0.000003,-0.000000,0.000000,0.473218,-0.146230,0.007116,0.000696,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.038367,0.016876,-0.001892,-0.000006,0.000007,-0.000002,0.000000,-0.000000,0.002690,-0.002578,0.000727,-0.000057,-0.000004,0.000002,-0.000000,0.000000,0.334801,-0.129907,0.009207,0.000697,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.023383,0.013096,-0.001881,0.000010,0.000002,-0.000001,0.000000,-0.000000,0.000779,-0.001305,0.000541,-0.000065,-0.000001,0.000000,-0.000000,0.000000,0.214798,-0.109400,0.011301,0.000699,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.012157,0.009370,-0.001843,0.000015,0.000001,-0.000001,0.000001,-0.000001,-0.000051,-0.000420,0.000343,-0.000066,0.000000,-0.000000,0.000000,-0.000000,0.117398,-0.084705,0.013388,0.000686,-0.000012,0.000010,-0.000010,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.004615,0.005729,-0.001802,0.000002,-0.000016,0.000006,-0.000015,0.000012,-0.000194,0.000067,0.000143,-0.000068,-0.000002,0.000001,-0.000003,0.000002,0.046764,-0.055866,0.015509,0.000841,0.000187,-0.000080,0.000187,-0.000142,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.000699,0.002091,-0.001804,0.000120,0.000212,0.000004,0.000246,-0.000169,-0.000055,0.000140,-0.000068,-0.000058,0.000027,-0.000002,0.000040,-0.000024,0.007401,-0.021843,0.018190,-0.000426,-0.002367,-0.000016,-0.002861,0.001922,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.398760,0.000000,0.000000,0.000000,0.006945,-0.007371,0.003373,-0.000613,0.834000,0.000000,0.000000,0.000000,-0.004994,0.005329,-0.002445,0.000445,0.641080,0.000000,0.000000,-0.000000,0.001998,-0.002121,0.000971,-0.000176,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.401095,0.006878,0.005696,0.000095,-0.000753,0.000617,-0.000257,0.000045,0.832335,-0.004886,-0.004006,-0.000018,0.000541,-0.000451,0.000188,-0.000033,0.641752,0.001978,0.001638,0.000027,-0.000217,0.000177,-0.000074,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.413416,0.017401,0.004725,-0.000306,0.000060,-0.000041,0.000016,-0.000003,0.823671,-0.012146,-0.003196,0.000242,-0.000050,0.000031,-0.000012,0.000002,0.645295,0.005004,0.001358,-0.000088,0.000017,-0.000012,0.000005,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.435267,0.026041,0.003934,-0.000257,-0.000004,0.000002,-0.000001,0.000000,0.808543,-0.017912,-0.002593,0.000187,-0.000001,-0.000001,0.000001,-0.000000,0.651578,0.007487,0.001130,-0.000074,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.464983,0.033130,0.003153,-0.000261,0.000000,-0.000000,0.000000,-0.000000,0.788223,-0.022544,-0.002044,0.000179,-0.000002,0.000000,-0.000000,0.000000,0.660120,0.009522,0.000905,-0.000075,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.501004,0.038651,0.002369,-0.000261,-0.000000,-0.000000,0.000000,0.000000,0.763813,-0.026101,-0.001515,0.000174,-0.000001,0.000000,-0.000000,-0.000000,0.670471,0.011105,0.000679,-0.000075,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.541762,0.042604,0.001584,-0.000262,-0.000000,0.000000,-0.000000,0.000000,0.736371,-0.028610,-0.000995,0.000173,-0.000000,0.000000,-0.000000,0.000000,0.682180,0.012237,0.000453,-0.000075,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.585688,0.044986,0.000798,-0.000262,-0.000000,0.000000,-0.000000,0.000000,0.706939,-0.030081,-0.000477,0.000172,-0.000000,0.000000,-0.000000,0.000000,0.694794,0.012917,0.000227,-0.000075,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.631211,0.045796,0.000011,-0.000262,-0.000000,0.000000,-0.000000,0.000000,0.676553,-0.030519,0.000039,0.000172,-0.000000,0.000000,-0.000000,0.000000,0.707862,0.013145,0.000001,-0.000075,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.676756,0.045031,-0.000777,-0.000263,-0.000000,-0.000000,-0.000000,0.000000,0.646245,-0.029924,0.000555,0.000172,-0.000000,-0.000000,0.000000,-0.000000,0.720933,0.012921,-0.000225,-0.000075,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.720747,0.042689,-0.001566,-0.000263,-0.000000,0.000000,-0.000000,0.000000,0.617047,-0.028300,0.001070,0.000171,-0.000000,0.000000,0.000000,-0.000000,0.733554,0.012245,-0.000451,-0.000075,-0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.761607,0.038766,-0.002357,-0.000264,-0.000000,-0.000000,-0.000000,-0.000000,0.589989,-0.025646,0.001584,0.000171,-0.000000,0.000000,-0.000000,0.000000,0.745272,0.011116,-0.000678,-0.000076,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.797752,0.033260,-0.003150,-0.000265,-0.000000,0.000000,-0.000000,0.000000,0.566098,-0.021964,0.002098,0.000172,0.000000,-0.000000,0.000000,-0.000000,0.755636,0.009535,-0.000904,-0.000076,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.827598,0.026168,-0.003941,-0.000261,0.000004,-0.000003,0.000003,-0.000003,0.546405,-0.017252,0.002611,0.000169,-0.000002,0.000002,-0.000002,0.000002,0.764191,0.007500,-0.001131,-0.000075,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.849564,0.017500,-0.004745,-0.000311,-0.000060,0.000026,-0.000061,0.000046,0.531932,-0.011522,0.003131,0.000202,0.000040,-0.000017,0.000040,-0.000030,0.770485,0.005014,-0.001360,-0.000089,-0.000017,0.000007,-0.000017,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.861960,0.006922,-0.005731,0.000093,0.000758,0.000003,0.000922,-0.000617,0.523775,-0.004552,0.003771,-0.000064,-0.000498,-0.000002,-0.000605,0.000405,0.774037,0.001983,-0.001642,0.000027,0.000217,0.000001,0.000264,-0.000177,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.864310,0.000000,0.000000,0.000000,0.010585,-0.011428,0.005270,-0.000962,0.522230,0.000000,0.000000,-0.000000,0.024215,-0.026145,0.012057,-0.002201,0.774710,0.000000,0.000000,0.000000,0.016500,-0.017816,0.008216,-0.001500,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.867775,0.010086,0.008080,-0.000205,-0.001169,0.000971,-0.000409,0.000073,0.530157,0.023074,0.018485,-0.000468,-0.002675,0.002221,-0.000936,0.000166,0.780111,0.015723,0.012596,-0.000319,-0.001823,0.001514,-0.000638,0.000113,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.885201,0.023864,0.005550,-0.000809,0.000094,-0.000066,0.000026,-0.000004,0.570024,0.054594,0.012697,-0.001851,0.000215,-0.000150,0.000059,-0.000010,0.807277,0.037201,0.008652,-0.001261,0.000147,-0.000102,0.000040,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.913856,0.032708,0.003322,-0.000733,-0.000006,0.000004,-0.000001,0.000000,0.635577,0.074826,0.007600,-0.001676,-0.000014,0.000008,-0.000003,0.000001,0.851947,0.050989,0.005179,-0.001142,-0.000009,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.949149,0.037141,0.001109,-0.000739,0.000000,-0.000000,0.000000,-0.000000,0.716319,0.084969,0.002536,-0.001691,0.000001,-0.000000,0.000000,-0.000000,0.906967,0.057900,0.001728,-0.001152,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.986660,0.037141,-0.001109,-0.000739,-0.000000,0.000001,-0.000000,0.000000,0.802133,0.084968,-0.002536,-0.001691,-0.000001,0.000001,-0.000001,0.000001,0.965443,0.057900,-0.001728,-0.001152,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.021954,0.032708,-0.003322,-0.000733,0.000006,-0.000006,0.000006,-0.000004,0.882874,0.074826,-0.007600,-0.001676,0.000014,-0.000013,0.000013,-0.000010,1.020463,0.050989,-0.005179,-0.001142,0.000009,-0.000009,0.000009,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.050609,0.023864,-0.005550,-0.000809,-0.000094,0.000043,-0.000100,0.000073,0.948427,0.054593,-0.012697,-0.001851,-0.000215,0.000099,-0.000228,0.000166,1.065132,0.037201,-0.008652,-0.001261,-0.000147,0.000067,-0.000155,0.000113,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.068035,0.010086,-0.008080,-0.000205,0.001169,-0.000007,0.001463,-0.000962,0.988294,0.023073,-0.018485,-0.000468,0.002675,-0.000017,0.003348,-0.002201,1.092299,0.015723,-0.012596,-0.000319,0.001823,-0.000011,0.002281,-0.001500,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.071500,0.000000,0.000000,0.000000,-0.036266,0.038998,-0.017952,0.003273,0.996220,0.000000,0.000000,0.000000,-0.028208,0.030333,-0.013964,0.002546,1.097700,0.000000,0.000000,-0.000000,0.003218,-0.003460,0.001593,-0.000290,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.059552,-0.034880,-0.028175,0.000417,0.003989,-0.003302,0.001388,-0.000246,0.986927,-0.027131,-0.021915,0.000324,0.003102,-0.002568,0.001079,-0.000191,1.098760,0.003095,0.002500,-0.000037,-0.000354,0.000293,-0.000123,0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.998742,-0.083929,-0.020362,0.002493,-0.000320,0.000222,-0.000086,0.000015,0.939627,-0.065283,-0.015839,0.001939,-0.000249,0.000173,-0.000067,0.000012,1.104156,0.007448,0.001808,-0.000221,0.000028,-0.000020,0.000008,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.896775,-0.117757,-0.013562,0.002233,0.000021,-0.000012,0.000004,-0.000001,0.860313,-0.091598,-0.010550,0.001736,0.000016,-0.000009,0.000003,-0.000001,1.113206,0.010452,0.001205,-0.000198,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.767701,-0.138138,-0.006809,0.002257,-0.000000,0.000000,0.000000,-0.000000,0.759911,-0.107454,-0.005298,0.001755,-0.000000,0.000000,0.000000,-0.000000,1.124664,0.012264,0.000606,-0.000200,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.625011,-0.144985,-0.000037,0.002259,0.000001,-0.000000,0.000000,-0.000000,0.648913,-0.112785,-0.000031,0.001757,0.000001,-0.000000,0.000000,-0.000000,1.137335,0.012877,0.000006,-0.000200,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.482249,-0.138276,0.006749,0.002265,0.000002,-0.000002,0.000001,-0.000001,0.537855,-0.107572,0.005247,0.001762,0.000002,-0.000002,0.000001,-0.000001,1.150018,0.012288,-0.000596,-0.000201,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.352988,-0.117984,0.013536,0.002247,-0.000019,0.000019,-0.000019,0.000015,0.437293,-0.091791,0.010528,0.001749,-0.000015,0.000015,-0.000015,0.000012,1.161509,0.010492,-0.001200,-0.000200,0.000001,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.250783,-0.084159,0.020387,0.002512,0.000322,-0.000146,0.000337,-0.000247,0.357776,-0.065479,0.015860,0.001955,0.000250,-0.000113,0.000262,-0.000192,1.170601,0.007491,-0.001812,-0.000225,-0.000029,0.000013,-0.000030,0.000022,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.189790,-0.034998,0.028261,0.000429,-0.004004,0.000015,-0.004979,0.003286,0.310319,-0.027231,0.021989,0.000335,-0.003116,0.000012,-0.003874,0.002557,1.176032,0.003117,-0.002516,-0.000039,0.000357,-0.000001,0.000444,-0.000293,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.177800,0.000000,0.000000,-0.000000,-0.039443,0.042806,-0.019786,0.003617,0.300990,0.000000,0.000000,0.000000,-0.009963,0.010812,-0.004998,0.000914,1.177100,0.000000,0.000000,0.000000,-0.028646,0.031088,-0.014370,0.002627,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.164993,-0.037143,-0.029439,0.001153,0.004382,-0.003652,0.001543,-0.000275,0.297755,-0.009382,-0.007436,0.000291,0.001107,-0.000923,0.000390,-0.000069,1.167799,-0.026975,-0.021380,0.000837,0.003183,-0.002653,0.001120,-0.000200,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.101562,-0.085962,-0.018839,0.003397,-0.000354,0.000248,-0.000097,0.000017,0.281733,-0.021714,-0.004759,0.000858,-0.000089,0.000063,-0.000025,0.000004,1.121731,-0.062431,-0.013682,0.002467,-0.000257,0.000180,-0.000071,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.000029,-0.114091,-0.009394,0.003111,0.000023,-0.000013,0.000005,-0.000001,0.256071,-0.028819,-0.002373,0.000786,0.000006,-0.000003,0.000001,-0.000000,1.047950,-0.082859,-0.006822,0.002260,0.000017,-0.000010,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.120389,-0.123496,-0.000000,0.003138,0.000000,-0.000002,0.000001,-0.000001,0.225668,-0.031196,-0.000000,0.000793,0.000000,-0.000000,0.000000,-0.000000,0.960539,-0.089689,0.000000,0.002279,-0.000000,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.240749,-0.114092,0.009394,0.003112,-0.000023,0.000022,-0.000022,0.000017,0.195264,-0.028821,0.002373,0.000786,-0.000006,0.000006,-0.000006,0.000004,0.873128,-0.082858,0.006822,0.002260,-0.000017,0.000016,-0.000016,0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.342341,-0.085963,0.018839,0.003397,0.000354,-0.000166,0.000381,-0.000275,0.169600,-0.021716,0.004759,0.000858,0.000090,-0.000042,0.000096,-0.000069,0.799348,-0.062430,0.013682,0.002467,0.000257,-0.000120,0.000276,-0.000200,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.405773,-0.037143,0.029439,0.001153,-0.004383,0.000041,-0.005531,0.003617,0.153575,-0.009383,0.007437,0.000291,-0.001107,0.000010,-0.001397,0.000914,0.753281,-0.026975,0.021380,0.000837,-0.003183,0.000030,-0.004017,0.002627,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.418580,0.000000,0.000000,0.000000,0.014218,-0.015292,0.007040,-0.001283,0.150340,0.000000,0.000000,-0.000000,0.044918,-0.048306,0.022239,-0.004054,0.743980,0.000000,0.000000,-0.000000,-0.000271,0.000292,-0.000135,0.000025,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.413897,0.013670,0.011039,-0.000168,-0.001564,0.001295,-0.000544,0.000097,0.165136,0.043190,0.034878,-0.000526,-0.004941,0.004090,-0.001719,0.000305,0.743891,-0.000259,-0.000208,0.000004,0.000030,-0.000025,0.000010,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.390073,0.032873,0.007963,-0.000981,0.000126,-0.000087,0.000034,-0.000006,0.240412,0.103874,0.025172,-0.003097,0.000397,-0.000275,0.000107,-0.000019,0.743441,-0.000618,-0.000146,0.000020,-0.000002,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.350151,0.046084,0.005286,-0.000879,-0.000008,0.000005,-0.000002,0.000000,0.366570,0.145649,0.016723,-0.002773,-0.000025,0.000015,-0.000005,0.000001,0.742696,-0.000855,-0.000092,0.000018,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.299664,0.054004,0.002631,-0.000886,0.000001,-0.000000,-0.000000,0.000000,0.526155,0.170726,0.008343,-0.002798,0.000003,-0.000000,-0.000000,0.000000,0.741767,-0.000986,-0.000040,0.000017,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.243915,0.056611,-0.000022,-0.000883,0.000001,-0.000000,-0.000000,0.000000,0.702429,0.179028,-0.000038,-0.002791,0.000001,-0.000000,-0.000000,0.000000,0.740758,-0.001015,0.000010,0.000016,-0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.188207,0.053922,-0.002666,-0.000880,0.000000,0.000001,-0.000000,0.000000,0.878630,0.170585,-0.008404,-0.002788,-0.000000,0.000002,-0.000001,0.000001,0.739768,-0.000950,0.000055,0.000015,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.137830,0.045953,-0.005299,-0.000870,0.000008,-0.000007,0.000007,-0.000006,1.038024,0.145422,-0.016746,-0.002758,0.000026,-0.000024,0.000023,-0.000019,0.738888,-0.000797,0.000098,0.000014,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.098043,0.032744,-0.007948,-0.000971,-0.000125,0.000056,-0.000131,0.000096,1.163948,0.103648,-0.025146,-0.003079,-0.000395,0.000179,-0.000414,0.000304,0.738203,-0.000560,0.000139,0.000015,0.000002,-0.000001,0.000002,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.074321,0.013606,-0.010991,-0.000161,0.001556,-0.000006,0.001933,-0.001276,1.239045,0.043076,-0.034794,-0.000515,0.004926,-0.000018,0.006123,-0.004042,0.737799,-0.000230,0.000187,0.000002,-0.000026,0.000000,-0.000032,0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.069661,0.000000,0.000000,0.000000,0.009933,-0.010657,0.004901,-0.000893,1.253800,0.000000,0.000000,-0.000000,-0.021838,0.023399,-0.010754,0.001959,0.737720,0.000000,0.000000,0.000000,0.028988,-0.031072,0.014283,-0.002602,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.066377,0.009603,0.007792,-0.000071,-0.001090,0.000900,-0.000378,0.000067,1.246565,-0.021174,-0.017224,0.000100,0.002392,-0.001975,0.000828,-0.000147,0.747318,0.028082,0.022827,-0.000155,-0.003177,0.002623,-0.001100,0.000195,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.049553,0.023320,0.005784,-0.000639,0.000088,-0.000060,0.000023,-0.000004,1.209366,-0.051684,-0.012974,0.001354,-0.000191,0.000133,-0.000051,0.000009,0.796613,0.068441,0.017118,-0.001818,0.000254,-0.000176,0.000068,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.021041,0.033133,0.004058,-0.000563,-0.000004,0.000003,-0.000001,0.000000,1.145961,-0.073916,-0.009314,0.001202,0.000014,-0.000007,0.000003,-0.000000,0.880489,0.097687,0.012203,-0.001611,-0.000017,0.000009,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.015585,0.039555,0.002366,-0.000561,0.000003,-0.000000,0.000000,-0.000000,1.063943,-0.088904,-0.005665,0.001223,0.000001,0.000000,0.000000,-0.000000,0.988758,0.117225,0.007326,-0.001630,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.056949,0.042617,0.000702,-0.000549,0.000003,-0.000000,0.000000,-0.000000,0.970598,-0.096559,-0.001985,0.001231,0.000003,-0.000000,0.000000,-0.000000,1.111680,0.126988,0.002438,-0.001629,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.099722,0.042386,-0.000927,-0.000537,0.000003,-0.000000,0.000000,-0.000000,0.873287,-0.096825,0.001725,0.001243,0.000003,-0.000000,0.000000,-0.000000,1.239477,0.126977,-0.002449,-0.001629,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.140646,0.038928,-0.002527,-0.000530,0.000001,0.000000,-0.000000,0.000000,0.779433,-0.089635,0.005471,0.001255,0.000004,-0.000001,0.000001,-0.000000,1.362376,0.117194,-0.007334,-0.001628,-0.000000,0.000001,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.176519,0.032293,-0.004103,-0.000518,0.000007,-0.000005,0.000005,-0.000004,0.696527,-0.074919,0.009246,0.001254,-0.000009,0.000011,-0.000011,0.000009,1.470608,0.097646,-0.012206,-0.001609,0.000017,-0.000015,0.000014,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.204193,0.022536,-0.005677,-0.000582,-0.000083,0.000037,-0.000086,0.000064,0.632109,-0.052646,0.013092,0.001427,0.000199,-0.000089,0.000205,-0.000151,1.554444,0.068403,-0.017113,-0.001816,-0.000254,0.000114,-0.000264,0.000195,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.220401,0.009218,-0.007505,-0.000036,0.001040,-0.000001,0.001284,-0.000851,0.594146,-0.021657,0.017581,0.000149,-0.002455,0.000005,-0.003040,0.002012,1.603709,0.028063,-0.022813,-0.000153,0.003175,-0.000005,0.003924,-0.002599,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.223550,0.000000,0.000000,-0.000000,-0.011005,0.011882,-0.005480,0.001000,0.586740,0.000000,0.000000,0.000000,0.023098,-0.024939,0.011501,-0.002099,1.613300,0.000000,0.000000,0.000000,0.009947,-0.010740,0.004953,-0.000904,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.219948,-0.010486,-0.008401,0.000213,0.001216,-0.001009,0.000425,-0.000076,0.594301,0.022009,0.017632,-0.000447,-0.002552,0.002119,-0.000892,0.000159,1.616556,0.009477,0.007592,-0.000193,-0.001099,0.000912,-0.000384,0.000068,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.201829,-0.024813,-0.005772,0.000841,-0.000098,0.000068,-0.000027,0.000005,0.632327,0.052072,0.012110,-0.001766,0.000205,-0.000143,0.000056,-0.000010,1.632930,0.022421,0.005213,-0.000761,0.000088,-0.000062,0.000024,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.172034,-0.034011,-0.003456,0.000762,0.000006,-0.000004,0.000001,-0.000000,0.694852,0.071367,0.007247,-0.001599,-0.000013,0.000008,-0.000003,0.000000,1.659849,0.030725,0.003118,-0.000689,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.135333,-0.038623,-0.001154,0.000769,-0.000000,0.000000,-0.000000,0.000000,0.771860,0.081037,0.002417,-0.001613,0.000001,-0.000000,0.000000,-0.000000,1.693001,0.034884,0.001039,-0.000694,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.096325,-0.038625,0.001152,0.000769,0.000000,-0.000001,0.000000,-0.000000,0.853702,0.081035,-0.002420,-0.001613,-0.000001,0.000001,-0.000001,0.000000,1.728230,0.034881,-0.001043,-0.000694,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.059621,-0.034015,0.003455,0.000762,-0.000006,0.000006,-0.000006,0.000005,0.930705,0.071360,-0.007249,-0.001598,0.000013,-0.000012,0.000012,-0.000010,1.761375,0.030715,-0.003121,-0.000688,0.000006,-0.000005,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.029821,-0.024818,0.005772,0.000841,0.000098,-0.000045,0.000104,-0.000076,0.993221,0.052064,-0.012109,-0.001765,-0.000205,0.000094,-0.000218,0.000159,1.788283,0.022409,-0.005212,-0.000760,-0.000088,0.000041,-0.000094,0.000068,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.011698,-0.010489,0.008403,0.000213,-0.001216,0.000008,-0.001522,0.001000,1.031241,0.022004,-0.017628,-0.000446,0.002551,-0.000016,0.003193,-0.002099,1.804647,0.009471,-0.007587,-0.000192,0.001098,-0.000007,0.001374,-0.000903,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/4/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.008094,0.000000,0.000000,0.000000,-0.012228,0.013203,-0.006089,0.001111,1.038800,0.000000,0.000000,0.000000,-0.028527,0.030801,-0.014205,0.002593,1.807900,0.000000,0.000000,0.000000,0.008522,-0.009201,0.004243,-0.000774,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.004091,-0.011652,-0.009335,0.000236,0.001351,-0.001122,0.000472,-0.000084,1.029462,-0.027183,-0.021777,0.000552,0.003152,-0.002617,0.001102,-0.000196,1.810689,0.008120,0.006505,-0.000165,-0.000941,0.000782,-0.000329,0.000059,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.016041,-0.027570,-0.006412,0.000935,-0.000109,0.000076,-0.000030,0.000005,0.982495,-0.064316,-0.014959,0.002180,-0.000254,0.000177,-0.000069,0.000012,1.824719,0.019212,0.004468,-0.000651,0.000076,-0.000053,0.000021,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.049146,-0.037787,-0.003838,0.000846,0.000007,-0.000004,0.000001,-0.000000,0.905267,-0.088152,-0.008954,0.001975,0.000016,-0.000010,0.000003,-0.000001,1.847789,0.026332,0.002674,-0.000590,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.089920,-0.042909,-0.001281,0.000854,-0.000000,0.000000,-0.000000,0.000000,0.810145,-0.100102,-0.002988,0.001992,-0.000001,0.000000,-0.000000,0.000000,1.876203,0.029901,0.000892,-0.000595,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.133256,-0.042909,0.001281,0.000854,0.000000,-0.000001,0.000000,-0.000000,0.709048,-0.100102,0.002988,0.001992,0.000001,-0.000001,0.000001,-0.000001,1.906401,0.029901,-0.000893,-0.000595,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.174031,-0.037787,0.003838,0.000847,-0.000007,0.000007,-0.000007,0.000005,0.613925,-0.088153,0.008953,0.001975,-0.000016,0.000015,-0.000015,0.000012,1.934815,0.026331,-0.002675,-0.000590,0.000005,-0.000005,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.207135,-0.027569,0.006412,0.000935,0.000109,-0.000050,0.000115,-0.000084,0.536696,-0.064317,0.014959,0.002181,0.000254,-0.000116,0.000269,-0.000196,1.957882,0.019211,-0.004468,-0.000651,-0.000076,0.000035,-0.000080,0.000058,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.227267,-0.011652,0.009335,0.000236,-0.001351,0.000008,-0.001691,0.001111,0.489728,-0.027184,0.021777,0.000552,-0.003152,0.000019,-0.003944,0.002593,1.971911,0.008119,-0.006504,-0.000165,0.000941,-0.000006,0.001178,-0.000774,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.500000,0.000000,0.000000,0.000000,0.029116,-0.031208,0.014346,-0.002613,0.000000,0.000000,0.000000,0.000000,0.026325,-0.028218,0.012971,-0.002363,1.500000,0.000000,0.000000,0.000000,-0.022297,0.023900,-0.010986,0.002001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.509640,0.028205,0.022927,-0.000156,-0.003191,0.002635,-0.001105,0.000196,0.008716,0.025501,0.020728,-0.000142,-0.002885,0.002382,-0.000999,0.000177,1.492618,-0.021600,-0.017557,0.000120,0.002444,-0.002018,0.000846,-0.000150,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.559150,0.068739,0.017192,-0.001826,0.000255,-0.000177,0.000068,-0.000012,0.053478,0.062145,0.015540,-0.001652,0.000231,-0.000160,0.000062,-0.000011,1.454704,-0.052638,-0.013164,0.001399,-0.000196,0.000135,-0.000052,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.643390,0.098109,0.012256,-0.001618,-0.000016,0.000009,-0.000003,0.000001,0.129634,0.088691,0.011075,-0.001463,-0.000015,0.000008,-0.000003,0.000001,1.390197,-0.075126,-0.009383,0.001239,0.000012,-0.000007,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.752127,0.117733,0.007361,-0.001636,0.000001,-0.000000,0.000000,-0.000000,0.227929,0.106421,0.006648,-0.001479,0.000001,-0.000000,0.000000,-0.000000,1.306934,-0.090148,-0.005634,0.001253,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.875586,0.127549,0.002455,-0.001635,-0.000000,0.000000,-0.000000,-0.000000,0.339519,0.115281,0.002213,-0.001478,0.000000,-0.000000,-0.000000,0.000000,1.212405,-0.097659,-0.001877,0.001252,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.003955,0.127554,-0.002450,-0.001635,0.000000,-0.000000,0.000000,-0.000000,0.455536,0.115276,-0.002219,-0.001477,0.000000,-0.000000,0.000000,-0.000000,1.114120,-0.097659,0.001878,0.001252,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.127423,0.117747,-0.007357,-0.001636,-0.000001,0.000001,-0.000001,0.000001,0.567115,0.106406,-0.006652,-0.001478,-0.000001,0.000001,-0.000001,0.000001,1.019591,-0.090147,0.005634,0.001253,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.236177,0.098127,-0.012255,-0.001619,0.000016,-0.000015,0.000015,-0.000012,0.665392,0.088671,-0.011076,-0.001462,0.000015,-0.000014,0.000013,-0.000011,0.936330,-0.075124,0.009383,0.001239,-0.000012,0.000011,-0.000011,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.320434,0.068755,-0.017194,-0.001828,-0.000255,0.000114,-0.000265,0.000196,0.741528,0.062127,-0.015538,-0.001651,-0.000231,0.000103,-0.000240,0.000177,0.871825,-0.052637,0.013164,0.001399,0.000196,-0.000087,0.000203,-0.000150,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.369957,0.028213,-0.022933,-0.000157,0.003192,-0.000005,0.003946,-0.002614,0.786277,0.025493,-0.020722,-0.000141,0.002884,-0.000005,0.003566,-0.002362,0.833912,-0.021599,0.017556,0.000120,-0.002444,0.000004,-0.003021,0.002001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.467080,0.000000,0.000000,0.000000,-0.059113,0.063827,-0.029436,0.005373,0.178880,0.000000,0.000000,0.000000,-0.007261,0.007858,-0.003628,0.000663,2.174900,0.000000,0.000000,-0.000000,-0.016719,0.018043,-0.008319,0.001518,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.447731,-0.056323,-0.045118,0.001147,0.006531,-0.005423,0.002284,-0.000406,0.176512,-0.006883,-0.005489,0.000171,0.000803,-0.000669,0.000282,-0.000050,2.169423,-0.015949,-0.012790,0.000308,0.001847,-0.001532,0.000645,-0.000115,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.350423,-0.133245,-0.030981,0.004520,-0.000527,0.000367,-0.000143,0.000025,0.164676,-0.016140,-0.003673,0.000575,-0.000069,0.000045,-0.000017,0.000003,2.141837,-0.037809,-0.008832,0.001270,-0.000146,0.000104,-0.000041,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.190439,-0.182606,-0.018539,0.004091,0.000033,-0.000020,0.000007,-0.000001,0.145399,-0.021899,-0.002115,0.000503,-0.000000,-0.000002,0.000001,-0.000000,2.096390,-0.051924,-0.005322,0.001159,0.000012,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.006596,-0.207343,-0.006183,0.004126,-0.000002,0.000001,-0.000000,0.000000,0.121887,-0.024628,-0.000621,0.000491,-0.000004,0.000000,-0.000000,-0.000000,2.040311,-0.059063,-0.001809,0.001176,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.215996,-0.207333,0.006193,0.004126,0.000002,-0.000003,0.000002,-0.000001,0.097124,-0.024413,0.000830,0.000477,-0.000003,-0.000000,0.000000,-0.000000,1.980616,-0.059149,0.001726,0.001181,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.413011,-0.182577,0.018547,0.004089,-0.000034,0.000032,-0.000032,0.000025,0.074015,-0.021334,0.002243,0.000463,-0.000006,0.000004,-0.000004,0.000003,1.924375,-0.052153,0.005267,0.001174,-0.000009,0.000009,-0.000009,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.572959,-0.133204,0.030982,0.004515,0.000526,-0.000241,0.000557,-0.000406,0.055384,-0.015464,0.003642,0.000506,0.000059,-0.000027,0.000064,-0.000047,1.878662,-0.038090,0.008841,0.001298,0.000151,-0.000069,0.000160,-0.000116,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.670230,-0.056297,0.045101,0.001142,-0.006527,0.000040,-0.008168,0.005369,0.044118,-0.006503,0.005223,0.000116,-0.000751,0.000004,-0.000938,0.000617,1.850836,-0.016112,0.012902,0.000334,-0.001869,0.000012,-0.002340,0.001538,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.689570,0.000000,0.000000,0.000000,0.032046,-0.034285,0.015747,-0.002867,0.041886,0.000000,0.000000,-0.000000,-0.005083,0.005372,-0.002454,0.000445,1.845300,0.000000,0.000000,-0.000000,0.001277,-0.001413,0.000659,-0.000121,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.678929,0.031174,0.025431,-0.000058,-0.003505,0.002890,-0.001211,0.000214,0.040166,-0.005079,-0.004238,-0.000109,0.000548,-0.000448,0.000186,-0.000033,1.845702,0.001148,0.000871,-0.000085,-0.000145,0.000123,-0.000052,0.000009,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.623994,0.076527,0.019463,-0.001898,0.000280,-0.000193,0.000075,-0.000013,0.030994,-0.013040,-0.003647,0.000185,-0.000043,0.000030,-0.000011,0.000002,1.847570,0.002418,0.000383,-0.000157,0.000012,-0.000008,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.529753,0.110272,0.014368,-0.001666,-0.000017,0.000010,-0.000004,0.000001,0.014468,-0.019858,-0.003184,0.000151,0.000003,-0.000001,0.000000,-0.000000,1.850220,0.002735,-0.000062,-0.000147,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.406789,0.133976,0.009330,-0.001680,0.000004,0.000000,-0.000000,0.000000,-0.008421,-0.025765,-0.002719,0.000157,0.000001,0.000000,-0.000001,0.000000,1.852745,0.002170,-0.000502,-0.000146,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.265158,0.147611,0.004311,-0.001666,0.000004,-0.000000,-0.000000,0.000000,-0.036746,-0.030726,-0.002239,0.000164,0.000005,0.000002,0.000002,0.000000,1.854268,0.000732,-0.000935,-0.000142,0.000003,0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.114899,0.151249,-0.000663,-0.001647,0.000010,0.000004,-0.000001,0.000000,-0.069538,-0.034671,-0.001670,0.000239,0.000041,0.000010,-0.000003,0.000000,1.853928,-0.001539,-0.001314,-0.000094,0.000028,0.000008,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.034054,0.145039,-0.005514,-0.001580,0.000022,0.000002,-0.000001,0.000000,-0.105592,-0.037096,-0.000641,0.000462,0.000065,0.000001,-0.000002,-0.000000,1.851016,-0.004303,-0.001365,0.000075,0.000052,0.000002,-0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.172022,0.129367,-0.010108,-0.001480,0.000026,-0.000002,-0.000003,0.000001,-0.142804,-0.036742,0.001109,0.000686,0.000037,-0.000015,0.000003,-0.000000,1.845475,-0.006600,-0.000832,0.000270,0.000036,-0.000012,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.289823,0.104798,-0.014423,-0.001401,0.000023,-0.000016,0.000014,-0.000012,-0.177727,-0.032379,0.003273,0.000729,-0.000005,0.000005,-0.000005,0.000004,1.838340,-0.007360,0.000097,0.000326,0.000001,0.000001,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.378807,0.071762,-0.018685,-0.001599,-0.000256,0.000113,-0.000263,0.000196,-0.206105,-0.023643,0.005491,0.000805,0.000093,-0.000043,0.000099,-0.000072,1.831404,-0.006180,0.001093,0.000353,0.000029,-0.000014,0.000032,-0.000023,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.430074,0.028927,-0.023722,0.000103,0.003223,0.000004,0.003953,-0.002631,-0.223375,-0.009998,0.008008,0.000206,-0.001160,0.000007,-0.001452,0.000954,1.826695,-0.002854,0.002192,0.000177,-0.000354,0.000006,-0.000456,0.000294,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.439930,0.000000,0.000000,0.000000,-0.016394,0.017598,-0.008095,0.001475,-0.226810,0.000000,0.000000,0.000000,0.024693,-0.026591,0.012249,-0.002234,1.825700,0.000000,0.000000,-0.000000,-0.006790,0.007270,-0.003341,0.000608,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.434514,-0.015830,-0.012831,0.000133,0.001800,-0.001488,0.000625,-0.000111,-0.218693,0.023672,0.019066,-0.000352,-0.002720,0.002254,-0.000948,0.000168,1.823448,-0.006592,-0.005369,0.000023,0.000743,-0.000613,0.000257,-0.000046,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.406812,-0.038360,-0.009466,0.001073,-0.000144,0.000100,-0.000039,0.000007,-0.177553,0.056627,0.013542,-0.001764,0.000218,-0.000152,0.000059,-0.000010,1.811851,-0.016131,-0.004072,0.000413,-0.000059,0.000041,-0.000016,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.359983,-0.054332,-0.006547,0.000962,0.000013,-0.000004,0.000002,-0.000000,-0.109032,0.078816,0.008714,-0.001584,-0.000012,0.000010,-0.000003,0.000001,1.792031,-0.023142,-0.002957,0.000367,0.000006,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.300077,-0.064495,-0.003593,0.001011,0.000017,0.000004,-0.000000,-0.000000,-0.023091,0.091478,0.003954,-0.001573,0.000015,0.000003,0.000002,-0.000001,1.766305,-0.027931,-0.001817,0.000397,0.000014,0.000004,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.233021,-0.068560,-0.000424,0.001104,0.000021,-0.000007,0.000001,0.000000,0.070787,0.094750,-0.000626,-0.001461,0.000042,-0.000005,-0.000004,0.000002,1.736972,-0.030298,-0.000501,0.000493,0.000032,-0.000006,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.165156,-0.066042,0.002956,0.001134,0.000000,-0.000002,0.000001,-0.000001,0.163484,0.089242,-0.004842,-0.001379,0.000004,-0.000002,0.000001,0.000000,1.706691,-0.029728,0.001098,0.000551,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.103203,-0.056733,0.006348,0.001122,-0.000010,0.000009,-0.000009,0.000007,0.246508,0.075432,-0.008960,-0.001361,0.000013,-0.000012,0.000012,-0.000009,1.678613,-0.025876,0.002753,0.000548,-0.000005,0.000005,-0.000004,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.053938,-0.040666,0.009766,0.001250,0.000157,-0.000071,0.000164,-0.000120,0.311622,0.053425,-0.013108,-0.001526,-0.000202,0.000091,-0.000211,0.000155,1.656037,-0.018725,0.004420,0.000607,0.000073,-0.000033,0.000077,-0.000056,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.024417,-0.016971,0.013681,0.000238,-0.001948,0.000008,-0.002425,0.001599,0.350246,0.022100,-0.017892,-0.000213,0.002517,-0.000007,0.003123,-0.002064,1.642400,-0.007868,0.006321,0.000137,-0.000908,0.000005,-0.001134,0.000746,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.018599,0.000000,0.000000,0.000000,0.009400,-0.010107,0.004652,-0.000848,0.357810,0.000000,0.000000,0.000000,-0.022813,0.024533,-0.011294,0.002059,1.639700,0.000000,0.000000,0.000000,0.013335,-0.014341,0.006602,-0.001204,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.021696,0.009042,0.007305,-0.000107,-0.001034,0.000856,-0.000360,0.000064,0.350295,-0.021939,-0.017719,0.000265,0.002509,-0.002077,0.000873,-0.000155,1.644093,0.012822,0.010355,-0.000156,-0.001467,0.001214,-0.000510,0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.037462,0.021763,0.005284,-0.000645,0.000083,-0.000058,0.000022,-0.000004,0.312051,-0.052778,-0.012798,0.001571,-0.000201,0.000140,-0.000054,0.000009,1.666441,0.030838,0.007473,-0.000920,0.000118,-0.000082,0.000032,-0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.063908,0.030548,0.003526,-0.000577,-0.000005,0.000003,-0.000001,0.000000,0.247940,-0.074029,-0.008514,0.001406,0.000013,-0.000007,0.000003,-0.000000,1.703895,0.043240,0.004964,-0.000824,-0.000008,0.000004,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.097401,0.035856,0.001780,-0.000583,0.000000,-0.000000,-0.000000,-0.000000,0.166812,-0.086809,-0.004261,0.001421,-0.000001,0.000000,-0.000000,0.000000,1.751272,0.050682,0.002474,-0.000832,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.134455,0.037667,0.000030,-0.000584,-0.000001,-0.000000,0.000000,-0.000000,0.077161,-0.091071,-0.000001,0.001420,0.000000,0.000000,-0.000000,0.000000,1.803597,0.053137,-0.000019,-0.000830,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.171567,0.035971,-0.001728,-0.000589,-0.000002,0.000000,-0.000000,0.000000,-0.012491,-0.086812,0.004260,0.001421,0.000001,-0.000001,0.000001,-0.000000,1.855885,0.050611,-0.002507,-0.000828,0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.205219,0.030743,-0.003500,-0.000589,0.000004,-0.000005,0.000005,-0.000004,-0.093622,-0.074031,0.008515,0.001407,-0.000013,0.000012,-0.000012,0.000009,1.903162,0.043118,-0.004980,-0.000816,0.000008,-0.000007,0.000007,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.231873,0.021968,-0.005303,-0.000663,-0.000085,0.000038,-0.000088,0.000065,-0.157734,-0.052777,0.012799,0.001570,0.000201,-0.000091,0.000211,-0.000155,1.940487,0.030710,-0.007461,-0.000908,-0.000116,0.000053,-0.000122,0.000090,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.247805,0.009149,-0.007382,-0.000119,0.001048,-0.000004,0.001304,-0.000860,-0.195975,-0.021937,0.017718,0.000264,-0.002509,0.000009,-0.003119,0.002059,1.962731,0.012755,-0.010306,-0.000149,0.001458,-0.000005,0.001812,-0.001196,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.250940,0.000000,0.000000,0.000000,0.002861,-0.003067,0.001410,-0.000257,-0.203490,0.000000,0.000000,0.000000,0.028180,-0.030334,0.013970,-0.002548,1.967100,0.000000,0.000000,0.000000,-0.014367,0.015395,-0.007076,0.001289,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.251887,0.002772,0.002254,-0.000015,-0.000314,0.000259,-0.000109,0.000019,-0.194221,0.027039,0.021795,-0.000380,-0.003103,0.002570,-0.001081,0.000192,1.962341,-0.013928,-0.011328,0.000068,0.001574,-0.001299,0.000545,-0.000096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.256754,0.006757,0.001691,-0.000179,0.000025,-0.000017,0.000006,-0.000001,-0.147190,0.064785,0.015554,-0.001994,0.000248,-0.000174,0.000068,-0.000011,1.937876,-0.033985,-0.008525,0.000892,-0.000126,0.000086,-0.000032,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.265036,0.009644,0.001199,-0.000168,-0.000009,-0.000002,0.000001,0.000000,-0.068714,0.090363,0.010103,-0.001782,-0.000005,0.000015,-0.000005,0.000001,1.896191,-0.048585,-0.006101,0.000816,0.000032,0.000005,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.275701,0.011500,0.000639,-0.000202,-0.000003,0.000004,-0.000001,0.000000,0.029976,0.105254,0.004819,-0.001724,0.000021,-0.000003,-0.000001,0.000000,1.842357,-0.058194,-0.003433,0.000963,0.000032,-0.000007,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.287637,0.012171,0.000036,-0.000198,0.000002,-0.000001,0.000000,0.000000,0.138342,0.109785,-0.000265,-0.001677,0.000004,-0.000002,0.000001,-0.000000,1.781717,-0.062079,-0.000421,0.001026,0.000004,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.299648,0.011655,-0.000551,-0.000195,0.000000,0.000000,-0.000000,0.000000,0.246187,0.104231,-0.005287,-0.001674,-0.000001,0.000001,-0.000001,0.000001,1.720245,-0.059837,0.002665,0.001029,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.310557,0.009969,-0.001134,-0.000193,0.000002,-0.000002,0.000002,-0.000001,0.343457,0.088638,-0.010299,-0.001657,0.000015,-0.000014,0.000014,-0.000011,1.664102,-0.051422,0.005746,0.001019,-0.000009,0.000009,-0.000008,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.319200,0.007122,-0.001721,-0.000215,-0.000027,0.000012,-0.000029,0.000021,0.420142,0.063063,-0.015348,-0.001853,-0.000240,0.000108,-0.000251,0.000184,1.619443,-0.036869,0.008850,0.001135,0.000142,-0.000064,0.000149,-0.000109,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.324364,0.002965,-0.002393,-0.000038,0.000340,-0.000001,0.000422,-0.000279,0.465806,0.026175,-0.021156,-0.000296,0.002990,-0.000010,0.003714,-0.002453,1.592675,-0.015389,0.012404,0.000217,-0.001766,0.000008,-0.002199,0.001450,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.325380,0.000000,0.000000,0.000000,-0.030618,0.032999,-0.015206,0.002774,0.474770,0.000000,0.000000,0.000000,-0.041573,0.044451,-0.020411,0.003715,1.587400,0.000000,0.000000,0.000000,0.003344,-0.003703,0.001727,-0.000317,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.315329,-0.029296,-0.023556,0.000486,0.003376,-0.002799,0.001178,-0.000209,0.460952,-0.040496,-0.033074,0.000026,0.004544,-0.003746,0.001570,-0.000278,1.588450,0.002997,0.002266,-0.000231,-0.000380,0.000321,-0.000137,0.000024,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.264510,-0.069835,-0.016554,0.002238,-0.000270,0.000188,-0.000071,0.000012,0.389498,-0.099646,-0.025479,0.002413,-0.000366,0.000256,-0.000107,0.000020,1.593312,0.006275,0.000970,-0.000416,0.000031,-0.000020,0.000005,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.180217,-0.096714,-0.010400,0.002029,0.000020,-0.000005,-0.000012,0.000002,0.266589,-0.144051,-0.019060,0.002075,0.000016,-0.000036,0.000073,-0.000015,1.600157,0.007019,-0.000225,-0.000404,-0.000004,-0.000008,0.000026,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.075137,-0.111426,-0.004371,0.001900,-0.000108,0.000007,0.000013,-0.000004,0.105592,-0.175726,-0.012311,0.002725,0.000416,-0.000085,-0.000031,0.000014,1.606556,0.005424,-0.001254,-0.000156,0.000167,-0.000032,-0.000013,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.038851,-0.114813,0.000867,0.001664,-0.000013,0.000013,-0.000006,0.000001,-0.079406,-0.191025,-0.002672,0.003392,0.000002,-0.000023,0.000016,-0.000004,1.610697,0.002914,-0.001123,0.000122,0.000003,-0.000010,0.000007,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.151138,-0.108101,0.005847,0.001664,0.000003,-0.000002,0.000001,-0.000001,-0.269719,-0.186227,0.007453,0.003363,-0.000002,0.000001,-0.000001,-0.000001,1.612609,0.001027,-0.000770,0.000114,-0.000001,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.251726,-0.091410,0.010839,0.001653,-0.000015,0.000014,-0.000014,0.000011,-0.445134,-0.161246,0.017514,0.003327,-0.000030,0.000027,-0.000026,0.000021,1.612979,-0.000172,-0.000427,0.000115,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.330648,-0.064766,0.015880,0.001854,0.000245,-0.000110,0.000256,-0.000188,-0.585547,-0.116233,0.027633,0.003690,0.000450,-0.000205,0.000475,-0.000347,1.612495,-0.000679,-0.000077,0.000121,0.000006,-0.000003,0.000007,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.377477,-0.026799,0.021693,0.000262,-0.003053,0.000009,-0.003788,0.002504,-0.670084,-0.048703,0.039182,0.000781,-0.005607,0.000027,-0.006993,0.004607,1.611865,-0.000452,0.000298,0.000090,-0.000068,0.000003,-0.000094,0.000058,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.386650,0.000000,0.000000,-0.000000,-0.001463,0.001573,-0.000724,0.000132,-0.686790,0.000000,0.000000,-0.000000,0.009173,-0.009864,0.004541,-0.000828,1.611700,0.000000,0.000000,0.000000,-0.007918,0.008515,-0.003920,0.000715,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.387132,-0.001407,-0.001136,0.000017,0.000161,-0.000133,0.000056,-0.000010,-0.683768,0.008821,0.007125,-0.000106,-0.001009,0.000835,-0.000351,0.000062,1.609092,-0.007614,-0.006150,0.000092,0.000871,-0.000721,0.000303,-0.000054,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.389584,-0.003384,-0.000820,0.000101,-0.000013,0.000009,-0.000003,0.000001,-0.668391,0.021222,0.005146,-0.000631,0.000081,-0.000056,0.000022,-0.000004,1.595819,-0.018317,-0.004442,0.000545,-0.000070,0.000049,-0.000019,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.393694,-0.004746,-0.000546,0.000090,0.000001,-0.000000,0.000000,-0.000000,-0.642612,0.029766,0.003423,-0.000566,-0.000005,0.000003,-0.000001,0.000000,1.573568,-0.025692,-0.002954,0.000488,0.000004,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.398895,-0.005565,-0.000273,0.000091,-0.000000,0.000000,-0.000000,0.000000,-0.609991,0.034905,0.001713,-0.000571,0.000000,-0.000000,0.000000,-0.000000,1.545413,-0.030127,-0.001478,0.000493,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.404642,-0.005838,0.000000,0.000091,-0.000000,0.000000,-0.000000,0.000000,-0.573943,0.036619,0.000000,-0.000571,-0.000000,-0.000000,0.000000,-0.000000,1.514300,-0.031605,0.000000,0.000493,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.410388,-0.005564,0.000273,0.000091,0.000000,-0.000000,0.000000,-0.000000,-0.537895,0.034907,-0.001713,-0.000571,-0.000000,0.000000,-0.000000,0.000000,1.483187,-0.030127,0.001478,0.000493,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.415588,-0.004745,0.000546,0.000090,-0.000001,0.000001,-0.000001,0.000001,-0.505272,0.029769,-0.003423,-0.000566,0.000005,-0.000005,0.000005,-0.000004,1.455031,-0.025692,0.002955,0.000488,-0.000004,0.000004,-0.000004,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.419697,-0.003383,0.000820,0.000101,0.000013,-0.000006,0.000014,-0.000010,-0.479491,0.021224,-0.005146,-0.000632,-0.000081,0.000037,-0.000085,0.000062,1.432781,-0.018317,0.004442,0.000545,0.000070,-0.000032,0.000073,-0.000054,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.422148,-0.001406,0.001136,0.000017,-0.000161,0.000001,-0.000200,0.000132,-0.464112,0.008823,-0.007126,-0.000106,0.001009,-0.000004,0.001254,-0.000828,1.419508,-0.007614,0.006150,0.000092,-0.000871,0.000003,-0.001083,0.000715,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.422630,0.000000,0.000000,0.000000,0.006563,-0.007114,0.003286,-0.000601,-0.461090,0.000000,0.000000,0.000000,0.054930,-0.059613,0.027554,-0.005037,1.416900,0.000000,0.000000,0.000000,-0.005019,0.005450,-0.002520,0.000461,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.420495,0.006197,0.004923,-0.000177,-0.000728,0.000606,-0.000256,0.000046,-0.443255,0.051726,0.040997,-0.001606,-0.006103,0.005087,-0.002149,0.000383,1.415272,-0.004720,-0.003736,0.000152,0.000558,-0.000465,0.000197,-0.000035,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.409885,0.014413,0.003202,-0.000552,0.000058,-0.000041,0.000016,-0.000003,-0.354921,0.119708,0.026232,-0.004733,0.000493,-0.000346,0.000136,-0.000024,1.407223,-0.010895,-0.002370,0.000438,-0.000045,0.000032,-0.000012,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.392792,0.019264,0.001665,-0.000509,-0.000006,0.000001,-0.000001,0.000000,-0.213455,0.158864,0.013069,-0.004337,-0.000032,0.000019,-0.000007,0.000001,1.394372,-0.014405,-0.001155,0.000399,0.000002,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.372377,0.021046,0.000106,-0.000530,-0.000005,-0.000000,-0.000000,0.000000,-0.045878,0.171924,-0.000023,-0.004371,0.000002,0.000002,-0.000002,0.000001,1.379211,-0.015517,0.000042,0.000396,-0.000002,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.351760,0.019645,-0.001518,-0.000550,-0.000001,-0.000003,0.000004,-0.000003,0.121656,0.158784,-0.013098,-0.004328,0.000033,-0.000031,0.000031,-0.000024,1.364129,-0.014258,0.001211,0.000383,-0.000005,0.000003,-0.000003,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.334187,0.014941,-0.003211,-0.000614,-0.000065,0.000030,-0.000067,0.000049,0.263024,0.119601,-0.026229,-0.004721,-0.000492,0.000230,-0.000529,0.000382,1.351463,-0.010692,0.002365,0.000414,0.000043,-0.000020,0.000047,-0.000034,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.323125,0.006502,-0.005135,-0.000225,0.000771,-0.000008,0.000977,-0.000638,0.351267,0.051664,-0.040954,-0.001596,0.006095,-0.000057,0.007690,-0.005029,1.343586,-0.004604,0.003655,0.000135,-0.000542,0.000005,-0.000683,0.000447,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.320880,0.000000,0.000000,0.000000,-0.017721,0.019361,-0.008976,0.001644,0.369080,0.000000,0.000000,0.000000,-0.050122,0.054761,-0.025386,0.004649,1.342000,0.000000,0.000000,0.000000,0.000729,-0.000797,0.000369,-0.000068,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.326572,-0.016425,-0.012828,0.000749,0.001984,-0.001661,0.000704,-0.000126,0.352982,-0.046456,-0.036282,0.002119,0.005610,-0.004699,0.001992,-0.000356,1.342234,0.000676,0.000528,-0.000031,-0.000082,0.000068,-0.000029,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.354174,-0.036860,-0.007369,0.001753,-0.000161,0.000114,-0.000045,0.000008,0.274910,-0.104256,-0.020845,0.004959,-0.000456,0.000322,-0.000127,0.000022,1.343370,0.001517,0.000303,-0.000072,0.000007,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.396734,-0.046629,-0.002447,0.001625,0.000011,-0.000007,0.000003,-0.000001,0.154530,-0.131889,-0.006921,0.004596,0.000031,-0.000021,0.000008,-0.000002,1.345122,0.001920,0.000101,-0.000067,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.444179,-0.046628,0.002447,0.001625,-0.000011,0.000011,-0.000011,0.000008,0.020331,-0.131889,0.006921,0.004596,-0.000031,0.000030,-0.000030,0.000022,1.347076,0.001920,-0.000101,-0.000067,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.486738,-0.036858,0.007369,0.001753,0.000161,-0.000077,0.000176,-0.000126,-0.100050,-0.104256,0.020845,0.004959,0.000456,-0.000218,0.000498,-0.000356,1.348829,0.001518,-0.000303,-0.000072,-0.000007,0.000003,-0.000007,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.514339,-0.016424,0.012827,0.000749,-0.001983,0.000027,-0.002530,0.001644,-0.178122,-0.046456,0.036282,0.002119,-0.005610,0.000075,-0.007158,0.004649,1.349966,0.000677,-0.000528,-0.000031,0.000082,-0.000001,0.000104,-0.000068,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.520030,0.000000,0.000000,0.000000,0.014075,-0.014919,0.006822,-0.001238,-0.194220,0.000000,0.000000,0.000000,-0.002858,0.003136,-0.001457,0.000267,1.350200,0.000000,0.000000,0.000000,-0.015941,0.016926,-0.007748,0.001407,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.515289,0.013975,0.011596,0.000219,-0.001527,0.001247,-0.000520,0.000092,-0.195132,-0.002622,-0.002029,0.000143,0.000320,-0.000271,0.000115,-0.000020,1.344844,-0.015770,-0.013051,-0.000205,0.001727,-0.001418,0.000591,-0.000104,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.490208,0.035471,0.009683,-0.000614,0.000115,-0.000083,0.000032,-0.000005,-0.199496,-0.005779,-0.001095,0.000295,-0.000030,0.000018,-0.000007,0.000001,1.316614,-0.039850,-0.010801,0.000703,-0.000141,0.000094,-0.000036,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.445610,0.053191,0.008061,-0.000541,-0.000014,0.000004,-0.000002,0.000000,-0.206092,-0.007145,-0.000287,0.000259,-0.000002,-0.000001,0.000000,-0.000000,1.266589,-0.059610,-0.009009,0.000574,0.000005,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.384911,0.067648,0.006380,-0.000575,-0.000006,-0.000000,0.000000,0.000000,-0.213269,-0.006958,0.000466,0.000242,-0.000005,0.000000,0.000000,-0.000000,1.198545,-0.075904,-0.007288,0.000568,-0.000005,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.311465,0.078655,0.004615,-0.000599,-0.000003,0.000001,0.000000,0.000000,-0.219523,-0.005315,0.001169,0.000227,-0.000003,-0.000000,-0.000000,0.000000,1.115916,-0.088798,-0.005619,0.000541,-0.000010,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.228795,0.086084,0.002816,-0.000592,0.000010,0.000003,-0.000003,0.000001,-0.223445,-0.002308,0.001829,0.000211,-0.000005,-0.000001,-0.000000,0.000000,1.022029,-0.098456,-0.004061,0.000497,-0.000013,-0.000000,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.140476,0.089985,0.001106,-0.000550,0.000011,0.000001,-0.000002,0.000001,-0.223720,0.001955,0.002416,0.000174,-0.000014,-0.000002,0.000001,-0.000000,0.919998,-0.105132,-0.002633,0.000460,-0.000006,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.049923,0.090591,-0.000480,-0.000509,0.000010,0.000001,-0.000001,0.000000,-0.219191,0.007244,0.002838,0.000102,-0.000024,-0.000003,0.000002,-0.000001,0.812689,-0.109037,-0.001281,0.000443,-0.000004,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.039690,0.088150,-0.001937,-0.000458,0.000018,0.000002,-0.000002,0.000001,-0.209034,0.013122,0.002988,-0.000003,-0.000029,-0.000001,0.000002,-0.000001,0.702810,-0.110285,0.000025,0.000427,-0.000004,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.125464,0.082978,-0.003194,-0.000374,0.000030,0.000004,-0.000004,0.000001,-0.192956,0.018973,0.002807,-0.000118,-0.000032,-0.000002,0.000004,-0.000001,0.592973,-0.108970,0.001282,0.000411,-0.000004,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.204906,0.075594,-0.004128,-0.000248,0.000036,0.000003,-0.000004,0.000001,-0.171325,0.024110,0.002273,-0.000233,-0.000026,0.000000,0.000002,-0.000001,0.485693,-0.105188,0.002493,0.000397,-0.000003,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.276159,0.066731,-0.004672,-0.000122,0.000027,0.000000,-0.000003,0.000001,-0.145200,0.027861,0.001438,-0.000315,-0.000015,0.000001,0.000001,-0.000000,0.383393,-0.099020,0.003669,0.000388,-0.000002,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.338122,0.057119,-0.004902,-0.000045,0.000009,-0.000003,0.000001,-0.000000,-0.116229,0.029742,0.000424,-0.000353,-0.000004,0.000002,-0.000000,0.000000,0.288428,-0.090523,0.004826,0.000384,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.390300,0.047204,-0.005003,-0.000026,0.000003,0.000000,-0.000000,0.000000,-0.086419,0.029519,-0.000651,-0.000362,-0.000001,0.000000,0.000000,-0.000000,0.203115,-0.079720,0.005976,0.000383,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.432478,0.037132,-0.005063,-0.000015,0.000002,-0.000000,-0.000000,0.000000,-0.057914,0.027128,-0.001743,-0.000366,-0.000001,0.000000,-0.000000,0.000000,0.129753,-0.066621,0.007122,0.000382,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.464534,0.026967,-0.005099,-0.000007,0.000004,-0.000003,0.000002,-0.000002,-0.032895,0.022543,-0.002841,-0.000364,0.000003,-0.000003,0.000003,-0.000003,0.070636,-0.051234,0.008261,0.000373,-0.000007,0.000006,-0.000006,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.486396,0.016748,-0.005136,-0.000048,-0.000050,0.000020,-0.000047,0.000037,-0.013557,0.015766,-0.003955,-0.000413,-0.000059,0.000026,-0.000061,0.000045,0.028036,-0.033588,0.009419,0.000466,0.000112,-0.000047,0.000111,-0.000084,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.497919,0.006206,-0.005312,0.000303,0.000638,0.000011,0.000749,-0.000513,-0.002208,0.006461,-0.005255,-0.000032,0.000730,-0.000001,0.000903,-0.000598,0.004423,-0.013067,0.010909,-0.000290,-0.001409,-0.000011,-0.001699,0.001143,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.379600,0.000000,0.000000,0.000000,0.001411,-0.001499,0.000686,-0.000125,0.794990,0.000000,0.000000,0.000000,-0.005338,0.005666,-0.002593,0.000471,0.826530,0.000000,0.000000,0.000000,0.012423,-0.013186,0.006034,-0.001096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.380074,0.001395,0.001153,0.000017,-0.000153,0.000126,-0.000052,0.000009,0.793196,-0.005285,-0.004376,-0.000072,0.000579,-0.000474,0.000198,-0.000035,0.830706,0.012300,0.010185,0.000167,-0.001347,0.001104,-0.000460,0.000081,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.382567,0.003516,0.000948,-0.000065,0.000012,-0.000008,0.000003,-0.000001,0.783731,-0.013365,-0.003626,0.000236,-0.000046,0.000031,-0.000012,0.000002,0.852737,0.031110,0.008442,-0.000550,0.000107,-0.000073,0.000028,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.386973,0.005240,0.000780,-0.000055,-0.000001,0.000000,-0.000000,0.000000,0.766951,-0.019994,-0.003017,0.000198,0.000003,-0.000002,0.000001,-0.000000,0.891796,0.046540,0.007021,-0.000462,-0.000007,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.392939,0.006635,0.000615,-0.000055,0.000000,-0.000000,0.000000,-0.000000,0.744139,-0.025430,-0.002418,0.000200,-0.000000,0.000000,-0.000000,0.000000,0.944892,0.059184,0.005619,-0.000469,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.400133,0.007699,0.000449,-0.000055,0.000000,0.000000,0.000000,0.000000,0.716491,-0.029665,-0.001817,0.000200,0.000000,0.000000,0.000000,-0.000000,1.009226,0.069016,0.004213,-0.000468,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.408226,0.008433,0.000286,-0.000054,0.000000,0.000000,-0.000000,0.000000,0.685209,-0.032699,-0.001217,0.000200,0.000000,0.000000,0.000000,-0.000000,1.081987,0.076037,0.002808,-0.000468,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.416891,0.008842,0.000124,-0.000053,0.000000,0.000000,-0.000000,0.000000,0.651494,-0.034531,-0.000615,0.000201,0.000000,0.000000,0.000000,-0.000000,1.160364,0.080248,0.001402,-0.000468,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.425804,0.008931,-0.000035,-0.000052,0.000000,0.000000,-0.000000,0.000000,0.616549,-0.035159,-0.000012,0.000201,0.000000,-0.000000,0.000000,-0.000000,1.241545,0.081647,-0.000003,-0.000468,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.434648,0.008706,-0.000189,-0.000051,0.000000,0.000000,-0.000000,0.000000,0.581579,-0.034579,0.000592,0.000202,0.000000,-0.000000,0.000000,-0.000000,1.322722,0.080237,-0.001408,-0.000468,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.443115,0.008178,-0.000338,-0.000049,0.000000,-0.000000,-0.000000,0.000000,0.547794,-0.032789,0.001199,0.000203,0.000000,-0.000000,0.000000,-0.000000,1.401082,0.076017,-0.002812,-0.000468,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.450906,0.007357,-0.000482,-0.000047,0.000000,-0.000000,0.000000,-0.000000,0.516407,-0.029783,0.001807,0.000203,0.000000,0.000000,0.000000,0.000000,1.473819,0.068988,-0.004216,-0.000468,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.457733,0.006252,-0.000622,-0.000046,0.000000,0.000000,-0.000000,0.000000,0.488635,-0.025558,0.002418,0.000204,0.000000,-0.000000,0.000000,-0.000000,1.538122,0.059152,-0.005620,-0.000468,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.463318,0.004872,-0.000756,-0.000044,0.000001,-0.000001,0.000001,-0.000000,0.465699,-0.020111,0.003028,0.000201,-0.000003,0.000003,-0.000002,0.000002,1.591186,0.046508,-0.007020,-0.000461,0.000007,-0.000006,0.000006,-0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.467391,0.003230,-0.000889,-0.000052,-0.000011,0.000005,-0.000011,0.000008,0.448815,-0.013452,0.003646,0.000239,0.000046,-0.000020,0.000047,-0.000035,1.630216,0.031085,-0.008437,-0.000549,-0.000107,0.000046,-0.000108,0.000081,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.469670,0.001268,-0.001054,0.000022,0.000138,0.000001,0.000167,-0.000112,0.439287,-0.005321,0.004405,-0.000071,-0.000583,-0.000003,-0.000709,0.000474,1.652228,0.012289,-0.010177,0.000168,0.001345,0.000006,0.001635,-0.001095,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.470100,0.000000,0.000000,0.000000,-0.001574,0.001718,-0.000796,0.000146,0.437480,0.000000,0.000000,0.000000,-0.018271,0.019727,-0.009098,0.001661,1.656400,0.000000,0.000000,0.000000,-0.002994,0.003232,-0.001491,0.000272,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.469594,-0.001462,-0.001144,0.000063,0.000175,-0.000148,0.000062,-0.000011,0.431499,-0.017410,-0.013948,0.000353,0.002019,-0.001676,0.000706,-0.000125,1.655420,-0.002853,-0.002285,0.000058,0.000331,-0.000275,0.000116,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.467130,-0.003302,-0.000682,0.000140,-0.000021,0.000009,-0.000004,0.000001,0.401418,-0.041193,-0.009581,0.001397,-0.000163,0.000113,-0.000044,0.000008,1.650491,-0.006749,-0.001570,0.000229,-0.000027,0.000019,-0.000007,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.463271,-0.004301,-0.000334,0.000101,-0.000005,0.000000,0.000001,-0.000000,0.351955,-0.056460,-0.005735,0.001265,0.000010,-0.000006,0.000002,-0.000000,1.642387,-0.009251,-0.000940,0.000207,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.458733,-0.004681,-0.000052,0.000089,-0.000001,0.000000,-0.000000,0.000000,0.291031,-0.064113,-0.001914,0.001276,-0.000001,0.000000,-0.000000,0.000000,1.632405,-0.010505,-0.000314,0.000209,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.454088,-0.004522,0.000210,0.000086,-0.000001,-0.000000,-0.000000,0.000000,0.226280,-0.064114,0.001914,0.001276,0.000001,-0.000001,0.000000,-0.000000,1.621796,-0.010505,0.000314,0.000209,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.449861,-0.003851,0.000456,0.000077,-0.000003,0.000001,-0.000000,0.000000,0.165356,-0.056461,0.005735,0.001265,-0.000010,0.000010,-0.000010,0.000008,1.611813,-0.009251,0.000940,0.000207,-0.000002,0.000002,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.446541,-0.002718,0.000675,0.000076,0.000008,-0.000004,0.000011,-0.000008,0.115892,-0.041194,0.009581,0.001397,0.000163,-0.000075,0.000172,-0.000125,1.603709,-0.006750,0.001570,0.000229,0.000027,-0.000012,0.000028,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.444582,-0.001117,0.000907,0.000007,-0.000127,0.000000,-0.000156,0.000104,0.085810,-0.017410,0.013948,0.000353,-0.002019,0.000012,-0.002526,0.001661,1.598780,-0.002853,0.002285,0.000058,-0.000331,0.000002,-0.000414,0.000272,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.444200,0.000000,0.000000,0.000000,-0.030286,0.032567,-0.014992,0.002733,0.079829,0.000000,0.000000,0.000000,0.005651,-0.006078,0.002798,-0.000510,1.597800,0.000000,0.000000,-0.000000,0.023786,-0.025579,0.011775,-0.002147,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.434223,-0.029128,-0.023528,0.000348,0.003331,-0.002757,0.001159,-0.000206,0.081691,0.005434,0.004389,-0.000066,-0.000622,0.000515,-0.000216,0.000038,1.605636,0.022874,0.018474,-0.000276,-0.002616,0.002166,-0.000910,0.000161,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.383443,-0.070085,-0.017003,0.002082,-0.000267,0.000186,-0.000072,0.000013,0.091163,0.013072,0.003169,-0.000389,0.000050,-0.000035,0.000013,-0.000002,1.645508,0.055025,0.013342,-0.001638,0.000210,-0.000146,0.000057,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.298295,-0.098332,-0.011324,0.001865,0.000017,-0.000010,0.000004,-0.000001,0.107041,0.018332,0.002106,-0.000349,-0.000003,0.000002,-0.000001,0.000000,1.712348,0.077177,0.008874,-0.001467,-0.000013,0.000008,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.190515,-0.115349,-0.005685,0.001884,-0.000000,0.000000,0.000000,-0.000000,0.127128,0.021492,0.001052,-0.000352,0.000000,-0.000000,0.000000,-0.000000,1.796924,0.090496,0.004439,-0.001481,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.071365,-0.121066,-0.000031,0.001886,0.000001,0.000000,0.000000,-0.000000,0.149321,0.022542,-0.000002,-0.000351,0.000000,-0.000000,0.000000,-0.000000,1.890379,0.094932,-0.000003,-0.001480,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.952155,-0.115466,0.005633,0.001891,0.000002,-0.000002,0.000001,-0.000001,0.171509,0.021483,-0.001056,-0.000351,-0.000000,0.000000,-0.000000,0.000000,1.983828,0.090486,-0.004444,-0.001481,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.844214,-0.098526,0.011301,0.001877,-0.000016,0.000016,-0.000016,0.000013,0.191585,0.018318,-0.002108,-0.000348,0.000003,-0.000003,0.000003,-0.000002,2.068390,0.077160,-0.008876,-0.001466,0.000014,-0.000013,0.000012,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.758863,-0.070284,0.017023,0.002099,0.000269,-0.000122,0.000281,-0.000206,0.207449,0.013059,-0.003167,-0.000388,-0.000050,0.000023,-0.000052,0.000038,2.135211,0.055006,-0.013340,-0.001636,-0.000210,0.000095,-0.000220,0.000161,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.707924,-0.029230,0.023602,0.000360,-0.003345,0.000013,-0.004159,0.002745,0.216911,0.005428,-0.004384,-0.000065,0.000621,-0.000002,0.000772,-0.000509,2.175068,0.022864,-0.018467,-0.000275,0.002615,-0.000010,0.003250,-0.002146,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.697910,0.000000,0.000000,0.000000,-0.029776,0.032314,-0.014936,0.002730,0.218770,0.000000,0.000000,0.000000,0.012789,-0.013878,0.006414,-0.001172,2.182900,0.000000,0.000000,-0.000000,-0.048751,0.052906,-0.024454,0.004470,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.688242,-0.028039,-0.022224,0.000870,0.003308,-0.002757,0.001165,-0.000207,0.222923,0.012044,0.009547,-0.000372,-0.001421,0.001184,-0.000500,0.000089,2.167071,-0.045907,-0.036386,0.001424,0.005417,-0.004514,0.001907,-0.000340,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.640358,-0.064893,-0.014222,0.002564,-0.000267,0.000187,-0.000074,0.000013,0.243495,0.027883,0.006115,-0.001100,0.000115,-0.000081,0.000032,-0.000006,2.088673,-0.106246,-0.023285,0.004199,-0.000438,0.000307,-0.000120,0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.563666,-0.086128,-0.007092,0.002349,0.000017,-0.000010,0.000004,-0.000001,0.276453,0.037021,0.003057,-0.001008,-0.000008,0.000004,-0.000002,0.000000,1.963110,-0.141012,-0.011611,0.003846,0.000028,-0.000016,0.000006,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.472806,-0.093228,-0.000000,0.002369,0.000000,-0.000001,0.000001,-0.000001,0.315519,0.040096,0.000014,-0.001017,-0.000000,0.000000,-0.000000,0.000000,1.814350,-0.152636,-0.000000,0.003878,0.000000,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.381945,-0.086128,0.007091,0.002349,-0.000017,0.000017,-0.000017,0.000013,0.354612,0.037074,-0.003034,-0.001011,0.000006,-0.000007,0.000007,-0.000006,1.665590,-0.141012,0.011611,0.003846,-0.000028,0.000027,-0.000027,0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.305253,-0.064894,0.014222,0.002565,0.000268,-0.000125,0.000287,-0.000207,0.387641,0.027966,-0.006111,-0.001110,-0.000117,0.000054,-0.000124,0.000090,1.540028,-0.106246,0.023285,0.004199,0.000438,-0.000205,0.000470,-0.000340,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.257368,-0.028040,0.022224,0.000870,-0.003308,0.000031,-0.004175,0.002730,0.408288,0.012097,-0.009583,-0.000383,0.001429,-0.000013,0.001804,-0.001179,1.461629,-0.045907,0.036386,0.001425,-0.005417,0.000051,-0.006836,0.004470,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.247700,0.000000,0.000000,0.000000,0.017754,-0.019092,0.008789,-0.001602,0.412460,0.000000,0.000000,0.000000,0.001893,-0.002035,0.000937,-0.000171,1.445800,0.000000,0.000000,0.000000,-0.025227,0.027129,-0.012489,0.002277,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.253549,0.017073,0.013790,-0.000206,-0.001953,0.001616,-0.000679,0.000121,0.413084,0.001820,0.001470,-0.000022,-0.000208,0.000172,-0.000072,0.000013,1.437489,-0.024260,-0.019594,0.000293,0.002775,-0.002297,0.000965,-0.000171,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.283310,0.041073,0.009959,-0.001222,0.000157,-0.000109,0.000042,-0.000007,0.416256,0.004379,0.001062,-0.000130,0.000017,-0.000012,0.000005,-0.000001,1.395200,-0.058362,-0.014152,0.001737,-0.000223,0.000155,-0.000060,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.333203,0.057610,0.006625,-0.001095,-0.000010,0.000006,-0.000002,0.000000,0.421575,0.006141,0.000706,-0.000117,-0.000001,0.000001,-0.000000,0.000000,1.324305,-0.081860,-0.009414,0.001555,0.000014,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.396337,0.067554,0.003315,-0.001106,0.000001,-0.000000,0.000000,-0.000000,0.428305,0.007201,0.000353,-0.000118,0.000000,-0.000000,0.000000,-0.000000,1.234596,-0.095991,-0.004711,0.001571,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.466100,0.070868,-0.000000,-0.001105,0.000000,-0.000000,0.000000,-0.000000,0.435741,0.007554,-0.000000,-0.000118,0.000000,-0.000000,0.000000,-0.000000,1.135465,-0.100701,0.000000,0.001570,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.535864,0.067554,-0.003315,-0.001106,-0.000000,0.000001,-0.000000,0.000000,0.443177,0.007201,-0.000353,-0.000118,-0.000000,0.000000,-0.000000,0.000000,1.036334,-0.095991,0.004711,0.001571,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.598997,0.057609,-0.006625,-0.001095,0.000010,-0.000009,0.000009,-0.000007,0.449907,0.006140,-0.000706,-0.000117,0.000001,-0.000001,0.000001,-0.000001,0.946624,-0.081860,0.009414,0.001555,-0.000014,0.000013,-0.000013,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.648890,0.041073,-0.009959,-0.001222,-0.000157,0.000071,-0.000164,0.000121,0.455225,0.004378,-0.001062,-0.000130,-0.000017,0.000008,-0.000017,0.000013,0.875730,-0.058362,0.014152,0.001737,0.000223,-0.000101,0.000233,-0.000171,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.678651,0.017074,-0.013790,-0.000206,0.001953,-0.000007,0.002428,-0.001602,0.458397,0.001820,-0.001470,-0.000022,0.000208,-0.000001,0.000259,-0.000171,0.833440,-0.024260,0.019594,0.000293,-0.002775,0.000010,-0.003449,0.002277,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.684500,0.000000,0.000000,-0.000000,0.011864,-0.012717,0.005846,-0.001065,0.459020,0.000000,0.000000,0.000000,-0.020736,0.022227,-0.010217,0.001861,0.825130,0.000000,0.000000,0.000000,0.040625,-0.043545,0.020017,-0.003646,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.688428,0.011493,0.009342,-0.000064,-0.001300,0.001074,-0.000450,0.000080,0.452154,-0.020088,-0.016328,0.000112,0.002273,-0.001877,0.000787,-0.000139,0.838581,0.039354,0.031988,-0.000218,-0.004452,0.003676,-0.001542,0.000273,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.708602,0.028009,0.007005,-0.000744,0.000104,-0.000072,0.000028,-0.000005,0.416894,-0.048954,-0.012243,0.001301,-0.000182,0.000126,-0.000049,0.000008,0.907659,0.095906,0.023985,-0.002549,0.000356,-0.000246,0.000095,-0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.742927,0.039975,0.004993,-0.000659,-0.000007,0.000004,-0.000001,0.000000,0.356902,-0.069868,-0.008726,0.001152,0.000012,-0.000007,0.000002,-0.000000,1.025190,0.136879,0.017096,-0.002258,-0.000023,0.000013,-0.000005,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.787232,0.047970,0.002998,-0.000667,0.000000,-0.000000,0.000000,-0.000000,0.279467,-0.083839,-0.005240,0.001165,-0.000001,0.000000,-0.000000,0.000000,1.176894,0.164250,0.010265,-0.002282,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.837534,0.051968,0.001000,-0.000666,-0.000000,0.000000,-0.000000,-0.000000,0.191553,-0.090825,-0.001746,0.001164,0.000000,-0.000000,0.000000,-0.000000,1.349127,0.177936,0.003421,-0.002281,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.889836,0.051970,-0.000998,-0.000666,0.000000,-0.000000,0.000000,-0.000000,0.100147,-0.090825,0.001746,0.001164,-0.000000,0.000000,-0.000000,0.000000,1.528203,0.177936,-0.003421,-0.002281,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.940141,0.047975,-0.002997,-0.000667,-0.000000,0.000001,-0.000000,0.000000,0.012233,-0.083839,0.005240,0.001165,0.000001,-0.000001,0.000000,-0.000000,1.700437,0.164250,-0.010265,-0.002282,-0.000001,0.000002,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.984454,0.039984,-0.004992,-0.000659,0.000007,-0.000006,0.000006,-0.000005,-0.065202,-0.069868,0.008726,0.001152,-0.000012,0.000011,-0.000010,0.000008,1.852140,0.136879,-0.017096,-0.002258,0.000023,-0.000021,0.000020,-0.000017,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.018787,0.028019,-0.007005,-0.000745,-0.000104,0.000047,-0.000108,0.000080,-0.125194,-0.048954,0.012243,0.001301,0.000182,-0.000081,0.000189,-0.000139,1.969671,0.095906,-0.023985,-0.002549,-0.000356,0.000159,-0.000370,0.000273,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.038970,0.011499,-0.009346,-0.000065,0.001301,-0.000002,0.001609,-0.001065,-0.160454,-0.020088,0.016328,0.000112,-0.002273,0.000004,-0.002810,0.001861,2.038749,0.039354,-0.031988,-0.000218,0.004452,-0.000007,0.005505,-0.003646,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.042900,0.000000,0.000000,0.000000,-0.016801,0.018145,-0.008369,0.001528,-0.167320,0.000000,0.000000,0.000000,0.025765,-0.027819,0.012829,-0.002342,2.052200,0.000000,0.000000,0.000000,-0.022611,0.024413,-0.011259,0.002055,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.037403,-0.016000,-0.012811,0.000333,0.001856,-0.001542,0.000650,-0.000115,-0.158886,0.024551,0.019669,-0.000498,-0.002847,0.002363,-0.000996,0.000177,2.044799,-0.021545,-0.017261,0.000437,0.002498,-0.002074,0.000874,-0.000155,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.009772,-0.037823,-0.008782,0.001284,-0.000151,0.000105,-0.000041,0.000007,-0.116466,0.058090,0.013511,-0.001969,0.000229,-0.000160,0.000062,-0.000011,2.007572,-0.050977,-0.011856,0.001728,-0.000201,0.000140,-0.000055,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.964372,-0.051810,-0.005252,0.001159,0.000009,-0.000005,0.000002,-0.000000,-0.046713,0.079620,0.008087,-0.001784,-0.000015,0.000009,-0.000003,0.000001,1.946361,-0.069870,-0.007097,0.001565,0.000013,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.908475,-0.058817,-0.001750,0.001170,-0.000000,0.000000,-0.000000,0.000000,0.039201,0.090413,0.002699,-0.001799,0.000001,-0.000000,0.000000,-0.000000,1.870966,-0.079341,-0.002368,0.001579,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.849077,-0.058809,0.001758,0.001170,0.000001,-0.000001,0.000000,-0.000000,0.130515,0.090415,-0.002698,-0.001800,-0.000001,0.000001,-0.000001,0.000001,1.790836,-0.079342,0.002368,0.001579,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.793196,-0.051786,0.005261,0.001160,-0.000010,0.000009,-0.000009,0.000007,0.216432,0.079624,-0.008086,-0.001784,0.000015,-0.000014,0.000014,-0.000011,1.715441,-0.069871,0.007097,0.001565,-0.000013,0.000012,-0.000012,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.747827,-0.037783,0.008787,0.001281,0.000149,-0.000068,0.000158,-0.000115,0.286190,0.058095,-0.013511,-0.001970,-0.000229,0.000105,-0.000243,0.000177,1.654229,-0.050978,0.011856,0.001728,0.000201,-0.000092,0.000213,-0.000155,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.720236,-0.015969,0.012793,0.000324,-0.001852,0.000011,-0.002317,0.001523,0.328615,0.024555,-0.019671,-0.000499,0.002847,-0.000018,0.003563,-0.002342,1.617002,-0.021546,0.017261,0.000437,-0.002498,0.000015,-0.003126,0.002055,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/5/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.714750,0.000000,0.000000,0.000000,-0.012652,0.013661,-0.006300,0.001150,0.337050,0.000000,0.000000,0.000000,-0.008082,0.008726,-0.004024,0.000734,1.609600,0.000000,0.000000,-0.000000,0.028880,-0.031182,0.014380,-0.002625,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.710608,-0.012056,-0.009658,0.000245,0.001398,-0.001161,0.000489,-0.000087,0.334405,-0.007701,-0.006169,0.000156,0.000893,-0.000741,0.000312,-0.000055,1.619054,0.027519,0.022046,-0.000559,-0.003191,0.002649,-0.001116,0.000198,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.689778,-0.028525,-0.006635,0.000967,-0.000113,0.000078,-0.000031,0.000005,0.321099,-0.018220,-0.004237,0.000618,-0.000072,0.000050,-0.000020,0.000003,1.666601,0.065111,0.015143,-0.002208,0.000257,-0.000179,0.000070,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.655525,-0.039098,-0.003971,0.000876,0.000007,-0.000004,0.000002,-0.000000,0.299222,-0.024972,-0.002536,0.000560,0.000005,-0.000003,0.000001,-0.000000,1.744784,0.089242,0.009064,-0.001999,-0.000017,0.000010,-0.000003,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.613337,-0.044398,-0.001325,0.000884,-0.000000,0.000000,-0.000000,0.000000,0.272277,-0.028355,-0.000846,0.000564,-0.000000,0.000000,-0.000000,0.000000,1.841080,0.101338,0.003024,-0.002017,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.568497,-0.044398,0.001325,0.000884,0.000000,-0.000001,0.000000,-0.000000,0.243640,-0.028354,0.000847,0.000564,0.000000,-0.000000,0.000000,-0.000000,1.943426,0.101337,-0.003025,-0.002017,-0.000001,0.000002,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.526307,-0.039099,0.003971,0.000876,-0.000007,0.000007,-0.000007,0.000005,0.216698,-0.024967,0.002537,0.000559,-0.000005,0.000004,-0.000004,0.000003,2.039721,0.089240,-0.009065,-0.001999,0.000017,-0.000016,0.000015,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.492054,-0.028527,0.006635,0.000967,0.000113,-0.000052,0.000119,-0.000087,0.194826,-0.018215,0.004237,0.000617,0.000072,-0.000033,0.000076,-0.000055,2.117901,0.065109,-0.015143,-0.002207,-0.000257,0.000118,-0.000272,0.000198,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.471222,-0.012057,0.009659,0.000245,-0.001398,0.000009,-0.001749,0.001150,0.181525,-0.007698,0.006167,0.000156,-0.000893,0.000006,-0.001117,0.000734,2.165447,0.027518,-0.022045,-0.000558,0.003191,-0.000020,0.003993,-0.002625,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.000000,0.000000,0.000000,0.000000,0.006815,-0.007319,0.003367,-0.000614,0.000000,0.000000,0.000000,0.000000,0.001874,-0.001996,0.000915,-0.000166,1.500000,0.000000,0.000000,0.000000,-0.012214,0.013091,-0.006018,0.001096,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.002250,0.006573,0.005323,-0.000062,-0.000749,0.000619,-0.000260,0.000046,0.000627,0.001843,0.001518,0.000014,-0.000204,0.000167,-0.000070,0.000012,1.495955,-0.011834,-0.009621,0.000064,0.001339,-0.001105,0.000464,-0.000082,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.013741,0.015898,0.003905,-0.000452,0.000061,-0.000041,0.000016,-0.000003,0.003909,0.004610,0.001222,-0.000094,0.000016,-0.000011,0.000004,-0.000001,1.475179,-0.028850,-0.007220,0.000764,-0.000107,0.000074,-0.000029,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.033125,0.022466,0.002685,-0.000396,-0.000000,0.000003,-0.000001,0.000000,0.009655,0.006801,0.000972,-0.000083,-0.000003,-0.000001,0.000000,0.000000,1.439817,-0.041192,-0.005155,0.000677,0.000007,-0.000004,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.057882,0.026659,0.001517,-0.000380,0.000005,-0.000000,-0.000000,0.000000,0.017341,0.008480,0.000698,-0.000100,-0.000005,-0.000000,0.000000,-0.000000,1.394152,-0.049454,-0.003103,0.000686,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.085684,0.028573,0.000405,-0.000363,0.000003,-0.000000,0.000000,-0.000000,0.026414,0.009557,0.000371,-0.000117,-0.000004,-0.000000,-0.000000,0.000000,1.342281,-0.053601,-0.001044,0.000687,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.114300,0.028303,-0.000668,-0.000352,0.000003,-0.000001,0.000000,-0.000000,0.036220,0.009931,-0.000005,-0.000135,-0.000005,0.000000,-0.000000,0.000000,1.288324,-0.053627,0.001019,0.000688,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.141586,0.025921,-0.001711,-0.000345,0.000001,-0.000000,0.000000,0.000000,0.046007,0.009497,-0.000439,-0.000154,-0.000004,0.000001,-0.000000,0.000000,1.236404,-0.049523,0.003085,0.000690,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.165453,0.021469,-0.002739,-0.000340,0.000004,-0.000003,0.000003,-0.000003,0.054908,0.008147,-0.000914,-0.000160,0.000001,-0.000001,0.000001,-0.000001,1.190656,-0.041285,0.005150,0.000682,-0.000007,0.000006,-0.000006,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.183844,0.014971,-0.003776,-0.000385,-0.000055,0.000025,-0.000057,0.000042,0.061982,0.005839,-0.001402,-0.000179,-0.000023,0.000010,-0.000024,0.000017,1.155202,-0.028935,0.007233,0.000771,0.000108,-0.000048,0.000112,-0.000082,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.194609,0.006121,-0.004984,-0.000023,0.000690,-0.000001,0.000852,-0.000565,0.066221,0.002437,-0.001964,-0.000034,0.000280,-0.000001,0.000348,-0.000230,1.134359,-0.011876,0.009652,0.000067,-0.001344,0.000002,-0.001662,0.001100,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.405350,0.000000,0.000000,0.000000,-0.031862,0.034402,-0.015865,0.002896,-0.341650,0.000000,0.000000,0.000000,0.005951,-0.006425,0.002963,-0.000541,1.361000,0.000000,0.000000,0.000000,-0.005814,0.006278,-0.002895,0.000528,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.394920,-0.030361,-0.024323,0.000616,0.003520,-0.002923,0.001231,-0.000219,-0.339702,0.005671,0.004543,-0.000115,-0.000657,0.000546,-0.000230,0.000041,1.359097,-0.005540,-0.004438,0.000113,0.000642,-0.000533,0.000225,-0.000040,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.342462,-0.071836,-0.016708,0.002435,-0.000283,0.000198,-0.000077,0.000013,-0.329903,0.013419,0.003122,-0.000455,0.000053,-0.000037,0.000014,-0.000003,1.349524,-0.013109,-0.003049,0.000444,-0.000052,0.000036,-0.000014,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.256203,-0.098461,-0.010001,0.002206,0.000018,-0.000011,0.000004,-0.000001,-0.313789,0.018395,0.001870,-0.000412,-0.000003,0.000002,-0.000001,0.000000,1.333784,-0.017966,-0.001824,0.000403,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.149958,-0.111808,-0.003338,0.002225,-0.000001,0.000001,-0.000000,0.000000,-0.293938,0.020892,0.000626,-0.000416,0.000000,-0.000000,0.000000,-0.000000,1.314398,-0.020401,-0.000608,0.000406,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.037036,-0.111810,0.003336,0.002225,0.000001,-0.000002,0.000001,-0.000001,-0.272836,0.020897,-0.000621,-0.000416,-0.000000,0.000000,-0.000000,0.000000,1.293795,-0.020400,0.000609,0.000406,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.069213,-0.098465,0.010000,0.002206,-0.000018,0.000017,-0.000017,0.000013,-0.252977,0.018406,-0.001868,-0.000413,0.000003,-0.000003,0.000003,-0.000003,1.274410,-0.017964,0.001825,0.000402,-0.000003,0.000003,-0.000003,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.155476,-0.071842,0.016708,0.002436,0.000283,-0.000130,0.000300,-0.000219,-0.236850,0.013432,-0.003123,-0.000456,-0.000053,0.000024,-0.000056,0.000041,1.258673,-0.013106,0.003048,0.000444,0.000052,-0.000024,0.000055,-0.000040,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.207939,-0.030364,0.024325,0.000616,-0.003521,0.000022,-0.004406,0.002896,-0.227041,0.005678,-0.004548,-0.000116,0.000658,-0.000004,0.000824,-0.000542,1.249103,-0.005539,0.004437,0.000112,-0.000642,0.000004,-0.000804,0.000528,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.218370,0.000000,0.000000,0.000000,0.009757,-0.010464,0.004812,-0.000877,-0.225090,0.000000,0.000000,0.000000,-0.000875,0.001001,-0.000473,0.000088,1.247200,0.000000,0.000000,0.000000,-0.002267,0.002452,-0.001132,0.000207,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.215142,0.009441,0.007667,-0.000060,-0.001068,0.000884,-0.000371,0.000066,-0.225350,-0.000721,-0.000497,0.000116,0.000102,-0.000089,0.000039,-0.000007,1.246460,-0.002150,-0.001716,0.000052,0.000251,-0.000209,0.000088,-0.000016,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.198584,0.022977,0.005735,-0.000610,0.000089,-0.000059,0.000023,-0.000004,-0.226407,-0.001223,0.000001,0.000157,-0.000012,0.000006,-0.000003,0.000000,1.242760,-0.005048,-0.001151,0.000180,-0.000021,0.000014,-0.000005,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.170431,0.032792,0.004117,-0.000519,0.000002,0.000004,-0.000001,0.000000,-0.227480,-0.000780,0.000430,0.000132,-0.000006,-0.000002,0.000000,-0.000000,1.236730,-0.006849,-0.000658,0.000159,-0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.134037,0.039489,0.002595,-0.000491,0.000009,0.000000,-0.000000,0.000000,-0.227706,0.000444,0.000775,0.000094,-0.000013,-0.000002,0.000001,-0.000000,1.229381,-0.007694,-0.000192,0.000149,-0.000005,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.092435,0.043241,0.001174,-0.000458,0.000006,-0.000001,0.000000,-0.000000,-0.226405,0.002222,0.000973,0.000036,-0.000016,-0.000001,0.000000,-0.000000,1.221639,-0.007653,0.000222,0.000126,-0.000007,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.048471,0.044238,-0.000169,-0.000440,0.000003,-0.000001,-0.000000,0.000000,-0.223190,0.004210,0.000980,-0.000033,-0.000018,-0.000000,-0.000000,0.000000,1.214327,-0.006860,0.000554,0.000093,-0.000010,-0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.004840,0.042586,-0.001482,-0.000437,-0.000000,-0.000000,-0.000000,0.000000,-0.218052,0.005995,0.000765,-0.000113,-0.000021,-0.000000,-0.000000,0.000000,1.208103,-0.005518,0.000764,0.000044,-0.000014,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.035826,0.038309,-0.002799,-0.000443,-0.000003,-0.000000,-0.000001,0.000000,-0.211426,0.007103,0.000301,-0.000194,-0.000017,0.000004,-0.000001,0.000000,1.203378,-0.003916,0.000808,-0.000015,-0.000013,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.070890,0.031367,-0.004150,-0.000456,0.000001,-0.000002,0.000004,-0.000004,-0.204231,0.007068,-0.000356,-0.000237,-0.000006,0.000000,0.000001,-0.000001,1.200243,-0.002389,0.000701,-0.000052,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.097651,0.021692,-0.005551,-0.000524,-0.000079,0.000035,-0.000082,0.000060,-0.197761,0.005624,-0.001103,-0.000273,-0.000027,0.000012,-0.000027,0.000020,1.198499,-0.001160,0.000522,-0.000064,-0.000000,0.000000,-0.000000,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.113203,0.008813,-0.007199,-0.000004,0.000988,-0.000000,0.001217,-0.000808,-0.193536,0.002524,-0.001964,-0.000124,0.000306,-0.000004,0.000393,-0.000254,1.197796,-0.000311,0.000320,-0.000082,-0.000020,-0.000003,-0.000013,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.116210,0.000000,0.000000,0.000000,0.005626,-0.006049,0.002785,-0.000508,-0.192660,0.000000,0.000000,0.000000,0.009313,-0.010014,0.004610,-0.000840,1.197700,0.000000,0.000000,0.000000,-0.005839,0.006280,-0.002891,0.000527,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.118064,0.005412,0.004372,-0.000064,-0.000619,0.000512,-0.000215,0.000038,-0.189591,0.008958,0.007237,-0.000106,-0.001024,0.000848,-0.000356,0.000063,1.195777,-0.005614,-0.004533,0.000069,0.000642,-0.000532,0.000224,-0.000040,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.127500,0.013026,0.003162,-0.000386,0.000050,-0.000034,0.000013,-0.000002,-0.173972,0.021559,0.005233,-0.000640,0.000082,-0.000057,0.000022,-0.000004,1.185993,-0.013499,-0.003269,0.000403,-0.000052,0.000036,-0.000014,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.143328,0.018282,0.002109,-0.000346,-0.000003,0.000002,-0.000001,0.000000,-0.147776,0.030256,0.003489,-0.000573,-0.000005,0.000003,-0.000001,0.000000,1.169601,-0.018921,-0.002169,0.000361,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.163371,0.021454,0.001062,-0.000350,-0.000000,-0.000000,-0.000000,0.000000,-0.114608,0.035503,0.001756,-0.000579,-0.000000,-0.000000,0.000000,-0.000000,1.148874,-0.022169,-0.001078,0.000364,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.185536,0.022525,0.000008,-0.000352,-0.000000,0.000000,-0.000000,0.000000,-0.077928,0.037276,0.000017,-0.000581,-0.000001,-0.000000,-0.000000,0.000000,1.125991,-0.023234,0.000012,0.000362,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.207717,0.021485,-0.001049,-0.000353,-0.000000,0.000000,-0.000000,0.000000,-0.041216,0.035565,-0.001729,-0.000584,-0.000001,0.000001,-0.000000,0.000000,1.103131,-0.022125,0.001096,0.000361,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.227800,0.018329,-0.002105,-0.000349,0.000003,-0.000003,0.000003,-0.000002,-0.007965,0.030355,-0.003479,-0.000579,0.000005,-0.000005,0.000005,-0.000004,1.082463,-0.018852,0.002175,0.000357,-0.000003,0.000003,-0.000003,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.243676,0.013071,-0.003168,-0.000390,-0.000050,0.000023,-0.000052,0.000038,0.018333,0.021656,-0.005245,-0.000647,-0.000083,0.000037,-0.000087,0.000064,1.066142,-0.013431,0.003261,0.000398,0.000051,-0.000023,0.000054,-0.000039,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.253148,0.005434,-0.004389,-0.000066,0.000622,-0.000002,0.000773,-0.000510,0.034028,0.009007,-0.007272,-0.000111,0.001031,-0.000004,0.001281,-0.000846,1.056411,-0.005580,0.004508,0.000066,-0.000638,0.000002,-0.000793,0.000523,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.255010,0.000000,0.000000,0.000000,0.005572,-0.005999,0.002763,-0.000504,0.037114,0.000000,0.000000,-0.000000,-0.004824,0.005190,-0.002390,0.000436,1.054500,0.000000,0.000000,0.000000,0.009180,-0.009868,0.004542,-0.000828,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.256843,0.005345,0.004308,-0.000076,-0.000614,0.000508,-0.000214,0.000038,0.035526,-0.004634,-0.003739,0.000061,0.000531,-0.000440,0.000185,-0.000033,1.057526,0.008835,0.007141,-0.000100,-0.001009,0.000835,-0.000351,0.000062,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.266139,0.012803,0.003072,-0.000394,0.000050,-0.000034,0.000013,-0.000002,0.027458,-0.011124,-0.002684,0.000336,-0.000043,0.000030,-0.000012,0.000002,1.072939,0.021286,0.005180,-0.000626,0.000081,-0.000056,0.000022,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.281645,0.017854,0.001995,-0.000353,-0.000002,0.000002,-0.000001,0.000000,0.013963,-0.015563,-0.001768,0.000300,0.000002,-0.000002,0.000001,-0.000000,1.098823,0.029916,0.003474,-0.000561,-0.000006,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.301140,0.020783,0.000936,-0.000351,0.000002,0.000000,-0.000000,0.000000,-0.003068,-0.018199,-0.000868,0.000299,-0.000001,0.000000,0.000000,-0.000000,1.131648,0.035168,0.001775,-0.000569,-0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.322510,0.021610,-0.000104,-0.000342,0.000003,0.000000,-0.000000,0.000000,-0.021837,-0.019042,0.000022,0.000295,-0.000001,0.000000,-0.000000,0.000000,1.168022,0.037008,0.000062,-0.000574,-0.000002,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.343677,0.020389,-0.001111,-0.000329,0.000003,0.000000,-0.000000,0.000000,-0.040563,-0.018116,0.000903,0.000293,-0.000000,-0.000000,0.000000,-0.000000,1.204516,0.035403,-0.001671,-0.000582,-0.000002,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.362629,0.017193,-0.002076,-0.000311,0.000007,-0.000003,0.000002,-0.000002,-0.057482,-0.015431,0.001780,0.000290,-0.000002,0.000003,-0.000002,0.000002,1.237665,0.030308,-0.003426,-0.000585,0.000003,-0.000005,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.377438,0.012120,-0.003004,-0.000336,-0.000043,0.000020,-0.000047,0.000035,-0.070843,-0.010997,0.002667,0.000326,0.000042,-0.000019,0.000044,-0.000032,1.263961,0.021690,-0.005221,-0.000660,-0.000084,0.000038,-0.000087,0.000064,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.386183,0.004991,-0.004050,-0.000037,0.000566,-0.000001,0.000701,-0.000464,-0.078811,-0.004571,0.003692,0.000055,-0.000523,0.000002,-0.000650,0.000429,1.279700,0.009044,-0.007293,-0.000123,0.001037,-0.000004,0.001291,-0.000851,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.387890,0.000000,0.000000,-0.000000,-0.014963,0.016089,-0.007406,0.001350,-0.080377,0.000000,0.000000,0.000000,0.004617,-0.004960,0.002283,-0.000416,1.282800,0.000000,0.000000,-0.000000,-0.006670,0.007182,-0.003308,0.000603,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.382960,-0.014395,-0.011629,0.000169,0.001646,-0.001362,0.000572,-0.000102,-0.078854,0.004448,0.003598,-0.000046,-0.000507,0.000420,-0.000176,0.000031,1.280607,-0.006395,-0.005152,0.000094,0.000735,-0.000609,0.000256,-0.000045,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.357859,-0.034650,-0.008414,0.001026,-0.000132,0.000092,-0.000036,0.000006,-0.071088,0.010734,0.002624,-0.000311,0.000041,-0.000028,0.000011,-0.000002,1.269491,-0.015303,-0.003662,0.000475,-0.000060,0.000041,-0.000016,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.315752,-0.048637,-0.005612,0.000922,0.000010,-0.000005,0.000002,-0.000000,-0.058019,0.015124,0.001778,-0.000279,-0.000004,0.000000,-0.000000,0.000000,1.250969,-0.021314,-0.002371,0.000419,-0.000000,-0.000004,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.262432,-0.057071,-0.002816,0.000936,0.000000,-0.000000,0.000000,-0.000000,-0.041399,0.017829,0.000920,-0.000292,-0.000002,0.000001,0.000000,-0.000000,1.227700,-0.024811,-0.001135,0.000403,-0.000004,0.000001,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.203481,-0.059894,-0.000008,0.000935,-0.000000,0.000000,-0.000000,0.000000,-0.022944,0.018785,0.000034,-0.000297,-0.000000,0.000000,-0.000000,0.000000,1.202154,-0.025885,0.000058,0.000395,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.144514,-0.057105,0.002797,0.000936,0.000000,-0.000001,0.000000,-0.000000,-0.004422,0.017960,-0.000859,-0.000298,-0.000000,0.000000,-0.000000,0.000000,1.176723,-0.024582,0.001244,0.000395,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.091141,-0.048706,0.005598,0.000926,-0.000008,0.000008,-0.000008,0.000006,0.012381,0.015349,-0.001751,-0.000295,0.000003,-0.000003,0.000002,-0.000002,1.153780,-0.020909,0.002428,0.000391,-0.000004,0.000003,-0.000003,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.048957,-0.034729,0.008419,0.001034,0.000133,-0.000060,0.000139,-0.000102,0.025684,0.010960,-0.002650,-0.000329,-0.000042,0.000019,-0.000044,0.000032,1.135689,-0.014878,0.003620,0.000438,0.000057,-0.000026,0.000059,-0.000044,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.023792,-0.014437,0.011660,0.000175,-0.001651,0.000006,-0.002053,0.001355,0.033630,0.004561,-0.003682,-0.000058,0.000522,-0.000002,0.000649,-0.000429,1.124915,-0.006176,0.004992,0.000070,-0.000706,0.000002,-0.000877,0.000579,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.018846,0.000000,0.000000,0.000000,0.022638,-0.024955,0.011613,-0.002132,0.035193,0.000000,0.000000,-0.000000,-0.025600,0.027900,-0.012920,0.002364,1.122800,0.000000,0.000000,0.000000,0.010375,-0.010930,0.004985,-0.000903,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.026011,0.020534,0.015706,-0.001352,-0.002558,0.002155,-0.000916,0.000163,0.026937,-0.023868,-0.018745,0.000958,0.002857,-0.002388,0.001010,-0.000180,1.126327,0.010437,0.008756,0.000285,-0.001116,0.000910,-0.000379,0.000067,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.059743,0.044083,0.007551,-0.002624,0.000205,-0.000136,0.000034,-0.000002,-0.013419,-0.054195,-0.011237,0.002409,-0.000229,0.000155,-0.000049,0.000006,1.145286,0.027084,0.007735,-0.000318,0.000090,-0.000065,0.000032,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.108855,0.051644,0.000022,-0.002546,-0.000028,-0.000046,0.000162,-0.000033,-0.076558,-0.069832,-0.004440,0.002276,0.000024,0.000024,-0.000097,0.000020,1.179837,0.041778,0.007005,-0.000212,-0.000000,0.000023,-0.000063,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.158030,0.044449,-0.006509,-0.001039,0.001010,-0.000227,-0.000071,0.000034,-0.148583,-0.072111,0.001735,0.001369,-0.000613,0.000138,0.000043,-0.000021,1.228381,0.054981,0.005930,-0.000784,-0.000375,0.000084,0.000027,-0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.195676,0.031026,-0.006199,0.000484,-0.000014,-0.000043,0.000035,-0.000009,-0.218043,-0.066181,0.003762,0.000445,0.000009,0.000026,-0.000021,0.000005,1.288231,0.063482,0.002305,-0.001349,0.000005,0.000016,-0.000013,0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.220956,0.019957,-0.004919,0.000396,-0.000005,0.000009,-0.000005,0.000001,-0.279999,-0.057250,0.005200,0.000498,0.000003,-0.000006,0.000003,-0.000001,1.352681,0.064090,-0.001680,-0.001318,0.000001,-0.000002,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.236390,0.011308,-0.003727,0.000399,0.000001,-0.000001,-0.000000,0.000000,-0.331550,-0.045357,0.006688,0.000489,-0.000007,0.000007,-0.000006,0.000005,1.413773,0.056779,-0.005627,-0.001307,0.000010,-0.000010,0.000010,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.244371,0.005053,-0.002531,0.000396,-0.000002,-0.000002,0.000004,0.000000,-0.369732,-0.030511,0.008190,0.000577,0.000106,-0.000046,0.000107,-0.000081,1.463620,0.041599,-0.009602,-0.001441,-0.000165,0.000076,-0.000175,0.000128,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.247289,0.001183,-0.001320,0.000444,0.000048,0.000016,0.000006,-0.000026,-0.391389,-0.012126,0.010015,-0.000132,-0.001334,-0.000005,-0.001625,0.001086,1.494039,0.017633,-0.014106,-0.000383,0.002049,-0.000014,0.002568,-0.001687,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.247640,0.000000,0.000000,0.000000,0.000432,-0.000471,0.000218,-0.000040,-0.395510,0.000000,0.000000,0.000000,0.005427,-0.005831,0.002683,-0.000489,1.500100,0.000000,0.000000,-0.000000,-0.004799,0.005161,-0.002376,0.000433,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.247779,0.000402,0.000315,-0.000017,-0.000048,0.000040,-0.000017,0.000003,-0.393719,0.005231,0.004233,-0.000053,-0.000596,0.000493,-0.000207,0.000037,1.498519,-0.004615,-0.003728,0.000055,0.000528,-0.000437,0.000184,-0.000033,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.248457,0.000910,0.000188,-0.000040,0.000004,-0.000003,0.000001,-0.000000,-0.384582,0.012633,0.003092,-0.000364,0.000048,-0.000033,0.000013,-0.000002,1.490473,-0.011105,-0.002693,0.000330,-0.000042,0.000029,-0.000011,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.249517,0.001174,0.000079,-0.000034,0.000001,0.000000,-0.000000,-0.000000,-0.369196,0.017810,0.002098,-0.000327,-0.000004,0.000002,-0.000001,0.000000,1.476983,-0.015578,-0.001793,0.000296,0.000003,-0.000002,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.250738,0.001237,-0.000013,-0.000027,0.000002,0.000000,0.000000,-0.000000,-0.349618,0.021014,0.001101,-0.000337,-0.000002,-0.000000,0.000000,0.000000,1.459910,-0.018269,-0.000897,0.000299,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.251938,0.001141,-0.000078,-0.000017,0.000002,-0.000000,0.000000,-0.000000,-0.327842,0.022197,0.000078,-0.000346,-0.000002,0.000000,-0.000000,0.000000,1.441042,-0.019166,0.000001,0.000299,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.252988,0.000945,-0.000114,-0.000008,0.000002,-0.000000,0.000000,-0.000000,-0.305916,0.021306,-0.000974,-0.000355,-0.000002,0.000001,-0.000000,0.000000,1.422176,-0.018267,0.000898,0.000299,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.253812,0.000699,-0.000130,-0.000003,0.000001,-0.000000,0.000000,-0.000000,-0.285941,0.018286,-0.002048,-0.000359,0.000002,-0.000003,0.000003,-0.000002,1.405106,-0.015574,0.001794,0.000296,-0.000003,0.000003,-0.000002,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.254379,0.000434,-0.000134,-0.000001,-0.000001,0.000000,-0.000001,0.000001,-0.270062,0.013108,-0.003146,-0.000403,-0.000051,0.000023,-0.000053,0.000039,1.391621,-0.011099,0.002693,0.000330,0.000042,-0.000019,0.000044,-0.000033,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.254677,0.000160,-0.000137,0.000008,0.000016,0.000000,0.000019,-0.000013,-0.260546,0.005472,-0.004410,-0.000078,0.000628,-0.000003,0.000782,-0.000516,1.383580,-0.004612,0.003726,0.000055,-0.000527,0.000002,-0.000656,0.000433,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.254730,0.000000,0.000000,0.000000,0.064803,-0.073303,0.034491,-0.006377,-0.258670,0.000000,0.000000,0.000000,0.008550,-0.008104,0.003503,-0.000611,1.382000,0.000000,0.000000,0.000000,-0.044359,0.049985,-0.023481,0.004337,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.274344,0.055003,0.039233,-0.007196,-0.007544,0.006494,-0.002838,0.000521,-0.255332,0.010421,0.009973,0.001836,-0.000808,0.000578,-0.000179,0.000020,1.368482,-0.038040,-0.027447,0.004582,0.005142,-0.004414,0.001924,-0.000352,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.358016,0.100792,0.005690,-0.010960,0.000590,-0.000547,0.000484,-0.000087,-0.233492,0.034596,0.014141,0.001493,0.000086,0.000086,-0.000347,0.000073,1.309876,-0.071612,-0.005528,0.007157,-0.000403,0.000368,-0.000316,0.000057,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.453978,0.081210,-0.023693,-0.007442,0.002063,-0.000560,0.000189,0.000010,-0.183362,0.066563,0.016325,-0.001691,-0.002139,0.000463,0.000205,-0.000081,1.239599,-0.062467,0.013659,0.004898,-0.001307,0.000351,-0.000110,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.505755,0.018157,-0.036188,-0.000648,0.002459,-0.000793,0.000291,-0.000016,-0.103717,0.088564,0.004425,-0.004350,0.000416,-0.000016,-0.000038,0.000019,1.194615,-0.024646,0.022197,0.000691,-0.001491,0.000484,-0.000178,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.489016,-0.048664,-0.027288,0.006511,0.002297,-0.000584,-0.000136,0.000090,-0.014697,0.085850,-0.006468,-0.002952,0.000422,-0.000142,0.000014,-0.000006,1.191681,0.017275,0.017697,-0.003650,-0.001395,0.000356,0.000081,-0.000053,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.421241,-0.077627,0.000038,0.010297,0.000498,-0.000377,0.000725,-0.000455,0.062021,0.065079,-0.014125,-0.002607,-0.000280,0.000115,-0.000281,0.000207,1.221992,0.038031,0.002031,-0.005917,-0.000266,0.000212,-0.000401,0.000248,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.354341,-0.045388,0.031463,0.007086,-0.006446,0.000273,-0.008784,0.005476,0.110129,0.028231,-0.022330,-0.000933,0.003340,-0.000030,0.004222,-0.002759,1.255930,0.023668,-0.016004,-0.004202,0.003459,-0.000162,0.004761,-0.002950,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.338020,0.000000,0.000000,0.000000,-0.019191,0.020968,-0.009720,0.001780,0.119870,0.000000,0.000000,0.000000,-0.047168,0.051534,-0.023890,0.004375,1.264500,0.000000,0.000000,0.000000,0.025902,-0.028299,0.013119,-0.002403,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.331856,-0.017787,-0.013892,0.000811,0.002148,-0.001799,0.000763,-0.000136,0.104721,-0.043718,-0.034144,0.001994,0.005280,-0.004422,0.001875,-0.000335,1.272819,0.024007,0.018750,-0.001095,-0.002899,0.002428,-0.001029,0.000184,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.301963,-0.039918,-0.007981,0.001899,-0.000175,0.000123,-0.000049,0.000009,0.031250,-0.098111,-0.019616,0.004666,-0.000429,0.000303,-0.000120,0.000021,1.313165,0.053877,0.010772,-0.002563,0.000236,-0.000167,0.000066,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.255871,-0.050499,-0.002650,0.001760,0.000012,-0.000008,0.000003,-0.000001,-0.082036,-0.124116,-0.006513,0.004325,0.000029,-0.000019,0.000008,-0.000002,1.375375,0.068157,0.003577,-0.002375,-0.000016,0.000011,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.204489,-0.050499,0.002650,0.001760,-0.000012,0.000011,-0.000011,0.000009,-0.208324,-0.124116,0.006513,0.004325,-0.000029,0.000028,-0.000028,0.000021,1.444725,0.068157,-0.003577,-0.002375,0.000016,-0.000015,0.000015,-0.000012,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.158396,-0.039918,0.007981,0.001899,0.000175,-0.000083,0.000191,-0.000136,-0.321610,-0.098111,0.019616,0.004666,0.000429,-0.000205,0.000469,-0.000335,1.506935,0.053877,-0.010772,-0.002563,-0.000236,0.000113,-0.000258,0.000184,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.128504,-0.017787,0.013892,0.000811,-0.002148,0.000029,-0.002741,0.001780,-0.395081,-0.043718,0.034144,0.001994,-0.005280,0.000071,-0.006736,0.004375,1.547281,0.024008,-0.018750,-0.001095,0.002899,-0.000039,0.003699,-0.002403,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.122340,0.000000,0.000000,0.000000,0.011833,-0.012613,0.005784,-0.001052,-0.410230,0.000000,0.000000,-0.000000,0.005073,-0.005395,0.002471,-0.000449,1.555600,0.000000,0.000000,0.000000,-0.016533,0.017519,-0.008012,0.001454,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.126292,0.011606,0.009535,0.000064,-0.001287,0.001061,-0.000443,0.000078,-0.408530,0.005002,0.004127,0.000051,-0.000550,0.000453,-0.000189,0.000033,1.550029,-0.016426,-0.013642,-0.000275,0.001786,-0.001466,0.000610,-0.000108,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.146906,0.028916,0.007616,-0.000591,0.000115,-0.000068,0.000024,-0.000004,-0.399602,0.012574,0.003376,-0.000231,0.000047,-0.000030,0.000011,-0.000002,1.520508,-0.041812,-0.011512,0.000655,-0.000151,0.000096,-0.000035,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.182915,0.042617,0.006141,-0.000458,0.000003,0.000003,-0.000001,0.000000,-0.383858,0.018724,0.002792,-0.000186,-0.000001,0.000001,-0.000001,0.000000,1.467755,-0.063166,-0.009901,0.000509,0.000005,-0.000004,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.231220,0.053545,0.004800,-0.000433,0.000008,0.000000,-0.000001,0.000000,-0.362528,0.023749,0.002234,-0.000185,0.000002,0.000000,-0.000000,0.000000,1.395199,-0.081436,-0.008369,0.000509,-0.000002,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.289141,0.061879,0.003548,-0.000404,0.000006,0.000000,-0.000000,0.000000,-0.336728,0.027670,0.001691,-0.000177,0.000002,0.000000,-0.000000,0.000000,1.305902,-0.096652,-0.006849,0.000505,-0.000001,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.354170,0.067788,0.002374,-0.000379,0.000006,0.000001,-0.000001,0.000000,-0.307541,0.030531,0.001175,-0.000166,0.000003,0.000001,-0.000001,0.000000,1.202905,-0.108838,-0.005337,0.000504,-0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.423960,0.071424,0.001275,-0.000353,0.000007,0.000000,-0.000000,0.000000,-0.275998,0.032396,0.000697,-0.000153,0.000004,0.000000,-0.000000,0.000000,1.089233,-0.118002,-0.003827,0.000504,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.496312,0.072942,0.000256,-0.000326,0.000007,0.000001,-0.000001,0.000000,-0.243054,0.033346,0.000261,-0.000138,0.000004,0.000000,-0.000000,-0.000000,0.967907,-0.124144,-0.002315,0.000505,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.569191,0.072506,-0.000677,-0.000296,0.000008,0.000001,-0.000001,0.000000,-0.209581,0.033468,-0.000132,-0.000124,0.000003,-0.000000,0.000000,-0.000000,0.841954,-0.127257,-0.000797,0.000507,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.640732,0.070295,-0.001519,-0.000265,0.000008,0.000001,-0.000001,0.000000,-0.176366,0.032844,-0.000489,-0.000115,0.000001,-0.000000,0.000000,-0.000000,0.714408,-0.127327,0.000728,0.000510,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.709251,0.066495,-0.002264,-0.000232,0.000008,0.000000,-0.000001,0.000000,-0.144125,0.031526,-0.000827,-0.000111,0.000001,-0.000000,0.000000,-0.000000,0.588319,-0.124339,0.002261,0.000512,0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.773260,0.061305,-0.002912,-0.000203,0.000006,-0.000000,-0.000000,0.000000,-0.113535,0.029542,-0.001156,-0.000109,0.000000,-0.000000,0.000000,-0.000000,0.466754,-0.118278,0.003801,0.000514,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.831456,0.054896,-0.003487,-0.000183,0.000004,-0.000000,-0.000000,0.000000,-0.085258,0.026905,-0.001481,-0.000108,0.000000,-0.000000,0.000000,-0.000000,0.352792,-0.109131,0.005346,0.000516,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.882685,0.047388,-0.004013,-0.000169,0.000003,-0.000000,-0.000000,0.000000,-0.059941,0.023620,-0.001805,-0.000108,-0.000000,-0.000000,-0.000000,-0.000000,0.249523,-0.096891,0.006894,0.000516,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.925893,0.038862,-0.004509,-0.000162,0.000001,0.000000,-0.000000,0.000000,-0.038234,0.019686,-0.002129,-0.000108,-0.000000,0.000000,-0.000000,0.000000,0.160042,-0.081554,0.008444,0.000517,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.960086,0.029366,-0.004984,-0.000153,0.000005,-0.000003,0.000003,-0.000003,-0.020785,0.015104,-0.002452,-0.000106,0.000002,-0.000002,0.000002,-0.000001,0.087448,-0.063117,0.009989,0.000508,-0.000009,0.000008,-0.000007,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.984317,0.018941,-0.005459,-0.000202,-0.000061,0.000025,-0.000060,0.000046,-0.008239,0.009881,-0.002781,-0.000133,-0.000033,0.000014,-0.000032,0.000025,0.034826,-0.041612,0.011559,0.000624,0.000139,-0.000059,0.000139,-0.000106,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.997548,0.007264,-0.006109,0.000217,0.000773,0.000008,0.000925,-0.000625,-0.001298,0.003837,-0.003206,0.000089,0.000413,0.000003,0.000498,-0.000335,0.005511,-0.016265,0.013547,-0.000320,-0.001762,-0.000012,-0.002130,0.001431,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.196700,0.000000,0.000000,0.000000,-0.003332,0.003536,-0.001618,0.000294,0.067056,0.000000,0.000000,0.000000,-0.003547,0.003765,-0.001723,0.000313,1.130300,0.000000,0.000000,0.000000,0.009439,-0.010018,0.004585,-0.000833,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.195580,-0.003299,-0.002732,-0.000045,0.000361,-0.000296,0.000123,-0.000022,0.065864,-0.003512,-0.002908,-0.000048,0.000385,-0.000315,0.000131,-0.000023,1.133473,0.009346,0.007739,0.000127,-0.001023,0.000838,-0.000350,0.000062,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.189671,-0.008345,-0.002265,0.000147,-0.000029,0.000020,-0.000008,0.000001,0.059574,-0.008882,-0.002410,0.000157,-0.000031,0.000021,-0.000008,0.000001,1.150212,0.023637,0.006414,-0.000418,0.000081,-0.000056,0.000021,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.179193,-0.012485,-0.001884,0.000124,0.000002,-0.000001,0.000000,-0.000000,0.048422,-0.013288,-0.002005,0.000132,0.000002,-0.000001,0.000000,-0.000000,1.179889,0.035362,0.005335,-0.000351,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.164949,-0.015879,-0.001509,0.000126,-0.000000,0.000000,-0.000000,0.000000,0.033262,-0.016898,-0.001605,0.000134,-0.000000,0.000000,-0.000000,0.000000,1.220233,0.044970,0.004270,-0.000356,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.147687,-0.018519,-0.001132,0.000126,0.000000,0.000000,-0.000000,0.000000,0.014892,-0.019706,-0.001203,0.000134,0.000000,0.000000,-0.000000,0.000000,1.269117,0.052443,0.003203,-0.000356,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.128161,-0.020407,-0.000755,0.000126,0.000000,0.000000,0.000000,-0.000000,-0.005883,-0.021712,-0.000802,0.000134,-0.000000,-0.000000,0.000000,-0.000000,1.324407,0.057780,0.002135,-0.000356,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.107124,-0.021541,-0.000379,0.000126,0.000000,0.000000,0.000000,0.000000,-0.028263,-0.022915,-0.000401,0.000134,-0.000000,0.000000,0.000000,-0.000000,1.383966,0.060983,0.001067,-0.000356,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.085330,-0.021922,-0.000002,0.000126,0.000000,0.000000,0.000000,0.000000,-0.051445,-0.023315,0.000000,0.000134,-0.000000,-0.000000,0.000000,-0.000000,1.445660,0.062050,-0.000000,-0.000356,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.063532,-0.021549,0.000375,0.000126,0.000000,0.000000,-0.000000,-0.000000,-0.074626,-0.022914,0.000401,0.000134,-0.000000,-0.000000,0.000000,-0.000000,1.507354,0.060981,-0.001068,-0.000356,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.042484,-0.020422,0.000752,0.000126,0.000000,0.000000,0.000000,0.000000,-0.097005,-0.021710,0.000803,0.000134,-0.000000,-0.000000,-0.000000,0.000000,1.566911,0.057778,-0.002135,-0.000356,0.000000,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.022941,-0.018540,0.001130,0.000126,0.000000,0.000000,-0.000000,0.000000,-0.117778,-0.019704,0.001204,0.000134,-0.000000,0.000000,-0.000000,0.000000,1.622198,0.052440,-0.003203,-0.000356,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.005656,-0.015903,0.001508,0.000126,0.000000,-0.000000,0.000000,-0.000000,-0.136144,-0.016895,0.001605,0.000134,0.000000,-0.000000,0.000000,-0.000000,1.671079,0.044966,-0.004271,-0.000356,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.991387,-0.012509,0.001885,0.000124,-0.000002,0.000002,-0.000002,0.000001,-0.151301,-0.013285,0.002005,0.000132,-0.000002,0.000002,-0.000002,0.000001,1.711418,0.035358,-0.005335,-0.000350,0.000005,-0.000005,0.000004,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.980888,-0.008365,0.002268,0.000148,0.000029,-0.000012,0.000029,-0.000022,-0.162450,-0.008880,0.002410,0.000157,0.000031,-0.000013,0.000031,-0.000023,1.741092,0.023634,-0.006414,-0.000418,-0.000081,0.000035,-0.000082,0.000062,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.974963,-0.003308,0.002739,-0.000044,-0.000362,-0.000002,-0.000440,0.000295,-0.168738,-0.003511,0.002907,-0.000048,-0.000384,-0.000002,-0.000467,0.000313,1.757828,0.009344,-0.007738,0.000127,0.001023,0.000005,0.001243,-0.000832,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.973840,0.000000,0.000000,0.000000,-0.013673,0.014761,-0.006807,0.001243,-0.169930,0.000000,0.000000,0.000000,0.004443,-0.004797,0.002212,-0.000404,1.761000,0.000000,0.000000,0.000000,-0.013244,0.014299,-0.006594,0.001204,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.969364,-0.013030,-0.010440,0.000263,0.001511,-0.001254,0.000528,-0.000094,-0.168475,0.004234,0.003393,-0.000085,-0.000491,0.000407,-0.000172,0.000031,1.756665,-0.012620,-0.010111,0.000256,0.001463,-0.001215,0.000512,-0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.946847,-0.030838,-0.007177,0.001044,-0.000121,0.000085,-0.000033,0.000006,-0.161158,0.010022,0.002333,-0.000339,0.000039,-0.000028,0.000011,-0.000002,1.734859,-0.029861,-0.006946,0.001012,-0.000118,0.000082,-0.000032,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.909813,-0.042278,-0.004299,0.000947,0.000008,-0.000005,0.000002,-0.000000,-0.149122,0.013741,0.001398,-0.000307,-0.000003,0.000001,-0.000001,0.000000,1.699001,-0.040931,-0.004159,0.000917,0.000008,-0.000004,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.864186,-0.048020,-0.001439,0.000956,-0.000000,0.000000,-0.000000,0.000000,-0.134292,0.015610,0.000469,-0.000310,-0.000000,-0.000000,0.000000,0.000000,1.654833,-0.046482,-0.001389,0.000925,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.815683,-0.048030,0.001429,0.000957,0.000001,-0.000001,0.000000,-0.000000,-0.118524,0.015617,-0.000463,-0.000311,-0.000000,0.000000,-0.000000,0.000000,1.607887,-0.046485,0.001386,0.000925,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.770038,-0.042304,0.004294,0.000948,-0.000008,0.000007,-0.000007,0.000006,-0.103681,0.013758,-0.001395,-0.000309,0.000003,-0.000002,0.000002,-0.000002,1.563714,-0.040938,0.004157,0.000917,-0.000008,0.000007,-0.000007,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.732975,-0.030868,0.007178,0.001047,0.000122,-0.000056,0.000129,-0.000094,-0.091627,0.010040,-0.002334,-0.000341,-0.000040,0.000018,-0.000042,0.000031,1.527849,-0.029869,0.006947,0.001013,0.000118,-0.000054,0.000125,-0.000091,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.710432,-0.013048,0.010452,0.000265,-0.001513,0.000009,-0.001893,0.001245,-0.084294,0.004244,-0.003400,-0.000087,0.000492,-0.000003,0.000616,-0.000405,1.506037,-0.012624,0.010113,0.000256,-0.001464,0.000009,-0.001832,0.001204,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.705950,0.000000,0.000000,0.000000,-0.029395,0.031611,-0.014552,0.002653,-0.082836,0.000000,0.000000,-0.000000,0.004202,-0.004519,0.002080,-0.000379,1.501700,0.000000,0.000000,-0.000000,0.033967,-0.036528,0.016816,-0.003066,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.696266,-0.028268,-0.022831,0.000341,0.003233,-0.002676,0.001125,-0.000200,-0.081452,0.004041,0.003264,-0.000049,-0.000462,0.000383,-0.000161,0.000029,1.512890,0.032665,0.026382,-0.000394,-0.003736,0.003093,-0.001300,0.000231,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.646990,-0.068005,-0.016490,0.002024,-0.000259,0.000180,-0.000070,0.000012,-0.074407,0.009722,0.002357,-0.000289,0.000037,-0.000026,0.000010,-0.000002,1.569831,0.078582,0.019054,-0.002339,0.000300,-0.000208,0.000081,-0.000014,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.564382,-0.095385,-0.010969,0.001812,0.000017,-0.000010,0.000003,-0.000001,-0.062598,0.013636,0.001568,-0.000259,-0.000002,0.000001,-0.000000,0.000000,1.665286,0.110220,0.012675,-0.002094,-0.000019,0.000011,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.459850,-0.111851,-0.005489,0.001831,-0.000001,0.000000,-0.000000,0.000000,-0.047654,0.015990,0.000785,-0.000262,0.000000,-0.000000,0.000000,-0.000000,1.786076,0.129247,0.006343,-0.002115,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.344341,-0.117339,-0.000000,0.001829,0.000000,0.000000,-0.000000,0.000000,-0.031140,0.016775,0.000000,-0.000262,-0.000000,-0.000000,0.000000,-0.000000,1.919551,0.135589,-0.000000,-0.002114,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.228830,-0.111851,0.005489,0.001831,0.000001,-0.000001,0.000001,-0.000001,-0.014626,0.015991,-0.000785,-0.000262,-0.000000,0.000000,-0.000000,0.000000,2.053025,0.129246,-0.006343,-0.002115,-0.000001,0.000002,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.124298,-0.095386,0.010969,0.001812,-0.000017,0.000015,-0.000015,0.000012,0.000319,0.013637,-0.001568,-0.000259,0.000002,-0.000002,0.000002,-0.000002,2.173814,0.110220,-0.012675,-0.002094,0.000019,-0.000018,0.000017,-0.000014,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.041689,-0.068006,0.016490,0.002024,0.000259,-0.000117,0.000272,-0.000200,0.012130,0.009723,-0.002358,-0.000289,-0.000037,0.000017,-0.000039,0.000029,2.269270,0.078581,-0.019054,-0.002339,-0.000300,0.000136,-0.000314,0.000231,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.007588,-0.028269,0.022832,0.000341,-0.003233,0.000012,-0.004019,0.002653,0.019175,0.004042,-0.003264,-0.000049,0.000462,-0.000002,0.000575,-0.000379,2.326210,0.032665,-0.026382,-0.000394,0.003736,-0.000014,0.004644,-0.003066,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.017272,0.000000,0.000000,0.000000,-0.002217,0.002400,-0.001108,0.000202,0.020560,0.000000,0.000000,-0.000000,-0.024810,0.026925,-0.012445,0.002275,2.337400,0.000000,0.000000,0.000000,-0.036909,0.040054,-0.018513,0.003384,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.017995,-0.002101,-0.001674,0.000054,0.000246,-0.000204,0.000086,-0.000015,0.012505,-0.023361,-0.018515,0.000726,0.002757,-0.002298,0.000970,-0.000173,2.325415,-0.034759,-0.027552,0.001076,0.004101,-0.003418,0.001444,-0.000257,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.021603,-0.004916,-0.001110,0.000182,-0.000019,0.000014,-0.000005,0.000001,-0.027388,-0.054060,-0.011844,0.002138,-0.000223,0.000156,-0.000061,0.000011,2.266051,-0.080457,-0.017640,0.003177,-0.000331,0.000232,-0.000091,0.000016,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.027456,-0.006621,-0.000598,0.000172,0.000003,-0.000001,0.000000,-0.000000,-0.091272,-0.071740,-0.005902,0.001957,0.000014,-0.000008,0.000003,-0.000001,2.170957,-0.106803,-0.008805,0.002911,0.000022,-0.000012,0.000005,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.034500,-0.007289,-0.000065,0.000183,0.000003,-0.000000,0.000000,-0.000000,-0.166949,-0.077645,0.000004,0.001972,-0.000000,-0.000001,0.000001,-0.000001,2.058274,-0.115631,-0.000012,0.002938,0.000001,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.041668,-0.006857,0.000503,0.000195,0.000002,0.000001,-0.000001,0.000001,-0.242619,-0.071726,0.005908,0.001955,-0.000014,0.000014,-0.000014,0.000011,1.945567,-0.106848,0.008787,0.002916,-0.000021,0.000021,-0.000021,0.000016,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.047823,-0.005253,0.001112,0.000222,0.000024,-0.000011,0.000024,-0.000017,-0.306484,-0.054039,0.011844,0.002135,0.000223,-0.000104,0.000239,-0.000173,1.850417,-0.080520,0.017640,0.003185,0.000332,-0.000155,0.000357,-0.000257,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.051722,-0.002298,0.001810,0.000085,-0.000274,0.000003,-0.000347,0.000226,-0.346359,-0.023349,0.018506,0.000724,-0.002755,0.000026,-0.003477,0.002273,1.790998,-0.034796,0.027577,0.001082,-0.004106,0.000038,-0.005182,0.003389,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.052516,0.000000,0.000000,0.000000,-0.001278,0.001374,-0.000633,0.000115,-0.354410,0.000000,0.000000,0.000000,0.019321,-0.020777,0.009565,-0.001744,1.779000,0.000000,0.000000,-0.000000,-0.025253,0.027156,-0.012501,0.002279,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.052937,-0.001229,-0.000993,0.000015,0.000141,-0.000116,0.000049,-0.000009,-0.348045,0.018580,0.015006,-0.000224,-0.002125,0.001759,-0.000739,0.000131,1.770681,-0.024285,-0.019614,0.000293,0.002778,-0.002299,0.000966,-0.000171,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.055080,-0.002959,-0.000718,0.000088,-0.000011,0.000008,-0.000003,0.000001,-0.315657,0.044698,0.010838,-0.001330,0.000171,-0.000118,0.000046,-0.000008,1.728349,-0.058421,-0.014166,0.001739,-0.000223,0.000155,-0.000060,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.058675,-0.004152,-0.000479,0.000079,0.000001,-0.000000,0.000000,-0.000000,-0.261361,0.062695,0.007210,-0.001191,-0.000011,0.000006,-0.000002,0.000000,1.657383,-0.081943,-0.009423,0.001557,0.000014,-0.000008,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.063227,-0.004872,-0.000241,0.000080,0.000000,0.000000,0.000000,-0.000000,-0.192654,0.073518,0.003608,-0.001203,0.000001,-0.000000,0.000000,-0.000000,1.567583,-0.096088,-0.004716,0.001573,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.068260,-0.005115,-0.000002,0.000080,0.000000,-0.000000,0.000000,-0.000000,-0.116731,0.077127,0.000001,-0.001202,-0.000000,-0.000000,0.000000,-0.000000,1.468351,-0.100803,-0.000000,0.001571,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.073296,-0.004879,0.000238,0.000080,0.000000,-0.000000,0.000000,-0.000000,-0.040806,0.073520,-0.003607,-0.001203,-0.000001,0.000001,-0.000000,0.000000,1.369120,-0.096089,0.004715,0.001573,0.000001,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.077857,-0.004162,0.000478,0.000079,-0.000001,0.000001,-0.000001,0.000001,0.027904,0.062698,-0.007210,-0.001191,0.000011,-0.000010,0.000010,-0.000008,1.279319,-0.081943,0.009423,0.001557,-0.000014,0.000013,-0.000013,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.081463,-0.002969,0.000719,0.000089,0.000011,-0.000005,0.000012,-0.000009,0.082204,0.044701,-0.010839,-0.001330,-0.000171,0.000077,-0.000179,0.000131,1.208352,-0.058422,0.014166,0.001739,0.000223,-0.000101,0.000234,-0.000171,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.083614,-0.001234,0.000997,0.000015,-0.000141,0.000001,-0.000176,0.000116,0.114595,0.018582,-0.015008,-0.000224,0.002125,-0.000008,0.002642,-0.001744,1.166019,-0.024285,0.019614,0.000293,-0.002778,0.000010,-0.003453,0.002279,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.084037,0.000000,0.000000,0.000000,0.010617,-0.011381,0.005232,-0.000953,0.120960,0.000000,0.000000,0.000000,-0.024369,0.026122,-0.012008,0.002187,1.157700,0.000000,0.000000,0.000000,0.010878,-0.011660,0.005360,-0.000976,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.080522,0.010282,0.008356,-0.000059,-0.001164,0.000961,-0.000403,0.000071,0.112892,-0.023605,-0.019186,0.000133,0.002671,-0.002205,0.000925,-0.000164,1.161302,0.010538,0.008566,-0.000059,-0.001192,0.000984,-0.000413,0.000073,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.062478,0.025048,0.006258,-0.000668,0.000093,-0.000064,0.000025,-0.000004,0.071461,-0.057517,-0.014379,0.001531,-0.000214,0.000148,-0.000057,0.000010,1.179799,0.025681,0.006422,-0.000683,0.000095,-0.000066,0.000026,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.031790,0.035731,0.004453,-0.000591,-0.000006,0.000003,-0.000001,0.000000,0.000982,-0.082074,-0.010243,0.001355,0.000013,-0.000008,0.000003,-0.000000,1.211271,0.036653,0.004578,-0.000604,-0.000006,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.007799,0.042853,0.002667,-0.000596,0.000001,-0.000000,0.000000,0.000000,-0.089973,-0.098468,-0.006144,0.001369,-0.000001,0.000000,-0.000000,0.000000,1.251893,0.043982,0.002749,-0.000611,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.052723,0.046398,0.000880,-0.000595,0.000000,0.000000,-0.000000,0.000000,-0.193217,-0.106652,-0.002041,0.001367,-0.000000,-0.000000,0.000000,-0.000000,1.298014,0.047648,0.000917,-0.000611,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.099406,0.046374,-0.000903,-0.000594,0.000000,-0.000000,0.000000,-0.000000,-0.300543,-0.106634,0.002059,0.001366,-0.000000,0.000000,-0.000000,0.000000,1.345968,0.047649,-0.000915,-0.000611,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.144283,0.042786,-0.002684,-0.000594,-0.000000,0.000001,-0.000000,0.000000,-0.403752,-0.098418,0.006157,0.001367,0.000001,-0.000001,0.000001,-0.000000,1.392091,0.043986,-0.002748,-0.000611,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.183792,0.035639,-0.004460,-0.000586,0.000006,-0.000005,0.000005,-0.000004,-0.494647,-0.082008,0.010247,0.001351,-0.000014,0.000013,-0.000012,0.000010,1.432718,0.036658,-0.004577,-0.000605,0.000006,-0.000006,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.214387,0.024959,-0.006248,-0.000661,-0.000093,0.000041,-0.000096,0.000071,-0.565060,-0.057455,0.014371,0.001526,0.000213,-0.000095,0.000222,-0.000164,1.464195,0.025687,-0.006423,-0.000683,-0.000095,0.000043,-0.000099,0.000073,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.232361,0.010238,-0.008323,-0.000055,0.001158,-0.000002,0.001431,-0.000948,-0.606442,-0.023575,0.019163,0.000130,-0.002667,0.000004,-0.003297,0.002184,1.482697,0.010541,-0.008568,-0.000059,0.001193,-0.000002,0.001475,-0.000977,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.235860,0.000000,0.000000,0.000000,-0.014315,0.015456,-0.007128,0.001301,-0.614500,0.000000,0.000000,0.000000,0.031736,-0.034266,0.015802,-0.002884,1.486300,0.000000,0.000000,-0.000000,-0.015541,0.016780,-0.007738,0.001412,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.231174,-0.013640,-0.010928,0.000277,0.001582,-0.001313,0.000553,-0.000098,-0.604111,0.030241,0.024226,-0.000614,-0.003506,0.002911,-0.001226,0.000218,1.481213,-0.014808,-0.011863,0.000301,0.001717,-0.001426,0.000600,-0.000107,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.207606,-0.032274,-0.007507,0.001094,-0.000127,0.000089,-0.000035,0.000006,-0.551862,0.071551,0.016641,-0.002426,0.000282,-0.000197,0.000077,-0.000013,1.455627,-0.035037,-0.008149,0.001188,-0.000138,0.000096,-0.000038,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.168852,-0.044237,-0.004493,0.000991,0.000008,-0.000005,0.000002,-0.000000,-0.465946,0.098069,0.009961,-0.002197,-0.000018,0.000011,-0.000004,0.000001,1.413555,-0.048022,-0.004878,0.001076,0.000009,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.121117,-0.050234,-0.001500,0.001000,-0.000000,0.000000,-0.000000,0.000000,-0.360124,0.111362,0.003324,-0.002216,0.000001,-0.000001,0.000000,-0.000000,1.361736,-0.054532,-0.001628,0.001085,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.070384,-0.050234,0.001499,0.001000,0.000000,-0.000001,0.000000,-0.000000,-0.247653,0.111363,-0.003323,-0.002217,-0.000001,0.000002,-0.000001,0.000001,1.306662,-0.054531,0.001628,0.001085,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.022648,-0.044239,0.004493,0.000991,-0.000008,0.000008,-0.000008,0.000006,-0.141829,0.098071,-0.009961,-0.002197,0.000018,-0.000017,0.000017,-0.000013,1.254844,-0.048022,0.004878,0.001076,-0.000009,0.000008,-0.000008,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.016109,-0.032277,0.007507,0.001094,0.000127,-0.000058,0.000135,-0.000098,-0.055911,0.071553,-0.016642,-0.002426,-0.000282,0.000130,-0.000299,0.000218,1.212773,-0.035037,0.008149,0.001188,0.000138,-0.000063,0.000146,-0.000107,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.039680,-0.013642,0.010929,0.000277,-0.001582,0.000010,-0.001979,0.001301,-0.003659,0.030242,-0.024227,-0.000614,0.003506,-0.000022,0.004388,-0.002884,1.187187,-0.014808,0.011863,0.000301,-0.001717,0.000011,-0.002149,0.001412,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/6/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.044366,0.000000,0.000000,-0.000000,0.022992,-0.024826,0.011450,-0.002090,0.006730,0.000000,0.000000,0.000000,-0.017883,0.019313,-0.008908,0.001626,1.182100,0.000000,0.000000,-0.000000,0.009131,-0.009858,0.004546,-0.000830,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.036840,0.021906,0.017548,-0.000447,-0.002540,0.002109,-0.000888,0.000158,0.000878,-0.017031,-0.013637,0.000354,0.001976,-0.001641,0.000691,-0.000123,1.185089,0.008701,0.006971,-0.000176,-0.001009,0.000837,-0.000353,0.000063,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.001005,0.051820,0.012046,-0.001759,0.000205,-0.000143,0.000056,-0.000010,-0.028533,-0.040257,-0.009340,0.001374,-0.000160,0.000111,-0.000043,0.000008,1.200125,0.020592,0.004791,-0.000697,0.000081,-0.000057,0.000022,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.063220,0.071007,0.007203,-0.001591,-0.000013,0.000008,-0.000003,0.000001,-0.076842,-0.055110,-0.005562,0.001241,0.000009,-0.000006,0.000002,-0.000000,1.224853,0.028230,0.002871,-0.000632,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.139831,0.080614,0.002399,-0.001604,0.000001,-0.000000,0.000000,-0.000000,-0.136269,-0.062495,-0.001822,0.001246,-0.000002,0.000000,-0.000000,0.000000,1.255319,0.032065,0.000962,-0.000638,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.221241,0.080604,-0.002409,-0.001603,-0.000001,0.000001,-0.000001,0.000000,-0.199342,-0.062408,0.001906,0.001240,-0.000001,-0.000001,0.000001,-0.000000,1.287707,0.032074,-0.000953,-0.000638,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.297833,0.070979,-0.007210,-0.001589,0.000013,-0.000012,0.000012,-0.000010,-0.258605,-0.054884,0.005611,0.001223,-0.000011,0.000010,-0.000009,0.000007,1.318190,0.028254,-0.002865,-0.000634,0.000005,-0.000005,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.360015,0.051785,-0.012044,-0.001756,-0.000204,0.000094,-0.000216,0.000158,-0.306658,-0.039993,0.009325,0.001347,0.000157,-0.000072,0.000167,-0.000122,1.342946,0.020620,-0.004793,-0.000700,-0.000081,0.000037,-0.000086,0.000063,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.397831,0.021887,-0.017534,-0.000444,0.002538,-0.000016,0.003176,-0.002088,-0.335850,-0.016886,0.013535,0.000334,-0.001956,0.000012,-0.002447,0.001609,1.358005,0.008717,-0.006983,-0.000178,0.001011,-0.000006,0.001265,-0.000832,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,1.500000,0.000000,0.000000,0.000000,0.025888,-0.027753,0.012759,-0.002324,0.000000,0.000000,0.000000,0.000000,-0.007078,0.007587,-0.003488,0.000635,1.500000,0.000000,0.000000,0.000000,-0.026526,0.028433,-0.013070,0.002381,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.508569,0.025068,0.020370,-0.000147,-0.002837,0.002344,-0.000983,0.000174,-0.002344,-0.006857,-0.005573,0.000038,0.000776,-0.000641,0.000269,-0.000048,1.491217,-0.025696,-0.020887,0.000143,0.002907,-0.002400,0.001007,-0.000178,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.552557,0.061054,0.015249,-0.001629,0.000228,-0.000157,0.000061,-0.000011,-0.014379,-0.016709,-0.004178,0.000444,-0.000062,0.000043,-0.000017,0.000003,1.446113,-0.062621,-0.015661,0.001664,-0.000233,0.000161,-0.000062,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.627352,0.087084,0.010853,-0.001438,-0.000013,0.000008,-0.000003,0.000001,-0.034856,-0.023847,-0.002978,0.000393,0.000004,-0.000002,0.000001,-0.000000,1.369372,-0.089374,-0.011163,0.001474,0.000015,-0.000008,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.723842,0.104448,0.006506,-0.001451,0.000001,-0.000000,0.000000,-0.000000,-0.061284,-0.028614,-0.001788,0.000397,-0.000000,0.000000,-0.000000,0.000000,1.270318,-0.107246,-0.006702,0.001490,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.833346,0.113110,0.002158,-0.001448,0.000000,-0.000000,-0.000000,0.000000,-0.091289,-0.030998,-0.000596,0.000397,-0.000000,0.000000,0.000000,-0.000000,1.157860,-0.116181,-0.002234,0.001489,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.947166,0.113082,-0.002186,-0.001448,0.000000,-0.000000,0.000000,-0.000000,-0.122487,-0.031000,0.000595,0.000397,0.000000,0.000000,-0.000000,0.000000,1.040935,-0.116180,0.002234,0.001489,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.056614,0.104366,-0.006530,-0.001449,-0.000001,0.000001,-0.000001,0.000000,-0.152495,-0.028619,0.001787,0.000398,0.000000,-0.000000,0.000000,-0.000000,0.928478,-0.107245,0.006702,0.001490,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.153001,0.086963,-0.010866,-0.001433,0.000014,-0.000013,0.000013,-0.000011,-0.178930,-0.023854,0.002977,0.000394,-0.000004,0.000004,-0.000004,0.000003,0.829426,-0.089373,0.011163,0.001474,-0.000015,0.000014,-0.000013,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.227669,0.060928,-0.015238,-0.001618,-0.000227,0.000101,-0.000235,0.000174,-0.199414,-0.016716,0.004179,0.000445,0.000062,-0.000028,0.000065,-0.000048,0.752686,-0.062620,0.015660,0.001664,0.000233,-0.000104,0.000242,-0.000178,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.271555,0.025002,-0.020322,-0.000140,0.002828,-0.000005,0.003498,-0.002317,-0.211455,-0.006861,0.005576,0.000039,-0.000776,0.000001,-0.000960,0.000636,0.707582,-0.025695,0.020886,0.000143,-0.002907,0.000005,-0.003594,0.002381,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/10.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.062437,0.000000,0.000000,0.000000,-0.025299,0.027317,-0.012598,0.002299,-1.072600,0.000000,0.000000,0.000000,0.003419,-0.003695,0.001705,-0.000311,1.158000,0.000000,0.000000,0.000000,-0.009136,0.009864,-0.004549,0.000830,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.070718,-0.024106,-0.019311,0.000490,0.002795,-0.002321,0.000978,-0.000174,-1.071482,0.003253,0.002602,-0.000070,-0.000377,0.000315,-0.000133,0.000024,1.155009,-0.008706,-0.006975,0.000176,0.001009,-0.000838,0.000353,-0.000063,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.112366,-0.057030,-0.013261,0.001934,-0.000225,0.000157,-0.000061,0.000011,-1.065869,0.007682,0.001783,-0.000259,0.000032,-0.000022,0.000008,-0.000001,1.139967,-0.020600,-0.004792,0.000698,-0.000081,0.000057,-0.000022,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.180842,-0.078159,-0.007935,0.001751,0.000014,-0.000008,0.000003,-0.000001,-1.056646,0.010529,0.001074,-0.000233,-0.000002,0.000001,-0.000000,0.000000,1.115230,-0.028237,-0.002869,0.000632,0.000005,-0.000003,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.265177,-0.088747,-0.002646,0.001766,-0.000001,0.000000,-0.000000,0.000000,-1.045278,0.011971,0.000367,-0.000237,-0.000000,-0.000000,-0.000000,-0.000000,1.084760,-0.032067,-0.000958,0.000638,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.354804,-0.088742,0.002651,0.001766,0.000001,-0.000001,0.000001,-0.000001,-1.033177,0.011994,-0.000346,-0.000239,-0.000001,0.000000,-0.000000,0.000000,1.052372,-0.032070,0.000955,0.000638,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.439131,-0.078147,0.007938,0.001750,-0.000014,0.000014,-0.000014,0.000011,-1.021768,0.010585,-0.001063,-0.000239,0.000002,-0.000002,0.000002,-0.000001,1.021896,-0.028246,0.002866,0.000633,-0.000005,0.000005,-0.000005,0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.507594,-0.057017,0.013260,0.001933,0.000225,-0.000103,0.000238,-0.000174,-1.012485,0.007741,-0.001791,-0.000265,-0.000031,0.000014,-0.000033,0.000024,0.997148,-0.020613,0.004791,0.000700,0.000082,-0.000037,0.000086,-0.000063,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.549231,-0.024099,0.019306,0.000490,-0.002794,0.000017,-0.003497,0.002299,-1.006827,0.003279,-0.002624,-0.000071,0.000381,-0.000002,0.000477,-0.000314,0.982094,-0.008714,0.006980,0.000178,-0.001011,0.000006,-0.001265,0.000831,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/11.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.557510,0.000000,0.000000,-0.000000,0.014632,-0.015642,0.007182,-0.001307,-1.005700,0.000000,0.000000,0.000000,0.004810,-0.005144,0.002362,-0.000430,0.979100,0.000000,0.000000,0.000000,0.018919,-0.020225,0.009286,-0.001690,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.552645,0.014259,0.011650,-0.000004,-0.001599,0.001317,-0.000552,0.000098,-1.004102,0.004683,0.003823,-0.000005,-0.000526,0.000434,-0.000182,0.000032,0.985390,0.018437,0.015064,-0.000005,-0.002067,0.001704,-0.000714,0.000126,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.527476,0.035112,0.008992,-0.000845,0.000128,-0.000088,0.000034,-0.000006,-0.995844,0.011512,0.002939,-0.000279,0.000043,-0.000029,0.000011,-0.000002,1.017935,0.045401,0.011628,-0.001092,0.000165,-0.000114,0.000044,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.484149,0.050796,0.006731,-0.000740,-0.000008,0.000005,-0.000002,0.000000,-0.981648,0.016633,0.002194,-0.000243,-0.000002,0.000001,-0.000001,0.000000,1.073959,0.065681,0.008703,-0.000957,-0.000010,0.000006,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.427366,0.062021,0.004490,-0.000749,0.000000,-0.000000,0.000000,-0.000000,-0.963066,0.020287,0.001459,-0.000245,0.000000,-0.000000,-0.000000,0.000000,1.147380,0.080195,0.005806,-0.000968,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.361604,0.068755,0.002245,-0.000748,-0.000000,-0.000000,0.000000,-0.000000,-0.941564,0.022472,0.000726,-0.000244,0.000000,-0.000000,0.000000,-0.000000,1.232412,0.088903,0.002903,-0.000968,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.291352,0.071000,0.000000,-0.000748,-0.000000,0.000000,-0.000000,-0.000000,-0.918610,0.023192,-0.000006,-0.000244,0.000000,-0.000000,0.000000,-0.000000,1.323250,0.091805,0.000000,-0.000968,-0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.221100,0.068755,-0.002245,-0.000748,0.000000,-0.000000,0.000000,-0.000000,-0.895667,0.022450,-0.000737,-0.000244,0.000000,-0.000000,0.000000,-0.000000,1.414088,0.088903,-0.002903,-0.000968,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.155338,0.062021,-0.004490,-0.000749,-0.000000,0.000001,-0.000000,0.000000,-0.874198,0.020244,-0.001468,-0.000244,-0.000000,0.000000,-0.000000,0.000000,1.499120,0.080195,-0.005806,-0.000968,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.098556,0.050796,-0.006731,-0.000740,0.000008,-0.000007,0.000007,-0.000006,-0.855666,0.016576,-0.002198,-0.000241,0.000003,-0.000002,0.000002,-0.000002,1.572541,0.065681,-0.008703,-0.000957,0.000010,-0.000010,0.000009,-0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.055228,0.035112,-0.008992,-0.000845,-0.000128,0.000057,-0.000132,0.000098,-0.841528,0.011456,-0.002935,-0.000275,-0.000042,0.000018,-0.000043,0.000032,1.628565,0.045401,-0.011628,-0.001092,-0.000165,0.000073,-0.000170,0.000126,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.030059,0.014259,-0.011650,-0.000004,0.001599,0.000000,0.001968,-0.001307,-0.833317,0.004652,-0.003801,-0.000001,0.000522,0.000000,0.000642,-0.000426,1.661110,0.018437,-0.015064,-0.000005,0.002067,0.000000,0.002544,-0.001690,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/12.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.025194,0.000000,0.000000,0.000000,-0.003824,0.004112,-0.001893,0.000345,-0.831730,0.000000,0.000000,0.000000,0.011425,-0.012291,0.005660,-0.001032,1.667400,0.000000,0.000000,0.000000,-0.020229,0.021754,-0.010015,0.001826,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.026454,-0.003677,-0.002970,0.000044,0.000421,-0.000348,0.000146,-0.000026,-0.827969,0.010975,0.008856,-0.000142,-0.001257,0.001041,-0.000438,0.000078,1.660736,-0.019454,-0.015712,0.000235,0.002225,-0.001842,0.000774,-0.000137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.032863,-0.008845,-0.002145,0.000263,-0.000034,0.000023,-0.000009,0.000002,-0.808856,0.026358,0.006369,-0.000791,0.000103,-0.000070,0.000027,-0.000005,1.626825,-0.046799,-0.011348,0.001393,-0.000179,0.000124,-0.000048,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.043608,-0.012407,-0.001427,0.000236,0.000002,-0.000001,0.000000,-0.000000,-0.776863,0.036916,0.004221,-0.000703,-0.000006,0.000004,-0.000001,0.000000,1.569977,-0.065642,-0.007548,0.001247,0.000011,-0.000007,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.057204,-0.014548,-0.000714,0.000238,-0.000000,0.000000,-0.000000,0.000000,-0.736432,0.043240,0.002102,-0.000707,0.000001,-0.000000,0.000000,-0.000000,1.498041,-0.076973,-0.003777,0.001260,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.072228,-0.015262,0.000000,0.000238,-0.000000,0.000000,-0.000000,0.000000,-0.691796,0.045326,-0.000016,-0.000705,0.000000,-0.000000,0.000000,-0.000000,1.418550,-0.080750,0.000000,0.001259,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.087252,-0.014548,0.000714,0.000238,0.000000,-0.000000,0.000000,-0.000000,-0.647191,0.043180,-0.002130,-0.000705,-0.000000,0.000001,-0.000000,0.000000,1.339059,-0.076973,0.003777,0.001260,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.100848,-0.012406,0.001427,0.000236,-0.000002,0.000002,-0.000002,0.000002,-0.606845,0.036808,-0.004239,-0.000698,0.000006,-0.000006,0.000006,-0.000005,1.267123,-0.065641,0.007548,0.001247,-0.000011,0.000011,-0.000010,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.111592,-0.008845,0.002145,0.000263,0.000034,-0.000015,0.000035,-0.000026,-0.574972,0.026234,-0.006365,-0.000779,-0.000100,0.000045,-0.000105,0.000077,1.210275,-0.046799,0.011348,0.001393,0.000179,-0.000081,0.000187,-0.000137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.118001,-0.003677,0.002969,0.000044,-0.000421,0.000002,-0.000523,0.000345,-0.555965,0.010903,-0.008807,-0.000130,0.001247,-0.000005,0.001550,-0.001023,1.176364,-0.019454,0.015712,0.000235,-0.002225,0.000008,-0.002766,0.001826,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/13.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.119260,0.000000,0.000000,0.000000,0.011524,-0.012392,0.005705,-0.001040,-0.552230,0.000000,0.000000,0.000000,-0.007812,0.008399,-0.003866,0.000705,1.169700,0.000000,0.000000,0.000000,0.008385,-0.009017,0.004151,-0.000757,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.115464,0.011082,0.008951,-0.000134,-0.001268,0.001049,-0.000441,0.000078,-0.554804,-0.007516,-0.006073,0.000087,0.000859,-0.000711,0.000299,-0.000053,1.172462,0.008064,0.006513,-0.000097,-0.000922,0.000763,-0.000321,0.000057,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.096146,0.026660,0.006465,-0.000793,0.000102,-0.000071,0.000027,-0.000005,-0.567911,-0.018096,-0.004397,0.000535,-0.000069,0.000048,-0.000019,0.000003,1.186518,0.019398,0.004704,-0.000577,0.000074,-0.000051,0.000020,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.063761,0.037394,0.004300,-0.000711,-0.000007,0.000004,-0.000001,0.000000,-0.589906,-0.025411,-0.002939,0.000479,0.000005,-0.000003,0.000001,-0.000000,1.210082,0.027209,0.003129,-0.000517,-0.000005,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.022782,0.043849,0.002152,-0.000718,0.000000,-0.000000,0.000000,-0.000000,-0.617775,-0.029844,-0.001491,0.000484,0.000000,0.000000,-0.000000,0.000000,1.239900,0.031906,0.001566,-0.000522,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.022502,0.046001,0.000000,-0.000717,-0.000000,-0.000000,0.000000,-0.000000,-0.648626,-0.031373,-0.000037,0.000485,0.000001,0.000000,0.000000,-0.000000,1.272850,0.033471,0.000000,-0.000522,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.067787,0.043850,-0.002152,-0.000718,-0.000000,0.000001,-0.000000,0.000000,-0.679550,-0.029989,0.001424,0.000489,0.000002,-0.000000,0.000000,-0.000000,1.305799,0.031906,-0.001566,-0.000522,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.108768,0.037396,-0.004300,-0.000711,0.000007,-0.000006,0.000006,-0.000005,-0.707625,-0.025668,0.002899,0.000492,-0.000002,0.000004,-0.000004,0.000003,1.335617,0.027209,-0.003129,-0.000517,0.000005,-0.000004,0.000004,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.141154,0.026661,-0.006465,-0.000793,-0.000102,0.000046,-0.000107,0.000078,-0.729900,-0.018382,0.004413,0.000560,0.000074,-0.000032,0.000074,-0.000055,1.359181,0.019399,-0.004704,-0.000577,-0.000074,0.000033,-0.000078,0.000057,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.160473,0.011083,-0.008951,-0.000134,0.001268,-0.000005,0.001576,-0.001040,-0.743248,-0.007677,0.006185,0.000112,-0.000881,0.000003,-0.001099,0.000724,1.373238,0.008064,-0.006513,-0.000097,0.000922,-0.000003,0.001147,-0.000757,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/14.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.164270,0.000000,0.000000,0.000000,-0.033552,0.036082,-0.016611,0.003028,-0.745880,0.000000,0.000000,0.000000,0.035189,-0.037840,0.017419,-0.003176,1.376000,0.000000,0.000000,0.000000,-0.003099,0.003333,-0.001534,0.000280,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.153218,-0.032264,-0.026057,0.000391,0.003691,-0.003055,0.001284,-0.000228,-0.734287,0.033844,0.027337,-0.000405,-0.003870,0.003203,-0.001346,0.000239,1.374979,-0.002980,-0.002407,0.000036,0.000341,-0.000282,0.000119,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.096979,-0.077609,-0.018814,0.002312,-0.000296,0.000206,-0.000080,0.000014,-0.675285,0.081434,0.019756,-0.002419,0.000311,-0.000216,0.000084,-0.000015,1.369785,-0.007168,-0.001738,0.000213,-0.000027,0.000019,-0.000007,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.002711,-0.108841,-0.012508,0.002070,0.000019,-0.000011,0.000004,-0.000001,-0.576350,0.114253,0.013157,-0.002167,-0.000020,0.000011,-0.000004,0.000001,1.361078,-0.010053,-0.001155,0.000191,0.000002,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.116557,-0.127608,-0.006251,0.002090,-0.000001,0.000000,-0.000000,0.000000,-0.451119,0.134023,0.006604,-0.002190,0.000001,-0.000000,0.000000,-0.000000,1.350062,-0.011787,-0.000578,0.000193,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.248328,-0.133845,0.000013,0.002087,-0.000000,0.000000,0.000000,0.000000,-0.312681,0.140663,0.000035,-0.002191,-0.000001,-0.000000,-0.000000,0.000000,1.337890,-0.012363,0.000001,0.000193,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.380074,-0.127561,0.006271,0.002087,0.000001,-0.000002,0.000001,-0.000001,-0.174175,0.134156,-0.006545,-0.002198,-0.000003,0.000002,-0.000001,0.000001,1.325720,-0.011783,0.000579,0.000193,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.499278,-0.108764,0.012516,0.002065,-0.000019,0.000018,-0.000017,0.000014,-0.048763,0.114472,-0.013133,-0.002181,0.000019,-0.000018,0.000018,-0.000015,1.314709,-0.010047,0.001156,0.000191,-0.000002,0.000002,-0.000002,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.593465,-0.077531,0.018805,0.002305,0.000296,-0.000134,0.000310,-0.000227,0.050400,0.081654,-0.019781,-0.002437,-0.000312,0.000141,-0.000327,0.000240,1.306009,-0.007162,0.001737,0.000213,0.000027,-0.000012,0.000029,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.649642,-0.032224,0.026028,0.000387,-0.003685,0.000013,-0.004581,0.003024,0.109577,0.033956,-0.027419,-0.000416,0.003885,-0.000015,0.004830,-0.003188,1.300820,-0.002977,0.002404,0.000036,-0.000340,0.000001,-0.000423,0.000279,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/15.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.660680,0.000000,0.000000,0.000000,-0.005595,0.006021,-0.002773,0.000506,0.121210,0.000000,0.000000,0.000000,-0.010053,0.010814,-0.004979,0.000908,1.299800,0.000000,0.000000,0.000000,0.007091,-0.007626,0.003511,-0.000640,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.662521,-0.005371,-0.004331,0.000073,0.000616,-0.000510,0.000214,-0.000038,0.117900,-0.009661,-0.007798,0.000122,0.001106,-0.000916,0.000385,-0.000068,1.302136,0.006819,0.005507,-0.000083,-0.000780,0.000646,-0.000271,0.000048,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.671868,-0.012880,-0.003100,0.000393,-0.000050,0.000034,-0.000013,0.000002,0.101070,-0.023214,-0.005613,0.000697,-0.000089,0.000062,-0.000024,0.000004,1.314021,0.016402,0.003976,-0.000489,0.000063,-0.000043,0.000017,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.687481,-0.017991,-0.002027,0.000352,0.000003,-0.000002,0.000001,-0.000000,0.072893,-0.032510,-0.003711,0.000623,0.000005,-0.000003,0.000001,-0.000000,1.333944,0.023002,0.002643,-0.000438,-0.000004,0.000002,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.707147,-0.020988,-0.000970,0.000350,-0.000003,-0.000001,0.000000,-0.000000,0.037297,-0.038055,-0.001833,0.000625,-0.000002,-0.000000,0.000000,-0.000000,1.359148,0.026965,0.001319,-0.000442,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.728757,-0.021889,0.000063,0.000339,-0.000002,0.000000,0.000000,-0.000000,-0.001967,-0.039853,0.000031,0.000619,-0.000001,0.000000,-0.000000,0.000000,1.386991,0.028279,-0.000005,-0.000441,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.750246,-0.020754,0.001069,0.000333,-0.000001,-0.000000,0.000000,-0.000000,-0.041171,-0.037937,0.001884,0.000617,0.000000,-0.000000,0.000000,-0.000000,1.414825,0.026948,-0.001326,-0.000441,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.769599,-0.017621,0.002061,0.000327,-0.000003,0.000003,-0.000003,0.000002,-0.076606,-0.032319,0.003731,0.000611,-0.000006,0.000005,-0.000005,0.000004,1.440006,0.022975,-0.002645,-0.000436,0.000004,-0.000004,0.000004,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.784833,-0.012519,0.003055,0.000365,0.000047,-0.000021,0.000050,-0.000037,-0.104585,-0.023024,0.005591,0.000682,0.000088,-0.000040,0.000092,-0.000067,1.459902,0.016377,-0.003973,-0.000487,-0.000062,0.000028,-0.000065,0.000048,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.793893,-0.005190,0.004197,0.000056,-0.000592,0.000002,-0.000735,0.000486,-0.121264,-0.009565,0.007728,0.000113,-0.001094,0.000004,-0.001359,0.000897,1.471768,0.006807,-0.005498,-0.000082,0.000778,-0.000003,0.000968,-0.000639,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/16.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.795670,0.000000,0.000000,0.000000,-0.000157,0.000174,-0.000082,0.000015,-0.124540,0.000000,0.000000,0.000000,0.007004,-0.007535,0.003470,-0.000633,1.474100,0.000000,0.000000,0.000000,0.010480,-0.011270,0.005188,-0.000946,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.795719,-0.000139,-0.000105,0.000011,0.000017,-0.000015,0.000006,-0.000001,-0.122234,0.006730,0.005432,-0.000086,-0.000770,0.000638,-0.000268,0.000048,1.477552,0.010078,0.008140,-0.000122,-0.001153,0.000954,-0.000401,0.000071,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.795945,-0.000295,-0.000052,0.000013,-0.000003,0.000001,-0.000000,0.000000,-0.110510,0.016171,0.003911,-0.000484,0.000063,-0.000043,0.000017,-0.000003,1.495120,0.024244,0.005878,-0.000722,0.000093,-0.000064,0.000025,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.796282,-0.000369,-0.000025,0.000007,-0.000000,0.000001,-0.000000,0.000000,-0.090879,0.022658,0.002596,-0.000430,-0.000003,0.000002,-0.000001,0.000000,1.524569,0.034004,0.003910,-0.000646,-0.000006,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.796669,-0.000400,-0.000006,0.000005,-0.000002,-0.000001,0.000000,0.000000,-0.066057,0.026555,0.001300,-0.000432,0.000001,-0.000000,-0.000000,0.000000,1.561834,0.039873,0.001956,-0.000653,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.797072,-0.000404,-0.000002,-0.000001,0.000001,0.000002,-0.000000,-0.000000,-0.038633,0.027861,0.000006,-0.000432,-0.000000,-0.000000,0.000000,0.000000,1.603011,0.041829,-0.000001,-0.000652,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.797477,-0.000401,0.000012,0.000012,0.000003,-0.000001,-0.000000,0.000000,-0.011198,0.026576,-0.001293,-0.000434,-0.000001,0.000000,-0.000000,0.000000,1.644187,0.039870,-0.001958,-0.000653,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.797852,-0.000335,0.000053,0.000010,-0.000003,-0.000000,0.000000,-0.000000,0.013651,0.022687,-0.002597,-0.000433,0.000003,-0.000004,0.000004,-0.000003,1.681447,0.033998,-0.003911,-0.000646,0.000006,-0.000005,0.000005,-0.000004,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.798127,-0.000209,0.000069,0.000002,-0.000001,0.000000,0.000000,-0.000000,0.033309,0.016192,-0.003917,-0.000485,-0.000062,0.000028,-0.000065,0.000048,1.710889,0.024236,-0.005878,-0.000721,-0.000092,0.000042,-0.000097,0.000071,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.798267,-0.000071,0.000065,-0.000008,-0.000007,-0.000000,-0.000007,0.000005,0.045047,0.006738,-0.005439,-0.000085,0.000771,-0.000003,0.000959,-0.000633,1.728449,0.010073,-0.008136,-0.000121,0.001152,-0.000004,0.001432,-0.000945,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/17.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.798290,0.000000,0.000000,0.000000,0.003011,-0.001662,0.000443,-0.000043,0.047356,0.000000,0.000000,-0.000000,-0.035098,0.038444,-0.017842,0.003270,1.731900,0.000000,0.000000,0.000000,-0.018535,0.019936,-0.009178,0.001673,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.796541,0.006089,0.007186,0.002779,-0.000156,0.000032,0.000011,-0.000004,0.036130,-0.032333,-0.025107,0.001658,0.003940,-0.003307,0.001405,-0.000251,1.725796,-0.017817,-0.014385,0.000222,0.002039,-0.001689,0.000711,-0.000126,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.780604,0.028371,0.014982,0.002542,0.000015,-0.000032,0.000069,-0.000024,-0.017866,-0.071681,-0.013772,0.003643,-0.000324,0.000234,-0.000102,0.000020,1.694751,-0.042828,-0.010364,0.001284,-0.000165,0.000118,-0.000052,0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.734680,0.066112,0.022917,0.002828,0.000051,0.000153,-0.000491,0.000096,-0.099846,-0.088886,-0.003541,0.003365,0.000028,-0.000051,0.000089,-0.000025,1.642753,-0.060017,-0.006890,0.001121,0.000005,-0.000022,0.000054,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.643014,0.119124,0.027885,-0.001905,-0.003198,0.000799,0.000004,-0.000060,-0.188868,-0.085661,0.007014,0.003862,0.000225,0.000063,-0.000346,0.000075,1.576993,-0.070275,-0.003128,0.001634,0.000340,-0.000088,0.000006,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.500365,0.159987,0.009768,-0.008737,-0.001254,0.000389,0.000039,-0.000058,-0.263636,-0.060383,0.016963,0.001093,-0.002029,0.000447,0.000153,-0.000070,1.505488,-0.070636,0.003131,0.002407,0.000161,-0.000039,-0.000017,0.000016,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.340229,0.150075,-0.020700,-0.011102,-0.000744,0.000423,-0.000917,0.000624,-0.307463,-0.028633,0.013361,-0.001943,0.000054,0.000093,-0.000073,0.000004,1.440509,-0.056703,0.010987,0.002853,0.000248,-0.000126,0.000282,-0.000198,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.222571,0.073370,-0.054902,-0.006366,0.009440,-0.000236,0.012381,-0.007904,-0.324601,-0.007470,0.007779,-0.002108,-0.000426,-0.000094,-0.000270,0.000290,1.397852,-0.025506,0.019833,0.001274,-0.003102,0.000047,-0.003970,0.002573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/18.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.196790,0.000000,0.000000,0.000000,-0.028094,0.030698,-0.014231,0.002606,-0.326900,0.000000,0.000000,0.000000,-0.026880,0.029379,-0.013622,0.002495,1.389000,0.000000,0.000000,0.000000,0.046388,-0.050680,0.023494,-0.004303,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.205812,-0.026033,-0.020328,0.001193,0.003145,-0.002635,0.001117,-0.000199,-0.335528,-0.024891,-0.019423,0.001156,0.003009,-0.002522,0.001069,-0.000191,1.403899,0.042996,0.033581,-0.001960,-0.005192,0.004349,-0.001844,0.000329,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.249553,-0.058400,-0.011663,0.002781,-0.000257,0.000180,-0.000071,0.000013,-0.377320,-0.055763,-0.011093,0.002671,-0.000249,0.000172,-0.000068,0.000012,1.476159,0.096497,0.019296,-0.004589,0.000422,-0.000298,0.000118,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.316971,-0.073847,-0.003860,0.002573,0.000016,-0.000012,0.000005,-0.000001,-0.441638,-0.070395,-0.003620,0.002457,0.000011,-0.000011,0.000005,-0.000001,1.587584,0.122081,0.006409,-0.004255,-0.000029,0.000019,-0.000008,0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.392097,-0.073822,0.003885,0.002570,-0.000018,0.000017,-0.000017,0.000013,-0.513192,-0.070255,0.003751,0.002439,-0.000020,0.000016,-0.000016,0.000012,1.711803,0.122083,-0.006407,-0.004255,0.000029,-0.000028,0.000028,-0.000021,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.459468,-0.058341,0.011670,0.002773,0.000255,-0.000122,0.000279,-0.000199,-0.577264,-0.055445,0.011125,0.002623,0.000241,-0.000115,0.000264,-0.000189,1.823233,0.096504,-0.019295,-0.004590,-0.000422,0.000202,-0.000461,0.000329,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.503153,-0.025992,0.020302,0.001184,-0.003139,0.000042,-0.004004,0.002601,-0.618760,-0.024677,0.019284,0.001112,-0.002978,0.000040,-0.003797,0.002467,1.895499,0.043001,-0.033584,-0.001961,0.005193,-0.000070,0.006625,-0.004303,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/19.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.512160,0.000000,0.000000,0.000000,0.024548,-0.026002,0.011889,-0.002158,-0.627310,0.000000,0.000000,0.000000,-0.002748,0.003075,-0.001440,0.000265,1.910400,0.000000,0.000000,0.000000,-0.019659,0.020793,-0.009501,0.001724,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.503884,0.024407,0.020280,0.000418,-0.002657,0.002172,-0.000905,0.000159,-0.628158,-0.002400,-0.001766,0.000246,0.000316,-0.000269,0.000116,-0.000021,1.903757,-0.019610,-0.016339,-0.000393,0.002123,-0.001735,0.000722,-0.000127,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.460009,0.062141,0.017087,-0.001009,0.000208,-0.000144,0.000055,-0.000009,-0.631937,-0.004731,-0.000532,0.000398,-0.000026,0.000019,-0.000008,0.000001,1.868399,-0.050204,-0.013964,0.000745,-0.000168,0.000114,-0.000044,0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.381681,0.093662,0.014492,-0.000849,-0.000018,0.000007,-0.000003,0.000001,-0.636815,-0.004647,0.000608,0.000376,0.000001,-0.000001,-0.000000,0.000000,1.804886,-0.076208,-0.012092,0.000604,0.000010,-0.000006,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.274388,0.120053,0.011882,-0.000884,-0.000005,0.000001,-0.000000,0.000000,-0.640480,-0.002308,0.001724,0.000362,-0.000008,-0.000001,0.000000,0.000000,1.717195,-0.098561,-0.010258,0.000611,-0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.143341,0.141149,0.009207,-0.000897,-0.000001,0.000001,-0.000001,0.000000,-0.640711,0.002189,0.002754,0.000324,-0.000008,0.000003,0.000000,-0.000000,1.608986,-0.117251,-0.008437,0.000603,-0.000002,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.006118,0.156873,0.006517,-0.000896,0.000000,0.000000,-0.000000,0.000000,-0.635449,0.008651,0.003706,0.000319,0.000002,0.000000,-0.000001,0.000000,1.483899,-0.132322,-0.006635,0.000600,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.168612,0.167220,0.003832,-0.000894,0.000001,0.000001,-0.000000,0.000000,-0.622771,0.017026,0.004668,0.000318,-0.000003,-0.000001,0.000000,-0.000000,1.345542,-0.143789,-0.004831,0.000602,0.000001,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.338772,0.172209,0.001160,-0.000888,0.000002,0.000000,0.000000,0.000000,-0.600762,0.027302,0.005598,0.000298,-0.000009,-0.000001,-0.000002,-0.000000,1.197524,-0.151644,-0.003022,0.000605,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.511255,0.171875,-0.001484,-0.000868,0.000014,0.000006,-0.000001,0.000000,-0.567577,0.039336,0.006392,0.000203,-0.000054,-0.000017,0.000005,-0.000001,1.043465,-0.155869,-0.001201,0.000610,0.000002,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.680797,0.166380,-0.003964,-0.000774,0.000032,0.000002,-0.000001,0.000000,-0.521713,0.052452,0.006565,-0.000112,-0.000093,0.000001,0.000000,-0.000000,0.887006,-0.156434,0.000642,0.000620,0.000003,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.842472,0.156265,-0.006078,-0.000630,0.000040,-0.000000,-0.000001,0.000000,-0.462899,0.064882,0.005687,-0.000468,-0.000085,0.000007,-0.000000,-0.000000,0.731837,-0.153276,0.002523,0.000634,0.000004,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.992068,0.142375,-0.007737,-0.000480,0.000035,-0.000002,-0.000000,0.000000,-0.392876,0.074547,0.003843,-0.000742,-0.000055,0.000007,-0.000001,0.000000,0.581723,-0.146312,0.004448,0.000648,0.000003,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.126259,0.125592,-0.008985,-0.000359,0.000026,-0.000002,-0.000000,0.000000,-0.315277,0.079817,0.001345,-0.000908,-0.000031,0.000005,-0.000001,0.000000,0.440509,-0.135461,0.006408,0.000659,0.000002,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.242531,0.106639,-0.009926,-0.000275,0.000016,-0.000002,-0.000000,0.000000,-0.235050,0.079682,-0.001523,-0.000993,-0.000014,0.000003,-0.000000,0.000000,0.312117,-0.120661,0.008397,0.000667,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.338983,0.086015,-0.010677,-0.000232,0.000006,-0.000001,-0.000000,0.000000,-0.157894,0.073617,-0.004557,-0.001024,-0.000004,0.000002,-0.000001,0.000000,0.200521,-0.101861,0.010404,0.000671,0.000001,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.414095,0.063989,-0.011338,-0.000208,0.000009,-0.000007,0.000006,-0.000005,-0.089861,0.061423,-0.007636,-0.001020,0.000009,-0.000009,0.000009,-0.000007,0.109735,-0.079041,0.012412,0.000660,-0.000011,0.000010,-0.000009,0.000008,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.466542,0.040689,-0.012003,-0.000315,-0.000128,0.000052,-0.000123,0.000095,-0.037093,0.043083,-0.010753,-0.001153,-0.000161,0.000072,-0.000167,0.000123,0.043763,-0.052232,0.014452,0.000806,0.000176,-0.000075,0.000176,-0.000133,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.494809,0.015413,-0.013044,0.000563,0.001620,0.000020,0.001927,-0.001308,-0.006049,0.017694,-0.014376,-0.000106,0.002003,-0.000004,0.002478,-0.001641,0.006933,-0.020456,0.017021,-0.000381,-0.002220,-0.000014,-0.002686,0.001804,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,2.280100,0.000000,0.000000,-0.000000,-0.022791,0.024192,-0.011072,0.002011,-0.213800,0.000000,0.000000,0.000000,-0.008352,0.008869,-0.004060,0.000737,0.698800,0.000000,0.000000,0.000000,0.025351,-0.026906,0.012313,-0.002236,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.272440,-0.022562,-0.018680,-0.000306,0.002469,-0.002026,0.000845,-0.000149,-0.216605,-0.008259,-0.006832,-0.000103,0.000906,-0.000743,0.000310,-0.000055,0.707322,0.025099,0.020783,0.000341,-0.002748,0.002252,-0.000939,0.000166,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.232032,-0.057063,-0.015491,0.001002,-0.000197,0.000135,-0.000051,0.000009,-0.231381,-0.020847,-0.005633,0.000378,-0.000072,0.000049,-0.000019,0.000003,0.752276,0.063479,0.017224,-0.001123,0.000218,-0.000149,0.000057,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.160375,-0.085400,-0.012907,0.000839,0.000012,-0.000007,0.000002,-0.000000,-0.257521,-0.031110,-0.004653,0.000319,0.000004,-0.000003,0.000001,-0.000000,0.831973,0.094961,0.014325,-0.000942,-0.000014,0.000008,-0.000003,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,2.062915,-0.108671,-0.010358,0.000853,-0.000001,0.000000,-0.000000,0.000000,-0.292962,-0.039450,-0.003685,0.000323,-0.000000,0.000000,-0.000000,0.000000,0.940308,0.120755,0.011463,-0.000957,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.944738,-0.126830,-0.007802,0.000852,0.000000,0.000000,0.000000,0.000000,-0.335773,-0.045850,-0.002716,0.000323,-0.000000,-0.000000,-0.000000,-0.000000,1.071570,0.140811,0.008593,-0.000956,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.810959,-0.139877,-0.005244,0.000853,0.000000,0.000000,0.000000,-0.000000,-0.384017,-0.050314,-0.001749,0.000322,-0.000000,-0.000000,-0.000000,0.000000,1.220018,0.155129,0.005724,-0.000956,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.666691,-0.147804,-0.002682,0.000855,0.000001,0.000000,0.000000,-0.000000,-0.435758,-0.052847,-0.000786,0.000320,-0.000001,-0.000000,-0.000000,0.000000,1.379915,0.163708,0.002855,-0.000956,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.517061,-0.150598,-0.000109,0.000860,0.000002,0.000000,0.000000,-0.000000,-0.489072,-0.053463,0.000167,0.000315,-0.000002,-0.000000,-0.000000,0.000000,1.545522,0.166550,-0.000013,-0.000956,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.367216,-0.148229,0.002481,0.000867,0.000002,-0.000000,-0.000000,0.000000,-0.542055,-0.052193,0.001099,0.000305,-0.000003,-0.000000,0.000000,-0.000000,1.711102,0.163655,-0.002881,-0.000955,0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.222337,-0.140659,0.005091,0.000873,0.000001,-0.000000,-0.000000,-0.000000,-0.592847,-0.049092,0.001996,0.000293,-0.000003,-0.000000,0.000000,0.000000,1.870922,0.155029,-0.005745,-0.000954,0.000000,0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,1.087644,-0.127852,0.007718,0.000878,0.000001,-0.000000,0.000000,0.000000,-0.639652,-0.044231,0.002858,0.000282,-0.000002,0.000001,-0.000000,-0.000000,2.019251,0.140677,-0.008606,-0.000953,0.000000,-0.000000,-0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.968390,-0.109778,0.010357,0.000881,0.000001,-0.000001,0.000000,-0.000000,-0.680745,-0.037675,0.003696,0.000278,-0.000000,-0.000000,0.000000,-0.000000,2.150368,0.120605,-0.011465,-0.000953,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.869849,-0.086424,0.012991,0.000868,-0.000012,0.000011,-0.000011,0.000009,-0.714446,-0.029451,0.004525,0.000272,-0.000004,0.000004,-0.000003,0.000003,2.258555,0.094818,-0.014315,-0.000938,0.000014,-0.000012,0.000011,-0.000010,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.797281,-0.057831,0.015664,0.001034,0.000199,-0.000086,0.000201,-0.000151,-0.739101,-0.019585,0.005362,0.000326,0.000067,-0.000029,0.000067,-0.000051,2.338124,0.063369,-0.017201,-0.001118,-0.000218,0.000094,-0.000219,0.000165,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.756312,-0.022886,0.018942,-0.000300,-0.002508,-0.000011,-0.003050,0.002041,-0.752944,-0.007711,0.006399,-0.000122,-0.000841,-0.000004,-0.001020,0.000684,2.382995,0.025051,-0.020745,0.000343,0.002742,0.000013,0.003333,-0.002231,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.748540,0.000000,0.000000,0.000000,-0.001490,0.001608,-0.000742,0.000135,-0.755560,0.000000,0.000000,-0.000000,0.000147,-0.000163,0.000076,-0.000014,2.391500,0.000000,0.000000,0.000000,-0.015270,0.016487,-0.007603,0.001388,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.748052,-0.001420,-0.001137,0.000029,0.000165,-0.000137,0.000058,-0.000010,-0.755514,0.000131,0.000098,-0.000011,-0.000017,0.000014,-0.000006,0.000001,2.386502,-0.014550,-0.011657,0.000295,0.001687,-0.001401,0.000590,-0.000105,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.745599,-0.003359,-0.000781,0.000114,-0.000013,0.000009,-0.000004,0.000001,-0.755303,0.000271,0.000041,-0.000018,0.000002,-0.000001,0.000000,-0.000000,2.361361,-0.034427,-0.008007,0.001167,-0.000136,0.000095,-0.000037,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.741566,-0.004605,-0.000468,0.000103,0.000001,-0.000000,0.000000,-0.000000,-0.755007,0.000305,-0.000004,-0.000013,0.000001,0.000000,-0.000000,0.000000,2.320023,-0.047186,-0.004793,0.001057,0.000009,-0.000005,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.736597,-0.005229,-0.000156,0.000104,-0.000000,0.000000,-0.000000,0.000000,-0.754717,0.000263,-0.000035,-0.000008,0.000001,0.000000,0.000000,-0.000000,2.269107,-0.053582,-0.001599,0.001066,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.731316,-0.005229,0.000156,0.000104,0.000000,-0.000000,0.000000,-0.000000,-0.754496,0.000175,-0.000050,-0.000002,0.000002,0.000000,-0.000000,-0.000000,2.214993,-0.053581,0.001599,0.001066,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.726346,-0.004605,0.000468,0.000103,-0.000001,0.000001,-0.000001,0.000001,-0.754371,0.000075,-0.000047,0.000004,0.000002,-0.000000,-0.000000,0.000000,2.164077,-0.047186,0.004793,0.001057,-0.000009,0.000008,-0.000008,0.000006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.722312,-0.003360,0.000781,0.000114,0.000013,-0.000006,0.000014,-0.000010,-0.754337,-0.000000,-0.000026,0.000010,0.000001,-0.000000,0.000000,-0.000000,2.122739,-0.034427,0.008007,0.001167,0.000136,-0.000062,0.000144,-0.000105,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.719858,-0.001420,0.001138,0.000029,-0.000165,0.000001,-0.000206,0.000135,-0.754352,-0.000019,0.000008,0.000010,-0.000004,0.000000,-0.000006,0.000004,2.097599,-0.014550,0.011657,0.000295,-0.001687,0.000010,-0.002111,0.001388,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.719370,0.000000,0.000000,0.000000,-0.020368,0.021903,-0.010083,0.001838,-0.754360,0.000000,0.000000,-0.000000,-0.004233,0.004551,-0.002095,0.000382,2.092600,0.000000,0.000000,-0.000000,0.015831,-0.017025,0.007837,-0.001429,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.712660,-0.019587,-0.015820,0.000236,0.002240,-0.001854,0.000779,-0.000138,-0.755755,-0.004072,-0.003289,0.000048,0.000466,-0.000385,0.000162,-0.000029,2.097815,0.015224,0.012296,-0.000184,-0.001741,0.001441,-0.000606,0.000107,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.678516,-0.047121,-0.011426,0.001402,-0.000180,0.000125,-0.000049,0.000008,-0.762854,-0.009800,-0.002379,0.000290,-0.000037,0.000026,-0.000010,0.000002,2.124354,0.036625,0.008881,-0.001090,0.000140,-0.000097,0.000038,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.621277,-0.066093,-0.007600,0.001256,0.000012,-0.000007,0.000002,-0.000000,-0.774762,-0.013754,-0.001587,0.000260,0.000002,-0.000001,0.000000,-0.000000,2.168844,0.051371,0.005907,-0.000976,-0.000009,0.000005,-0.000002,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.548847,-0.077502,-0.003803,0.001268,-0.000001,0.000000,-0.000000,0.000000,-0.789841,-0.016142,-0.000799,0.000263,-0.000000,0.000000,-0.000000,0.000000,2.225141,0.060239,0.002956,-0.000986,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.468810,-0.081304,-0.000000,0.001268,0.000000,0.000000,-0.000000,0.000000,-0.806519,-0.016951,-0.000010,0.000264,0.000000,0.000000,0.000000,0.000000,2.287350,0.063195,0.000000,-0.000985,-0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.388773,-0.077502,0.003803,0.001268,0.000001,-0.000001,0.000000,-0.000000,-0.823217,-0.016179,0.000782,0.000265,0.000000,-0.000000,0.000000,-0.000000,2.349559,0.060239,-0.002956,-0.000986,-0.000000,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.316343,-0.066093,0.007600,0.001256,-0.000012,0.000011,-0.000010,0.000008,-0.838348,-0.013819,0.001577,0.000264,-0.000002,0.000002,-0.000002,0.000002,2.405856,0.051371,-0.005907,-0.000976,0.000009,-0.000008,0.000008,-0.000007,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.259104,-0.047121,0.011426,0.001402,0.000180,-0.000081,0.000188,-0.000138,-0.850326,-0.009869,0.002385,0.000297,0.000038,-0.000017,0.000040,-0.000029,2.450346,0.036625,-0.008881,-0.001090,-0.000140,0.000063,-0.000146,0.000107,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.224960,-0.019587,0.015820,0.000236,-0.002240,0.000008,-0.002785,0.001838,-0.857482,-0.004109,0.003316,0.000053,-0.000471,0.000002,-0.000585,0.000386,2.476885,0.015224,-0.012296,-0.000184,0.001741,-0.000006,0.002165,-0.001429,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,0.218250,0.000000,0.000000,0.000000,-0.041345,0.044869,-0.020739,0.003791,-0.858890,0.000000,0.000000,0.000000,-0.007144,0.007753,-0.003584,0.000655,2.482100,0.000000,0.000000,-0.000000,-0.012302,0.013350,-0.006171,0.001128,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.204826,-0.038933,-0.030858,0.001208,0.004594,-0.003829,0.001617,-0.000288,-0.861210,-0.006728,-0.005332,0.000209,0.000794,-0.000662,0.000279,-0.000050,2.478106,-0.011584,-0.009182,0.000359,0.001367,-0.001139,0.000481,-0.000086,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.138338,-0.090105,-0.019747,0.003561,-0.000371,0.000260,-0.000102,0.000018,-0.872699,-0.015570,-0.003412,0.000615,-0.000064,0.000045,-0.000018,0.000003,2.458323,-0.026810,-0.005876,0.001060,-0.000111,0.000077,-0.000030,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,0.031851,-0.119589,-0.009847,0.003261,0.000024,-0.000014,0.000005,-0.000001,-0.891100,-0.020665,-0.001701,0.000564,0.000004,-0.000002,0.000001,-0.000000,2.426638,-0.035583,-0.002930,0.000970,0.000007,-0.000004,0.000002,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.094310,-0.129448,-0.000000,0.003289,0.000000,-0.000002,0.000001,-0.000001,-0.912900,-0.022368,0.000000,0.000568,-0.000000,-0.000000,0.000000,-0.000000,2.389100,-0.038516,-0.000000,0.000979,0.000000,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.220470,-0.119589,0.009847,0.003261,-0.000024,0.000023,-0.000023,0.000018,-0.934701,-0.020665,0.001702,0.000564,-0.000004,0.000004,-0.000004,0.000003,2.351562,-0.035583,0.002930,0.000970,-0.000007,0.000007,-0.000007,0.000005,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.326957,-0.090106,0.019747,0.003561,0.000371,-0.000174,0.000399,-0.000288,-0.953101,-0.015570,0.003412,0.000615,0.000064,-0.000030,0.000069,-0.000050,2.319877,-0.026810,0.005876,0.001060,0.000111,-0.000052,0.000119,-0.000086,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.393446,-0.038933,0.030858,0.001208,-0.004594,0.000043,-0.005797,0.003791,-0.964590,-0.006727,0.005332,0.000209,-0.000794,0.000007,-0.001002,0.000655,2.300094,-0.011584,0.009182,0.000359,-0.001367,0.000013,-0.001725,0.001128,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.406870,0.000000,0.000000,0.000000,-0.006429,0.006914,-0.003183,0.000580,-0.966910,0.000000,0.000000,0.000000,0.015764,-0.016954,0.007805,-0.001423,2.296100,0.000000,0.000000,-0.000000,-0.046811,0.050340,-0.023174,0.004225,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.408988,-0.006183,-0.004994,0.000075,0.000707,-0.000585,0.000246,-0.000044,-0.961718,0.015157,0.012240,-0.000185,-0.001734,0.001436,-0.000603,0.000107,2.280679,-0.045017,-0.036358,0.000543,0.005149,-0.004262,0.001791,-0.000318,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.419766,-0.014874,-0.003607,0.000443,-0.000057,0.000039,-0.000015,0.000003,-0.935301,0.036452,0.008834,-0.001086,0.000140,-0.000097,0.000038,-0.000007,2.202208,-0.108295,-0.026259,0.003223,-0.000413,0.000287,-0.000111,0.000019,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.437833,-0.020862,-0.002399,0.000396,0.000004,-0.000002,0.000001,-0.000000,-0.891027,0.051118,0.005874,-0.000971,-0.000009,0.000005,-0.000002,0.000000,2.070658,-0.151897,-0.017468,0.002886,0.000026,-0.000015,0.000005,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.460696,-0.024464,-0.001201,0.000400,-0.000000,0.000000,-0.000000,0.000000,-0.835011,0.059934,0.002938,-0.000981,0.000000,-0.000000,0.000000,-0.000000,1.904195,-0.178118,-0.008741,0.002915,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.485960,-0.025664,0.000000,0.000400,-0.000000,0.000000,-0.000000,0.000000,-0.773120,0.062869,-0.000002,-0.000980,0.000000,-0.000000,0.000000,-0.000000,1.720250,-0.186858,0.000000,0.002913,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.511224,-0.024464,0.001201,0.000400,0.000000,-0.000000,0.000000,-0.000000,-0.711233,0.059925,-0.002942,-0.000980,-0.000000,0.000001,-0.000000,0.000000,1.536305,-0.178118,0.008741,0.002915,0.000001,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.534087,-0.020862,0.002399,0.000396,-0.000004,0.000003,-0.000003,0.000003,-0.655231,0.051101,-0.005877,-0.000971,0.000009,-0.000008,0.000008,-0.000007,1.369842,-0.151897,0.017468,0.002886,-0.000026,0.000025,-0.000024,0.000019,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.552154,-0.014874,0.003607,0.000443,0.000057,-0.000026,0.000059,-0.000044,-0.610976,0.036431,-0.008834,-0.001084,-0.000139,0.000063,-0.000146,0.000107,1.238292,-0.108295,0.026259,0.003223,0.000413,-0.000187,0.000433,-0.000318,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.562932,-0.006183,0.004994,0.000075,-0.000707,0.000003,-0.000879,0.000580,-0.584578,0.015144,-0.012231,-0.000183,0.001732,-0.000006,0.002153,-0.001421,1.159821,-0.045017,0.036358,0.000543,-0.005149,0.000019,-0.006400,0.004225,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/7.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.565050,0.000000,0.000000,0.000000,0.015778,-0.016912,0.007774,-0.001416,-0.579390,0.000000,0.000000,0.000000,-0.006867,0.007355,-0.003379,0.000615,1.144400,0.000000,0.000000,0.000000,0.037560,-0.040260,0.018507,-0.003371,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.559826,0.015284,0.012423,-0.000085,-0.001729,0.001428,-0.000599,0.000106,-0.581667,-0.006666,-0.005427,0.000025,0.000752,-0.000620,0.000260,-0.000046,1.156836,0.036385,0.029575,-0.000202,-0.004116,0.003399,-0.001426,0.000253,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.532998,0.037247,0.009314,-0.000990,0.000138,-0.000096,0.000037,-0.000006,-0.593389,-0.016301,-0.004109,0.000420,-0.000060,0.000042,-0.000016,0.000003,1.220703,0.088670,0.022175,-0.002357,0.000329,-0.000228,0.000088,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.487354,0.053158,0.006639,-0.000877,-0.000009,0.000005,-0.000002,0.000000,-0.613411,-0.023369,-0.002977,0.000371,0.000004,-0.000002,0.000001,-0.000000,1.329367,0.126552,0.015806,-0.002087,-0.000021,0.000012,-0.000004,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.428439,0.063787,0.003986,-0.000886,0.000000,-0.000000,0.000000,-0.000000,-0.639384,-0.028201,-0.001852,0.000377,0.000000,0.000000,0.000000,-0.000000,1.469625,0.151859,0.009491,-0.002110,0.000001,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.361552,0.069101,0.001328,-0.000886,-0.000000,0.000000,-0.000000,0.000000,-0.669059,-0.030771,-0.000717,0.000380,0.000001,0.000000,0.000000,0.000000,1.628865,0.164512,0.003163,-0.002109,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.292009,0.069100,-0.001329,-0.000886,0.000000,-0.000000,0.000000,-0.000000,-0.700167,-0.031062,0.000429,0.000386,0.000002,0.000000,0.000000,-0.000000,1.794432,0.164512,-0.003163,-0.002109,0.000000,-0.000000,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.225123,0.063785,-0.003986,-0.000886,-0.000000,0.000001,-0.000000,0.000000,-0.730411,-0.029034,0.001607,0.000402,0.000006,0.000000,0.000000,-0.000000,1.953672,0.151860,-0.009490,-0.002110,-0.000001,0.000002,-0.000001,0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.166211,0.053155,-0.006639,-0.000877,0.000009,-0.000008,0.000008,-0.000006,-0.757430,-0.024587,0.002854,0.000428,0.000005,0.000005,-0.000004,0.000003,2.093932,0.126553,-0.015806,-0.002087,0.000021,-0.000019,0.000019,-0.000015,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.120569,0.037244,-0.009314,-0.000990,-0.000138,0.000062,-0.000144,0.000106,-0.778726,-0.017554,0.004219,0.000522,0.000077,-0.000032,0.000072,-0.000052,2.202596,0.088671,-0.022175,-0.002357,-0.000329,0.000147,-0.000342,0.000253,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.093743,0.015283,-0.012422,-0.000085,0.001729,-0.000003,0.002138,-0.001416,-0.791474,-0.007336,0.005905,0.000112,-0.000840,0.000002,-0.001052,0.000694,2.266464,0.036385,-0.029575,-0.000202,0.004117,-0.000007,0.005089,-0.003371,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/8.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.088519,0.000000,0.000000,0.000000,-0.025303,0.027320,-0.012599,0.002300,-0.793990,0.000000,0.000000,0.000000,0.018926,-0.020435,0.009424,-0.001720,2.278900,0.000000,0.000000,0.000000,-0.027153,0.029317,-0.013520,0.002468,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.096802,-0.024111,-0.019315,0.000489,0.002795,-0.002321,0.000978,-0.000174,-0.787795,0.018032,0.014445,-0.000367,-0.002091,0.001736,-0.000731,0.000130,2.270012,-0.025873,-0.020728,0.000525,0.003000,-0.002491,0.001049,-0.000186,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.138460,-0.057047,-0.013268,0.001934,-0.000225,0.000157,-0.000061,0.000011,-0.756641,0.042660,0.009919,-0.001447,0.000169,-0.000117,0.000046,-0.000008,2.225308,-0.061217,-0.014238,0.002075,-0.000242,0.000168,-0.000066,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.206959,-0.078189,-0.007942,0.001752,0.000014,-0.000008,0.000003,-0.000001,-0.705420,0.058465,0.005936,-0.001310,-0.000011,0.000006,-0.000002,0.000000,2.151801,-0.083905,-0.008522,0.001880,0.000016,-0.000009,0.000003,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.291329,-0.088787,-0.002650,0.001767,-0.000001,0.000000,-0.000000,0.000000,-0.642335,0.066386,0.001980,-0.001321,0.000001,-0.000000,0.000000,-0.000000,2.061263,-0.095278,-0.002844,0.001896,-0.000001,0.000000,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.380999,-0.088787,0.002650,0.001767,0.000001,-0.000001,0.000001,-0.000001,-0.575290,0.066383,-0.001982,-0.001321,-0.000001,0.000001,-0.000000,0.000000,1.965037,-0.095278,0.002844,0.001896,0.000001,-0.000001,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.465370,-0.078189,0.007942,0.001752,-0.000014,0.000014,-0.000014,0.000011,-0.512210,0.058458,-0.005938,-0.001309,0.000011,-0.000010,0.000010,-0.000008,1.874499,-0.083905,0.008522,0.001880,-0.000016,0.000015,-0.000015,0.000011,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.533869,-0.057047,0.013268,0.001934,0.000225,-0.000103,0.000238,-0.000174,-0.460997,0.042650,-0.009920,-0.001446,-0.000168,0.000077,-0.000178,0.000130,1.800992,-0.061217,0.014238,0.002075,0.000242,-0.000111,0.000256,-0.000186,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.575527,-0.024111,0.019316,0.000489,-0.002795,0.000017,-0.003498,0.002300,-0.429852,0.018026,-0.014441,-0.000366,0.002090,-0.000013,0.002615,-0.001719,1.756288,-0.025873,0.020728,0.000525,-0.003000,0.000019,-0.003754,0.002468,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/sequence_trajectories/7/9.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n1.000000,-0.583810,0.000000,0.000000,0.000000,0.026636,-0.028759,0.013263,-0.002421,-0.423660,0.000000,0.000000,0.000000,-0.033152,0.035795,-0.016508,0.003013,1.747400,0.000000,0.000000,-0.000000,-0.030111,0.032511,-0.014993,0.002737,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.575091,0.025380,0.020333,-0.000515,-0.002943,0.002443,-0.001029,0.000183,-0.434512,-0.031590,-0.025307,0.000641,0.003663,-0.003041,0.001281,-0.000228,1.737544,-0.028692,-0.022986,0.000582,0.003327,-0.002762,0.001163,-0.000207,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.531239,0.060051,0.013966,-0.002036,0.000237,-0.000165,0.000064,-0.000011,-0.489093,-0.074743,-0.017384,0.002534,-0.000295,0.000206,-0.000080,0.000014,1.687970,-0.067886,-0.015789,0.002302,-0.000268,0.000187,-0.000073,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.459132,0.082306,0.008360,-0.001844,-0.000015,0.000009,-0.000003,0.000001,-0.578842,-0.102444,-0.010405,0.002295,0.000019,-0.000011,0.000004,-0.000001,1.606455,-0.093045,-0.009451,0.002084,0.000017,-0.000010,0.000004,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.370319,0.093463,0.002790,-0.001860,0.000001,-0.000000,0.000000,-0.000000,-0.689385,-0.116330,-0.003472,0.002315,-0.000001,0.000001,-0.000000,0.000000,1.506054,-0.105657,-0.003154,0.002103,-0.000001,0.000001,-0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.275927,0.093462,-0.002790,-0.001860,-0.000001,0.000001,-0.000001,0.000001,-0.806873,-0.116330,0.003472,0.002315,0.000001,-0.000002,0.000001,-0.000001,1.399346,-0.105657,0.003154,0.002103,0.000001,-0.000002,0.000001,-0.000001,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.187114,0.082306,-0.008360,-0.001844,0.000015,-0.000014,0.000014,-0.000011,-0.917417,-0.102445,0.010405,0.002295,-0.000019,0.000018,-0.000018,0.000014,1.298945,-0.093045,0.009451,0.002084,-0.000017,0.000016,-0.000016,0.000013,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.115008,0.060050,-0.013967,-0.002036,-0.000237,0.000109,-0.000251,0.000183,-1.007166,-0.074744,0.017384,0.002534,0.000295,-0.000135,0.000312,-0.000228,1.217430,-0.067886,0.015789,0.002302,0.000268,-0.000123,0.000284,-0.000207,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.000000,-0.071156,0.025380,-0.020333,-0.000515,0.002943,-0.000018,0.003683,-0.002421,-1.061748,-0.031590,0.025308,0.000641,-0.003663,0.000023,-0.004584,0.003013,1.167856,-0.028692,0.022986,0.000582,-0.003327,0.000021,-0.004163,0.002737,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\n\nfrom pycrazyswarm import *\nimport pycrazyswarm.cfsim.cffirmware as firm\nimport uav_trajectory\n\nTIMESCALE = 1.0\n\nPOSITIONS = [\n    [0, 1.0, 1.5],\n    [0.25, 0.5, 2.37],\n    [0.25, -0.5, 2.37],\n    [-0.25, 0.5, 0.63],\n    [-0.25, -0.5, 0.63],\n    [0, -1.0, 1.5]\n]\n\nOFFSET = [0.0, 0.0, -0.3]\n\nif __name__ == \"__main__\":\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    ids = [15, 16, 17, 18, 19, 20] #[15, 16, 17] #range(1, 6+1)\n    trajIds = [1, 2, 3, 4, 5, 6] #[1, 2, 3, 4, 5, 6]\n\n    cfs = [allcfs.crazyfliesById[i] for i in ids]\n    root = 'swap6v_pps'\n    fnames = ['{0}/pp{1}.csv'.format(root, i) for i in trajIds]\n    # trajs = [piecewise.loadcsv(fname) for fname in fnames]\n\n    T = 0\n    for cf, fname in zip(cfs, fnames):\n        traj = uav_trajectory.Trajectory()\n        traj.loadcsv(fname)\n        cf.uploadTrajectory(0, 0, traj)\n        T = max(T, traj.duration)\n    print(\"T: \", T * TIMESCALE)\n\n    allcfs.takeoff(targetHeight=1.0, duration=2.0)\n    timeHelper.sleep(2.5)\n\n    for cf, trajId in zip(cfs, trajIds):\n        pos = POSITIONS[trajId - 1]\n        print(pos)\n        cf.goTo(np.array(pos) + np.array(OFFSET), 0, 3.0)\n    timeHelper.sleep(3.5)\n\n    allcfs.startTrajectory(0, timescale=TIMESCALE)\n    timeHelper.sleep(T + 3.0)\n    allcfs.startTrajectory(0, timescale=TIMESCALE, reverse=True)\n    timeHelper.sleep(T + 3.0)\n\n    for cf in cfs:\n        pos = np.array(cf.initialPosition) + np.array([0, 0, 1.0])\n        cf.goTo(pos, 0, 3.0)\n    timeHelper.sleep(3.5)\n\n    allcfs.land(targetHeight=0.06, duration=2.0)\n    timeHelper.sleep(3.0)\n\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp1.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.300000,0.000000,0.000000,0.000000,-0.329790,0.516062,-0.307082,0.073682,0.000000,0.000000,0.000000,0.000000,-1.136523,1.428935,-0.753062,0.159072,2.000000,0.000000,0.000000,0.000000,0.173516,-0.206401,0.104584,-0.021660,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.300855,-0.012206,-0.059519,-0.093141,0.067693,0.151610,-0.172804,0.061839,-0.003218,-0.047264,-0.243788,-0.457023,0.030642,0.508959,-0.457256,0.163264,2.000500,0.007389,0.038502,0.074237,0.001718,-0.078163,0.064024,-0.023697,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.308707,-0.053144,-0.089158,0.023761,0.129019,-0.028332,-0.065544,0.031943,-0.036897,-0.245394,-0.518983,-0.228852,0.327448,0.032531,-0.170897,0.087426,2.005859,0.039475,0.085877,0.043871,-0.048922,-0.012505,0.022228,-0.012322,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.326732,-0.086087,-0.030567,0.118957,0.049625,-0.085447,-0.012183,0.020340,-0.132983,-0.527547,-0.570967,0.077476,0.255707,-0.112843,-0.021212,0.027042,2.021582,0.087447,0.099530,-0.007605,-0.050453,0.005414,0.000815,-0.000358,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.348197,-0.077670,0.063613,0.114152,-0.057482,-0.076188,0.021095,0.033683,-0.298460,-0.784804,-0.435290,0.259724,0.109555,-0.110824,0.022816,0.000645,2.049353,0.132742,0.075792,-0.054469,-0.043117,0.006810,0.000376,0.009888,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.362147,-0.029360,0.117693,0.020249,-0.114521,0.001270,0.080050,-0.034284,-0.517483,-0.948933,-0.215380,0.307232,-0.007232,-0.075668,0.021689,-0.001801,2.086264,0.157883,0.020060,-0.091861,-0.028845,0.020758,0.018290,-0.007760,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.362243,0.026561,0.094120,-0.073149,-0.056636,0.077161,0.022394,-0.051777,-0.763474,-1.000822,0.001743,0.259239,-0.082469,-0.044284,0.017186,0.016297,2.125465,0.149386,-0.055496,-0.103077,0.010006,0.037852,0.005857,-0.018116,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.351007,0.057916,0.030327,-0.081640,0.032495,0.042402,-0.066939,0.034700,-1.009880,-0.957234,0.159669,0.156692,-0.112799,0.004503,0.045819,-0.026533,2.157808,0.103679,-0.123166,-0.070060,0.052905,0.022106,-0.025168,0.005217,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.335754,0.060298,-0.015303,-0.038818,0.041719,-0.013088,-0.006621,0.006143,-1.237187,-0.854759,0.237733,0.057399,-0.078725,0.039582,0.000569,-0.007553,2.175158,0.032559,-0.153785,-0.010490,0.059796,-0.009670,-0.016324,0.011123,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.322094,0.047692,-0.031079,-0.006508,0.022511,-0.015294,0.003679,0.000744,-1.435391,-0.729287,0.257323,0.002558,-0.032844,0.031023,-0.011730,0.000428,2.173743,-0.042828,-0.141469,0.039681,0.038487,-0.020133,0.002543,0.001934,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.312141,0.032063,-0.029677,0.007695,0.007249,-0.008912,0.004717,-0.001051,-1.601691,-0.601661,0.251093,-0.014504,-0.004828,0.014072,-0.010563,0.001735,2.154946,-0.104092,-0.100232,0.066644,0.016763,-0.014034,0.005514,-0.002132,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.305839,0.018972,-0.022325,0.010705,-0.000043,-0.003217,0.002783,-0.001082,-1.736647,-0.478920,0.240019,-0.013602,0.003807,0.000454,-0.007514,0.000941,2.123752,-0.140910,-0.045876,0.076067,0.003223,-0.008612,0.001528,-0.002923,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.302327,0.009766,-0.014674,0.009373,-0.002047,-0.000433,0.000877,-0.000609,-1.841575,-0.361256,0.230896,-0.011730,-0.002154,-0.009543,-0.006152,0.001542,2.086850,-0.149548,0.011067,0.073986,-0.007709,-0.010039,-0.003886,-0.001036,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.300664,0.004053,-0.008441,0.007246,-0.002099,0.000115,-0.000185,-0.000108,-1.917660,-0.248362,0.219471,-0.021560,-0.019008,-0.016461,-0.003952,0.006114,2.051270,-0.130845,0.061848,0.058647,-0.024467,-0.016858,-0.006210,0.004866,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.300074,0.001061,-0.003789,0.005147,-0.002187,-0.000271,-0.000382,0.000417,-1.966462,-0.144191,0.193495,-0.051255,-0.039946,-0.013779,0.006326,0.015494,2.023228,-0.090811,0.093760,0.022368,-0.048701,-0.019066,0.001726,0.016392,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.299973,-0.000011,-0.000805,0.002727,-0.002657,-0.000257,0.000338,0.001046,-1.991384,-0.059756,0.138609,-0.095717,-0.042764,0.016672,0.033862,0.025256,2.006527,-0.043115,0.089731,-0.035469,-0.061951,0.005952,0.030503,0.030766,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.299994,-0.000070,0.000246,0.000159,-0.002089,0.001648,0.002228,0.001488,-1.999296,-0.010504,0.055892,-0.114027,0.023634,0.100040,0.081449,0.017670,2.000575,-0.008425,0.043246,-0.079960,-0.009088,0.091985,0.087505,0.030810,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp2.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.050000,0.000000,0.000000,0.000000,-0.060696,0.043589,-0.012758,-0.000719,-0.500000,0.000000,0.000000,0.000000,0.048791,-0.090020,0.057520,-0.015756,2.865000,0.000000,0.000000,0.000000,-0.555496,0.656161,-0.332329,0.065456,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.050198,-0.003018,-0.016713,-0.037538,-0.018564,0.023824,-0.013237,0.004036,-0.499884,0.001601,0.007278,0.008350,-0.018425,-0.024226,0.029083,-0.012100,2.863394,-0.023738,-0.123916,-0.240299,-0.011056,0.244337,-0.209460,0.073350,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.052636,-0.019179,-0.048798,-0.044798,0.001013,0.009253,-0.005910,0.003867,-0.498988,0.005331,0.004302,-0.017783,-0.028060,0.003935,0.008044,-0.005516,2.846109,-0.127773,-0.280877,-0.154072,0.138110,0.024387,-0.080521,0.041468,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.061168,-0.051761,-0.080838,-0.039319,0.009154,0.005328,0.001018,0.001681,-0.497768,0.002509,-0.018584,-0.041623,-0.018616,0.009039,-0.001343,-0.001076,2.794749,-0.288392,-0.344696,-0.020213,0.115783,-0.043678,-0.009231,0.014123,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.079734,-0.098868,-0.105968,-0.026287,0.017687,0.008793,0.004225,-0.002581,-0.499017,-0.015585,-0.055472,-0.055157,-0.009165,0.005751,-0.003057,0.001148,2.701200,-0.458177,-0.323513,0.067318,0.060255,-0.039900,0.014301,-0.000416,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.111406,-0.155483,-0.117482,-0.002138,0.031227,0.011276,0.000058,-0.010004,-0.507273,-0.054139,-0.099533,-0.061526,-0.004214,0.002737,-0.000968,0.002164,2.567688,-0.604241,-0.255834,0.107047,0.023559,-0.019359,0.013004,-0.006211,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.157520,-0.212470,-0.105815,0.034787,0.039905,-0.002338,-0.017510,0.008295,-0.528004,-0.115654,-0.146843,-0.064036,-0.000516,0.004131,0.002940,0.003364,2.402387,-0.710927,-0.169104,0.121721,0.008155,-0.008126,0.001898,-0.001082,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.216558,-0.256495,-0.065982,0.068893,0.025103,-0.018088,-0.003535,0.002379,-0.567093,-0.201010,-0.194177,-0.060592,0.009244,0.012811,0.009210,0.001043,2.216012,-0.772296,-0.075936,0.125242,-0.000815,-0.006687,-0.000195,-0.000888,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.283649,-0.275369,-0.007882,0.081912,0.000481,-0.020275,0.000023,0.002260,-0.630377,-0.308576,-0.233591,-0.040320,0.034462,0.027472,0.011863,-0.007311,2.020139,-0.786966,0.016615,0.120065,-0.009843,-0.007998,-0.001989,0.001478,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.351722,-0.264314,0.050612,0.070037,-0.023606,-0.016925,0.003462,0.007697,-0.722586,-0.430184,-0.246071,0.014019,0.075925,0.034537,0.000135,-0.025265,1.826265,-0.756927,0.101637,0.104804,-0.020897,-0.008730,0.000327,0.006420,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.413650,-0.227648,0.092004,0.037987,-0.037308,-0.001098,0.016891,-0.009586,-0.844964,-0.545213,-0.202198,0.108118,0.105406,0.000069,-0.044052,0.018459,1.644934,-0.687921,0.171190,0.079431,-0.027992,0.000586,0.011575,-0.009226,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.464362,-0.176794,0.107125,0.003961,-0.028087,0.012076,0.000477,-0.002912,-0.991813,-0.619677,-0.083774,0.202325,0.074288,-0.042879,-0.013026,0.000979,1.484788,-0.589119,0.220846,0.054160,-0.021454,0.006164,-0.004384,-0.004057,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.501901,-0.124011,0.101418,-0.016828,-0.014137,0.009185,-0.004347,0.000512,-1.148562,-0.619898,0.088385,0.245877,0.009013,-0.061256,-0.013136,-0.000980,1.352078,-0.469794,0.254044,0.034634,-0.020078,-0.005428,-0.011650,0.000883,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.526875,-0.077186,0.084687,-0.026512,-0.006450,0.003437,-0.003350,0.002095,-1.294198,-0.530315,0.265811,0.212365,-0.080408,-0.081033,-0.017295,0.018366,1.250962,-0.337706,0.270978,0.007643,-0.037302,-0.021178,-0.010750,0.009901,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.541316,-0.040165,0.062768,-0.031575,-0.004149,0.001223,0.000351,0.003074,-1.407242,-0.364269,0.381633,0.078417,-0.187870,-0.080095,0.012415,0.062743,1.183423,-0.203575,0.258986,-0.044900,-0.068438,-0.023298,0.005866,0.026047,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.547942,-0.014930,0.037805,-0.034430,-0.000611,0.005791,0.005894,0.003148,-1.474037,-0.171876,0.359494,-0.147054,-0.242037,0.024448,0.122606,0.118851,1.147727,-0.087154,0.196884,-0.122505,-0.077817,0.020829,0.051941,0.043933,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.549845,-0.002368,0.013069,-0.029149,0.013875,0.018524,0.012019,-0.000439,-1.497720,-0.033430,0.171881,-0.319248,-0.031537,0.363886,0.343090,0.118051,1.136061,-0.015759,0.083023,-0.165065,0.020940,0.155725,0.134125,0.035714,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp3.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.050000,0.000000,0.000000,0.000000,-0.675389,0.879090,-0.473181,0.103356,-1.500000,0.000000,0.000000,0.000000,0.584666,-0.724336,0.378638,-0.079059,2.865000,0.000000,0.000000,0.000000,0.003689,-0.077488,0.064811,-0.022218,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.051889,-0.027638,-0.141519,-0.259696,0.036389,0.305225,-0.281821,0.101771,-1.498336,0.024478,0.126637,0.239471,-0.009016,-0.260665,0.231369,-0.082728,2.864953,-0.000941,-0.007382,-0.027526,-0.044562,-0.008838,0.025546,-0.012252,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.071324,-0.140332,-0.289380,-0.106697,0.209368,0.012978,-0.103531,0.053209,-1.480798,0.128257,0.273990,0.128532,-0.163181,-0.019786,0.086170,-0.044945,2.863649,-0.012622,-0.044872,-0.071303,-0.038360,0.013973,0.004534,-0.003173,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.125351,-0.292205,-0.293837,0.085703,0.157629,-0.074810,-0.012613,0.015977,-1.430240,0.279195,0.310232,-0.026232,-0.131708,0.052424,0.009051,-0.013816,2.856440,-0.050531,-0.110351,-0.099946,-0.018378,0.016883,-0.000520,0.001201,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.214888,-0.414710,-0.182550,0.194819,0.061029,-0.073682,0.013156,0.001261,-1.341923,0.422214,0.249606,-0.124236,-0.065249,0.048853,-0.013678,0.001903,2.835293,-0.125266,-0.189570,-0.107771,0.002895,0.017635,0.002107,0.000487,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.326761,-0.467002,-0.024266,0.214080,-0.018049,-0.052035,0.013802,0.005342,-1.222921,0.520522,0.138832,-0.162966,-0.015966,0.031079,-0.009429,0.005842,2.790473,-0.239720,-0.266424,-0.093129,0.027181,0.021027,0.003598,-0.006024,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.441800,-0.441049,0.122314,0.168553,-0.067232,-0.023350,0.022442,-0.010782,-1.086694,0.558946,0.015044,-0.161654,0.017239,0.024345,0.001523,-0.002296,2.712564,-0.388273,-0.322705,-0.052505,0.053543,0.017732,-0.006404,0.003643,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.542065,-0.352833,0.220962,0.092266,-0.081277,-0.002628,0.003478,0.007525,-0.948452,0.537716,-0.095886,-0.129038,0.047842,0.022904,-0.001790,-0.013761,2.594731,-0.555809,-0.339535,0.010616,0.071695,0.011836,0.000346,-0.012729,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.615340,-0.230150,0.259630,0.011462,-0.077186,0.013588,0.017035,-0.011296,-0.821824,0.468982,-0.171532,-0.069322,0.067269,0.001192,-0.025820,0.013041,2.435015,-0.718893,-0.303079,0.088077,0.079854,-0.005508,-0.022076,0.013054,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.656757,-0.102665,0.242171,-0.053452,-0.050407,0.025069,-0.001986,-0.003144,-0.716124,0.374316,-0.199357,-0.007594,0.051684,-0.021189,-0.003630,0.006010,2.238027,-0.849142,-0.208962,0.159375,0.059412,-0.022375,0.000103,0.002531,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.668295,0.005721,0.186916,-0.089242,-0.022653,0.018306,-0.006948,0.002344,-0.634942,0.276020,-0.189070,0.030535,0.025082,-0.019125,0.006321,-0.000046,2.015382,-0.920459,-0.070590,0.205180,0.032923,-0.019393,0.003962,-0.005353,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.656649,0.081351,0.113991,-0.102304,-0.005002,0.011037,-0.002521,0.003572,-0.577196,0.188441,-0.159382,0.045634,0.007077,-0.009815,0.005950,-0.001818,1.784172,-0.915590,0.092733,0.226489,0.009469,-0.020612,-0.006014,-0.007518,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.630795,0.119059,0.037037,-0.100708,0.008384,0.011816,0.004083,0.001523,-0.539315,0.117589,-0.123725,0.048187,-0.000608,-0.003269,0.002673,-0.001713,1.564624,-0.826616,0.262423,0.220168,-0.026045,-0.039094,-0.020338,-0.001039,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.600244,0.119476,-0.033233,-0.083454,0.027815,0.019517,0.007338,-0.005191,-0.516903,0.064672,-0.088202,0.046137,-0.003125,-0.001461,-0.000369,-0.000966,1.377667,-0.656635,0.410461,0.163191,-0.094548,-0.069535,-0.024262,0.021773,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.573627,0.089365,-0.082020,-0.041858,0.056251,0.022876,-0.001052,-0.018519,-0.505540,0.028994,-0.055042,0.041851,-0.005826,-0.003193,-0.002155,0.000449,1.241270,-0.428178,0.485558,0.020578,-0.192306,-0.074510,0.011574,0.067215,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.556825,0.044431,-0.089187,0.025830,0.073732,-0.004098,-0.033483,-0.035661,-0.501104,0.008882,-0.026454,0.033417,-0.011592,-0.005661,-0.001544,0.003229,1.164077,-0.194832,0.419292,-0.205490,-0.237834,0.034575,0.129881,0.122237,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.550614,0.008952,-0.045499,0.081662,0.017717,-0.101121,-0.099377,-0.037469,-0.500066,0.001081,-0.006648,0.018245,-0.018351,-0.003477,0.004014,0.007492,1.137508,-0.036935,0.191506,-0.364415,-0.006004,0.388950,0.357116,0.115030,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp4.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.550000,0.000000,0.000000,0.000000,-0.120958,0.175170,-0.100145,0.024070,-0.500000,0.000000,0.000000,0.000000,-0.206522,0.232409,-0.113584,0.020764,1.135000,0.000000,0.000000,0.000000,0.473198,-0.555078,0.279546,-0.054397,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.550324,-0.004684,-0.023363,-0.039481,0.017282,0.056444,-0.056064,0.021367,-0.500606,-0.008998,-0.047362,-0.093923,-0.011141,0.089662,-0.074207,0.025279,1.136371,0.020278,0.105982,0.206195,0.011676,-0.207832,0.177277,-0.061629,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.553462,-0.021878,-0.040521,-0.001521,0.046962,-0.000303,-0.018720,0.010416,-0.507256,-0.049627,-0.111802,-0.068759,0.045192,0.010867,-0.029699,0.014889,1.151169,0.109535,0.241657,0.134949,-0.115621,-0.021104,0.068925,-0.034959,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.561309,-0.039586,-0.024982,0.040826,0.034730,-0.015227,-0.000938,0.002185,-0.527544,-0.115531,-0.146161,-0.024020,0.039076,-0.014715,-0.004074,0.005675,1.195307,0.248372,0.299535,0.022897,-0.096502,0.037824,0.008855,-0.012185,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.572008,-0.042551,0.016272,0.066045,0.016012,-0.014007,0.002471,-0.001660,-0.565799,-0.190975,-0.151944,0.005361,0.019966,-0.013680,0.005451,0.000847,1.276140,0.397171,0.286698,-0.048864,-0.047584,0.035834,-0.011404,-0.000700,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.580548,-0.021293,0.069732,0.073847,-0.000088,-0.012478,-0.000805,-0.001630,-0.622890,-0.264928,-0.142236,0.018597,0.008440,-0.004524,0.006801,-0.001260,1.392434,0.529016,0.237123,-0.077711,-0.013866,0.018027,-0.012096,0.002777,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.580372,0.027163,0.123054,0.065486,-0.017331,-0.015562,-0.004124,0.002544,-0.697691,-0.332082,-0.125458,0.026162,0.008472,0.003894,0.004716,-0.003340,1.538255,0.632426,0.175805,-0.083711,-0.001154,0.003551,-0.007133,0.003157,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.564951,0.099562,0.163049,0.037488,-0.039259,-0.017823,-0.000221,0.011877,-0.788106,-0.389278,-0.101844,0.038085,0.015934,0.006346,-0.000931,-0.007116,1.706039,0.704593,0.112790,-0.084443,-0.001677,-0.002979,-0.001702,0.003582,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.529454,0.185333,0.173889,-0.011356,-0.055250,-0.001771,0.020487,-0.010558,-0.891128,-0.431957,-0.066514,0.056721,0.019103,-0.004656,-0.013505,0.012034,1.887907,0.744989,0.048338,-0.088024,-0.005038,-0.000764,0.004555,-0.004039,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.472643,0.266762,0.145360,-0.062754,-0.044032,0.015755,0.002480,-0.003643,-1.002321,-0.453535,-0.018082,0.070339,0.007203,-0.009238,0.007273,-0.003002,2.075781,0.752343,-0.019505,-0.092668,-0.003931,0.000830,-0.002489,0.002181,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.398005,0.325240,0.084315,-0.096662,-0.024005,0.015055,-0.003452,0.002113,-1.115715,-0.449080,0.036295,0.073630,0.000832,-0.002283,0.001955,-0.003225,2.261184,0.724975,-0.090452,-0.096561,-0.004035,0.000017,0.001325,0.003119,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.313015,0.348051,0.005011,-0.112047,-0.007266,0.012759,0.000624,0.003833,-1.224564,-0.417113,0.091521,0.073205,-0.001952,-0.003550,-0.003793,-0.002707,2.435251,0.661405,-0.164241,-0.099744,-0.001065,0.006108,0.006963,0.003270,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.227455,0.329353,-0.079640,-0.110619,0.011364,0.018549,0.007885,0.001021,-1.321991,-0.357845,0.144860,0.067479,-0.011426,-0.012615,-0.008908,0.000136,2.588782,0.560682,-0.238019,-0.094369,0.014885,0.020610,0.013302,-0.000458,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.151759,0.269912,-0.154962,-0.085059,0.042501,0.031075,0.010613,-0.009229,-1.401403,-0.273775,0.188695,0.045404,-0.035471,-0.025260,-0.009435,0.008700,2.712683,0.425388,-0.299224,-0.062508,0.052869,0.039162,0.013687,-0.013216,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.095096,0.179792,-0.197530,-0.021081,0.086247,0.033606,-0.004515,-0.029619,-1.457509,-0.173665,0.205124,-0.007614,-0.071134,-0.026944,0.004970,0.025498,2.799599,0.268183,-0.319629,0.017308,0.107426,0.040763,-0.008199,-0.038574,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.062457,0.083044,-0.176620,0.080709,0.107824,-0.013632,-0.056600,-0.054592,-1.488526,-0.077430,0.169343,-0.090549,-0.086210,0.015247,0.049916,0.045408,2.847394,0.119010,-0.261265,0.142375,0.129598,-0.024071,-0.076224,-0.068488,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.051083,0.015915,-0.082220,0.154862,0.007867,-0.169871,-0.157961,-0.052642,-1.499021,-0.014457,0.075340,-0.145423,0.004476,0.149285,0.134482,0.041093,2.863502,0.022139,-0.115517,0.223745,-0.009405,-0.227602,-0.203854,-0.061325,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp5.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.550000,0.000000,0.000000,0.000000,0.269437,-0.337244,0.177199,-0.037339,-1.500000,0.000000,0.000000,0.000000,0.202310,-0.229737,0.112890,-0.020900,1.135000,0.000000,0.000000,0.000000,0.111282,-0.084255,0.025820,0.001354,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.549236,0.011227,0.057962,0.108929,-0.006414,-0.120662,0.107726,-0.038520,-1.499408,0.008783,0.046156,0.091144,0.009542,-0.088184,0.073322,-0.025013,1.135359,0.005463,0.030106,0.066876,0.030910,-0.044285,0.026736,-0.006671,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.541223,0.058440,0.123922,0.055500,-0.077314,-0.008491,0.040138,-0.020611,-1.492936,0.048211,0.108097,0.065065,-0.045628,-0.010361,0.029294,-0.014515,1.139735,0.034268,0.086365,0.077551,-0.003029,-0.012898,0.014700,-0.006137,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.518303,0.126010,0.137157,-0.017396,-0.061570,0.025574,0.004818,-0.006068,-1.473292,0.111552,0.139584,0.020131,-0.039054,0.015104,0.004335,-0.005310,1.154890,0.091626,0.142113,0.070216,-0.008727,0.001222,0.003996,-0.004127,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.478715,0.187995,0.105175,-0.062306,-0.028404,0.025265,-0.005050,0.000763,-1.436503,0.182989,0.142543,-0.008854,-0.019013,0.014926,-0.004513,-0.000722,1.187743,0.175342,0.191843,0.062937,-0.005710,0.001886,-0.003169,-0.002723,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.426203,0.227590,0.051461,-0.076394,-0.001140,0.018711,-0.003159,0.001084,-1.382046,0.251676,0.130826,-0.020047,-0.004982,0.007288,-0.005560,0.000545,1.244531,0.282721,0.236958,0.057043,-0.007813,-0.006317,-0.008123,-0.000748,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.367270,0.239274,-0.003501,-0.066678,0.019880,0.015100,-0.000807,-0.003622,-1.311277,0.313129,0.114746,-0.022137,-0.000786,-0.000321,-0.004616,0.000800,1.330874,0.411235,0.275332,0.042642,-0.023734,-0.019122,-0.010009,0.005033,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.308620,0.226548,-0.043817,-0.038108,0.036017,0.008603,-0.006870,-0.012087,-1.226173,0.366271,0.097545,-0.024457,-0.005077,-0.006116,-0.003400,0.002055,1.451444,0.554989,0.294942,0.004516,-0.054268,-0.026718,-0.002025,0.017960,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.255171,0.199852,-0.058198,-0.000514,0.033721,-0.018027,-0.028563,0.028291,-1.128918,0.410004,0.076186,-0.034138,-0.014787,-0.008299,-0.000060,0.004901,1.608458,0.699412,0.274054,-0.064627,-0.079742,-0.005036,0.029237,-0.014465,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.208744,0.172293,-0.049848,0.016882,-0.000119,-0.023768,0.020224,-0.006835,-1.022254,0.440618,0.043837,-0.053461,-0.022537,-0.001632,0.008464,-0.003777,1.799119,0.819386,0.196309,-0.140358,-0.066538,0.020821,0.004542,-0.004906,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.168542,0.150169,-0.039900,0.007294,-0.014607,-0.002191,0.008204,-0.003477,-0.910283,0.451115,-0.004546,-0.074889,-0.018707,0.006384,0.002043,0.000638,2.013803,0.887490,0.069508,-0.193135,-0.038938,0.021777,-0.003404,0.004399,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.133437,0.130673,-0.039841,-0.006594,-0.011556,0.005722,0.002289,-0.000765,-0.799025,0.433769,-0.066598,-0.088880,-0.008463,0.010409,0.003467,0.002599,2.236871,0.884010,-0.086652,-0.218925,-0.012502,0.022627,0.004963,0.007301,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.103400,0.108918,-0.048107,-0.013963,-0.002676,0.008190,0.001194,-0.000145,-0.696155,0.383504,-0.134549,-0.089399,0.009219,0.018875,0.008578,0.000286,2.449012,0.799338,-0.251558,-0.214736,0.024427,0.039273,0.018912,0.001228,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.079398,0.082246,-0.058236,-0.011167,0.008601,0.009661,0.001232,-0.002205,-0.610029,0.300463,-0.194683,-0.065664,0.041011,0.031497,0.010032,-0.009601,2.629907,0.635703,-0.396180,-0.159686,0.091920,0.067862,0.023115,-0.020943,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.062608,0.051763,-0.061850,0.003556,0.020627,0.008311,-0.002374,-0.007062,-0.547914,0.194030,-0.223240,-0.003145,0.084537,0.032695,-0.005775,-0.029567,2.762006,0.414841,-0.469946,-0.020992,0.186964,0.072284,-0.011336,-0.065122,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.053389,0.022931,-0.050433,0.027670,0.024928,-0.004885,-0.014840,-0.012813,-0.513049,0.087658,-0.189733,0.095979,0.103823,-0.016303,-0.057849,-0.053571,2.836811,0.188852,-0.406284,0.198704,0.231078,-0.033598,-0.125962,-0.118583,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.050288,0.004256,-0.022228,0.043156,-0.002098,-0.043825,-0.038758,-0.011377,-0.501121,0.016528,-0.085851,0.164210,-0.000087,-0.172959,-0.157517,-0.049742,2.862568,0.035812,-0.185664,0.353208,0.006142,-0.377329,-0.346405,-0.111667,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/swap6v_pps/pp6.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n0.250000,-3.300000,0.000000,0.000000,0.000000,0.371339,-0.482492,0.259857,-0.057039,-2.000000,0.000000,0.000000,0.000000,0.805862,-0.977830,0.504158,-0.102597,2.000000,0.000000,0.000000,0.000000,0.048944,-0.063808,0.034422,-0.007578,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.298961,0.015210,0.077919,0.143189,-0.019353,-0.167717,0.154278,-0.056310,-1.997690,0.034047,0.176849,0.338240,0.000114,-0.357138,0.312422,-0.110472,2.000137,0.002002,0.010246,0.018785,-0.002689,-0.022138,0.020400,-0.007450,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.288256,0.077340,0.159733,0.059526,-0.115157,-0.008506,0.055590,-0.029580,-1.973119,0.180565,0.390809,0.197671,-0.213827,-0.030350,0.118413,-0.061034,2.001543,0.010153,0.020909,0.007616,-0.015311,-0.001090,0.007344,-0.003896,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.258454,0.161279,0.162515,-0.047620,-0.089851,0.037383,0.004920,-0.008324,-1.901304,0.399665,0.459822,-0.006465,-0.174130,0.069735,0.013648,-0.019904,2.005448,0.021094,0.021060,-0.006613,-0.011919,0.004989,0.000673,-0.001077,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.209035,0.228737,0.099064,-0.113707,-0.043062,0.034487,-0.008626,0.002044,-1.773359,0.618889,0.400962,-0.135466,-0.085051,0.065369,-0.019244,0.000607,2.011893,0.029739,0.012428,-0.015351,-0.005640,0.004670,-0.001073,0.000281,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.147572,0.254884,0.002561,-0.137631,-0.006922,0.024340,-0.004326,0.003758,-1.595967,0.789819,0.276567,-0.185592,-0.021048,0.037630,-0.017067,0.005867,2.019847,0.032807,-0.000528,-0.018369,-0.000655,0.003439,-0.000480,0.000444,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.085846,0.230383,-0.099632,-0.130179,0.021502,0.022460,0.002923,-0.001388,-1.384176,0.892633,0.134480,-0.187653,0.013198,0.019540,-0.006217,0.002829,2.027729,0.029123,-0.014032,-0.016964,0.003437,0.003251,0.000395,-0.000377,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.036405,0.157955,-0.185550,-0.093916,0.051558,0.024252,0.001238,-0.013657,-1.155475,0.925863,0.001436,-0.163799,0.033341,0.013431,-0.000856,-0.005079,2.033885,0.019206,-0.024943,-0.011423,0.007666,0.003235,-0.000165,-0.002197,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.009756,0.051251,-0.233071,-0.028681,0.075565,0.007090,-0.022430,0.007129,-0.926336,0.898202,-0.106966,-0.123026,0.046549,0.004799,-0.009587,-0.000668,2.036981,0.005130,-0.030185,-0.002088,0.010353,-0.000044,-0.004008,0.002234,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.011661,-0.065920,-0.226305,0.045281,0.067298,-0.018188,-0.010492,0.008675,-0.710209,0.824597,-0.181605,-0.076564,0.043195,-0.011087,-0.011082,0.008950,2.036384,-0.009728,-0.028065,0.007291,0.007762,-0.003240,-0.000195,0.000635,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.041334,-0.166778,-0.170386,0.099119,0.039471,-0.023133,0.004004,-0.000769,-0.516451,0.721872,-0.225028,-0.042538,0.023841,-0.016323,0.004092,0.003217,2.032339,-0.021971,-0.020190,0.013054,0.003877,-0.002757,0.000835,-0.000299,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.091997,-0.231349,-0.084641,0.125278,0.013888,-0.018346,0.002116,-0.004103,-0.350633,0.602583,-0.250236,-0.027180,0.009033,-0.006105,0.009542,0.000929,2.025801,-0.029426,-0.009334,0.015428,0.001050,-0.001912,0.000256,-0.000553,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.153130,-0.249665,0.011699,0.127800,-0.009305,-0.020414,-0.005673,-0.001814,-0.216020,0.472872,-0.267610,-0.018854,0.010855,0.009255,0.011446,-0.001817,2.018105,-0.031171,0.002336,0.015288,-0.001402,-0.002232,-0.000778,-0.000208,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.212876,-0.220869,0.100500,0.103715,-0.041133,-0.030683,-0.009775,0.008099,-0.114768,0.336455,-0.275600,0.001114,0.032161,0.023553,0.008982,-0.009587,2.010689,-0.027273,0.012878,0.012219,-0.005036,-0.003596,-0.001251,0.001006,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.260384,-0.154386,0.157661,0.041458,-0.084223,-0.033471,0.003380,0.028026,-0.047712,0.201370,-0.258694,0.049492,0.064780,0.023489,-0.007079,-0.024846,2.004843,-0.018933,0.019539,0.004682,-0.010154,-0.004003,0.000387,0.003409,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.288838,-0.073633,0.152713,-0.058796,-0.107565,0.009972,0.052574,0.052988,-0.012492,0.085727,-0.194537,0.123343,0.073917,-0.020824,-0.051057,-0.041814,2.001361,-0.008991,0.018709,-0.007387,-0.012931,0.001243,0.006372,0.006409,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.250000,-3.299015,-0.014430,0.074005,-0.136454,-0.016833,0.158221,0.150742,0.053343,-0.001038,0.015428,-0.081413,0.162574,-0.022845,-0.151597,-0.129387,-0.033257,2.000120,-0.001757,0.009019,-0.016674,-0.001899,0.019190,0.018247,0.006419,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/takeoff.csv",
    "content": "Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7\n1.15839,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1.06614,-1.57474,0.868105,-0.172428,0,0,0,0,0,0,0,0\n1.13522,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.25,0.399333,3.03717e-14,-0.0697493,0.0551273,-0.643041,0.742072,-0.234074,0,0,0,0,0,0,0,0\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_collisionAvoidance.py",
    "content": "import sys\n\nimport numpy as np\nimport pytest\n\nfrom pycrazyswarm import *\nfrom pycrazyswarm.util import *\n\n\nRADII = np.array([0.125, 0.125, 0.375])\nZ = 1.0\n\n\ndef setUp(args):\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - id: 1\n      channel: 100\n      initialPosition: [-1.0, 0.0, 0.0]\n    - id: 2\n      channel: 100\n      initialPosition: [1.0, 0.0, 0.0]\n    \"\"\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=args)\n    timeHelper = swarm.timeHelper\n    return swarm.allcfs, timeHelper\n\n\ndef test_velocityMode_sidestepWorstCase(args=None):\n    if args is None:\n        args = \"--sim --vis null --dt 0.05 --maxvel 1.0\"\n\n    allcfs, timeHelper = setUp(args)\n    a, b = allcfs.crazyflies\n\n    a.enableCollisionAvoidance([b], RADII)\n    b.enableCollisionAvoidance([a], RADII)\n\n    a.cmdVelocityWorld([1.0, 0.0, 0.0], yawRate=0.0)\n    b.cmdVelocityWorld([-1.0, 0.0, 0.0], yawRate=0.0)\n\n    while timeHelper.time() < 10.0:\n        positions = np.stack([a.position(), b.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        assert not np.any(collisions)\n\n        timeHelper.sleep(timeHelper.dt)\n        if a.position()[0] > 1.0 and b.position()[0] < -1.0:\n            return\n    assert False\n\n\ndef test_goToWithoutCA_CheckCollision():\n    args = \"--sim --vis null\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n\n    cf0.goTo([1.0, 0.0, 1.0], 0, 5.0)\n    cf1.goTo([-1.0, 0.0, 1.0], 0, 5.0)\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        if np.any(collisions):\n            return\n        timeHelper.sleep(timeHelper.dt)\n    assert False\n\n\ndef test_goToWithCA_CheckCollision():\n    args = \"--sim --vis null\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    cf0.enableCollisionAvoidance([cf1], RADII)\n    cf1.enableCollisionAvoidance([cf0], RADII)\n\n    cf0.goTo([1.0, 0.0, 1.0], 0, 5.0)\n    cf1.goTo([-1.0, 0.0, 1.0], 0, 5.0)\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        assert not np.any(collisions)\n        timeHelper.sleep(timeHelper.dt)\n\n\ndef test_goToWithCA_CheckDestination():\n    args = \"--sim --vis null\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    cf0.enableCollisionAvoidance([cf1], RADII)\n    cf1.enableCollisionAvoidance([cf0], RADII)\n\n    goal0 = [1.0, 0.0, 1.0]\n    goal1 = [-1.0, 0.0, 1.0]\n    cf0.goTo(goal0, 0, 5.0)\n    cf1.goTo(goal1, 0, 5.0)\n    timeHelper.sleep(5)\n    assert np.all(np.isclose(cf0.position(), goal0))\n    assert np.all(np.isclose(cf1.position(), goal1))\n\n\ndef test_goToWithCA_changeEllipsoid():\n    args = \"--sim --vis null\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n\n    newRADII = np.array([0.1, 0.1, 0.3])\n    cf0.enableCollisionAvoidance([cf1], newRADII)\n    cf1.enableCollisionAvoidance([cf0], newRADII)\n\n    goal0 = [1.0, 0.0, 1.0]\n    goal1 = [-1.0, 0.0, 1.0]\n    cf0.goTo(goal0, 0, 5.0)\n    cf1.goTo(goal1, 0, 5.0)\n\n    # flag if a collision happened during sleep\n    collisionHappend = False\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisionsOld = check_ellipsoid_collisions(positions, RADII)\n        collisionsNew = check_ellipsoid_collisions(positions, newRADII)\n        if np.any(collisionsOld):\n            collisionHappend = True\n        assert not np.any(collisionsNew)\n\n        timeHelper.sleep(timeHelper.dt)\n    assert collisionHappend\n\n\ndef test_goToWithCA_Intersection():\n    args = \"--sim --vis null --dt 0.01\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    cf0.enableCollisionAvoidance([cf1], RADII)\n    cf1.enableCollisionAvoidance([cf0], RADII)\n\n    goal0 = [1.0, 1.0, 1.0]\n    goal1 = [-1.0, 1.0, 1.0]\n    cf0.goTo(goal0, 0, 5.0)\n    cf1.goTo(goal1, 0, 5.0)\n\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        assert not np.any(collisions)\n\n        timeHelper.sleep(timeHelper.dt)\n    assert np.all(np.isclose(cf0.position(), goal0))\n    assert np.all(np.isclose(cf1.position(), goal1))\n\n\ndef test_goToWithoutCA_Intersection():\n    args = \"--sim --vis null --dt 0.05\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n\n    goal0 = [1.0, 1.0, 1.0]\n    goal1 = [-1.0, 1.0, 1.0]\n    cf0.goTo(goal0, 0, 5.0)\n    cf1.goTo(goal1, 0, 5.0)\n\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        if np.any(collisions):\n            return\n\n        timeHelper.sleep(timeHelper.dt)\n    assert False\n\n\ndef test_goToWithCA_random():\n    rows, cols = 3, 5\n    N = rows * cols\n    crazyflies_yaml = grid_yaml(rows, cols, spacing=0.5)\n\n    args = \"--sim --vis null\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=args)\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n\n    cfs = allcfs.crazyflies\n\n    for _, cf in enumerate(cfs):\n        cf.enableCollisionAvoidance(cfs, RADII)\n\n    np.random.seed(0)\n    xy_radius = 0.125\n    for _ in range(5):\n        lastTime = timeHelper.time()\n        goals = poisson_disk_sample(N, dim=2, mindist=5*xy_radius)\n        goals_z = Z * np.ones(N) + 0.2 * np.random.uniform(-1.0, 1.0, size=N)\n        goals = np.hstack([goals, goals_z[:, None]])\n\n        for goal, cf in zip(goals, cfs):\n            cf.goTo(goal, yaw=0.0, duration=5)\n        while timeHelper.time() - lastTime < 20.0:\n            positions = np.stack([cf.position() for cf in cfs])\n            timeHelper.sleep(timeHelper.dt)\n            collisions = check_ellipsoid_collisions(positions, RADII)\n            assert not np.any(collisions)\n        for goal, cf in zip(goals, cfs):\n            assert np.all(np.isclose(cf.position(), goal, atol=1e-4))\n\n\ndef test_cmdPosition():\n    args = \"--sim --vis null --maxvel 1.0\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    cf0.enableCollisionAvoidance([cf1], RADII)\n    cf1.enableCollisionAvoidance([cf0], RADII)\n\n    goal0 = np.array([1.0, 0.0, 2.0])\n    goal1 = np.array([-1.0, 0.0, 2.0])\n    cf0.cmdPosition(goal0, yaw=0.0)\n    cf1.cmdPosition(goal1, yaw=0.0)\n    while timeHelper.time() < 10.0:\n        positions = np.stack([cf0.position(), cf1.position()])\n        collisions = check_ellipsoid_collisions(positions, RADII)\n        assert not np.any(collisions)\n\n        timeHelper.sleep(timeHelper.dt)\n    assert np.all(np.isclose(cf0.position(), goal0))\n    assert np.all(np.isclose(cf1.position(), goal1))\n\n\ndef test_boundingBox():\n    args = \"--sim --vis null --maxvel 1.0\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    BBOXMAX = [5, 5, 5]\n    BBOXMIN = [-3, -3, -3]\n    cf0.enableCollisionAvoidance(\n        [cf1], RADII, bboxMax=BBOXMAX, bboxMin=BBOXMIN)\n    cf1.enableCollisionAvoidance(\n        [cf0], RADII, bboxMax=BBOXMAX, bboxMin=BBOXMIN)\n\n    goal0 = np.array([BBOXMAX[0] - 1, 0.0, Z])\n    goal1 = np.array([BBOXMIN[0] - 1, 0.0, Z])\n    cf0.cmdPosition(goal0, yaw=0.0)\n    cf1.cmdPosition(goal1, yaw=0.0)\n    while timeHelper.time() < 10.0:\n        assert np.all(cf1.position() >= BBOXMIN)\n        assert np.all(cf1.position() <= BBOXMAX)\n        timeHelper.sleep(timeHelper.dt)\n\n    assert np.all(np.isclose(cf0.position(), goal0))\n    assert not np.all(np.isclose(cf1.position(), goal1))\n\n\n#@pytest.mark.xfail(reason=\"Bug in firmware\")\ndef test_maxSpeed_zero():\n    args = \"--sim --vis null --maxvel 1.0\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n    cf0.enableCollisionAvoidance([cf1], RADII, maxSpeed=0.0)\n    cf1.enableCollisionAvoidance([cf0], RADII, maxSpeed=0.0)\n\n    goal0 = np.array([1.0, 0.0, Z])\n    goal1 = np.array([-1.0, 0.0, Z])\n    cf0.cmdPosition(goal0, yaw=0.0)\n    cf1.cmdPosition(goal1, yaw=0.0)\n    while timeHelper.time() < 10.0:\n        timeHelper.sleep(timeHelper.dt)\n        assert np.all(cf0.velocity() == np.zeros(3))\n        assert np.all(cf1.velocity() == np.zeros(3))\n\n    assert np.all(np.isclose(cf0.position(), goal1))\n    assert np.all(np.isclose(cf1.position(), goal0))\n\n\ndef test_maxSpeed_limit():\n    args = \"--sim --vis null --maxvel 1.0\"\n    allcfs, timeHelper = setUp(args)\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    cf0, cf1 = allcfs.crazyflies\n\n    cf0.enableCollisionAvoidance([cf1], RADII, maxSpeed=1.0)\n    cf1.enableCollisionAvoidance([cf0], RADII, maxSpeed=3.0)\n\n    cf0.cmdVelocityWorld([2.0, 0.0, 0.0], yawRate=0.0)\n    cf1.cmdVelocityWorld([-2.0, 0.0, 0.0], yawRate=0.0)\n\n    while timeHelper.time() < 10.0:\n        assert np.all(np.abs(cf0.velocity()) < 1.2 * np.ones(3))\n        assert np.all(np.abs(cf1.velocity()) < 3.2 * np.ones(3))\n        timeHelper.sleep(timeHelper.dt)\n        if cf0.position()[0] > 2.0 and cf1.position()[0] < -2.0:\n            return\n\n    assert False\n\n\nif __name__ == \"__main__\":\n    # test_velocityMode_sidestepWorstCase(sys.argv)\n    test_maxSpeed_limit()\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_highLevel.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\nfrom pycrazyswarm import *\nimport uav_trajectory\n\nZ = 1.0\n\ndef setUp():\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - channel: 100\n      id: 1\n      initialPosition: [1.0, 0.0, 0.0]\n    - channel: 100\n      id: 10\n      initialPosition: [0.0, -1.0, 0.0]\n    \"\"\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=\"--sim --vis null\")\n    timeHelper = swarm.timeHelper\n    return swarm.allcfs, timeHelper\n\ndef _collectRelativePositions(timeHelper, cf, duration):\n    t0 = timeHelper.time()\n    positions = []\n    while timeHelper.time() - t0 < duration:\n        positions.append(cf.position() - cf.initialPosition)\n        timeHelper.sleep(timeHelper.dt + 1e-6)\n    return np.stack(positions)\n\n\ndef test_takeOff():\n    allcfs, timeHelper = setUp()\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n\n    for cf in allcfs.crazyflies:\n        pos = cf.initialPosition + np.array([0, 0, Z])\n        assert np.all(np.isclose(cf.position(), pos, atol=0.0001))\n\ndef test_goTo_nonRelative():\n    allcfs, timeHelper = setUp()\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n    \n    for cf in allcfs.crazyflies:\n        pos = np.array(cf.initialPosition) + np.array([1, 1, Z])\n        cf.goTo(pos, 0, 1.0)\n    timeHelper.sleep(1.0)\n\n    for cf in allcfs.crazyflies:\n        pos = cf.initialPosition + np.array([1, 1, Z])\n        assert np.all(np.isclose(cf.position(), pos))\n\ndef test_goTo_relative():\n    allcfs, timeHelper = setUp()\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n\n    allcfs.goTo(np.array([1.0,1.0,1.0]), 0, Z)\n    timeHelper.sleep(2.0)\n\n    for cf in allcfs.crazyflies:\n        pos = cf.initialPosition + np.array([1.0,1.0,2*Z])\n        assert np.all(np.isclose(cf.position(), pos))\n\ndef test_landing():\n    allcfs, timeHelper = setUp()\n    allcfs.takeoff(targetHeight=Z, duration=1.0+Z)\n    timeHelper.sleep(1.5+Z)\n\n    allcfs.land(targetHeight=0.02, duration=1.0+Z)\n    timeHelper.sleep(1.0+Z)\n\n    for cf in allcfs.crazyflies:\n        pos = cf.initialPosition + np.array([0, 0, 0.02])\n        assert np.all(np.isclose(cf.position(), pos, atol=0.0001))\n\ndef test_uploadTrajectory_timescale():\n    allcfs, timeHelper = setUp()\n    cf = allcfs.crazyflies[0]\n\n    traj = uav_trajectory.Trajectory()\n    traj.loadcsv(\"figure8.csv\")\n    trajId = 100\n    cf.uploadTrajectory(trajectoryId=trajId, pieceOffset=0, trajectory=traj)\n\n    # We know the traj isn't close to origin at 3/4 of its duration\n    cf.startTrajectory(trajId)\n    timeHelper.sleep(0.75 * traj.duration)\n    assert np.linalg.norm(cf.position() - cf.initialPosition) >= 0.5\n\n    # Make sure we're back at origin\n    timeHelper.sleep(traj.duration)\n\n    # Speeding up time by 2x, we should finish the trajectory in less time\n    cf.startTrajectory(trajId, timescale=0.5)\n    timeHelper.sleep(0.75 * traj.duration)\n    assert np.linalg.norm(cf.position() - cf.initialPosition) <= 0.001\n\ndef test_uploadTrajectory_fig8Bounds():\n    allcfs, timeHelper = setUp()\n    cf = allcfs.crazyflies[0]\n\n    traj = uav_trajectory.Trajectory()\n    traj.loadcsv(\"figure8.csv\")\n\n    trajId = 100\n    cf.uploadTrajectory(trajectoryId=trajId, pieceOffset=0, trajectory=traj)\n    cf.startTrajectory(trajId)\n    positions = _collectRelativePositions(timeHelper, cf, traj.duration)\n\n    # We know the approximate range the bounding box should lie in by plotting\n    # the trajectory.\n    xs, ys, _ = positions.T\n    assert 0.9 < np.amax(xs) < 1.1\n    assert -0.9 > np.amin(xs) > -1.1\n    assert 0.4 < np.amax(ys) < 0.6\n    assert -0.4 > np.amin(ys) > -0.6\n\ndef test_uploadTrajectory_reverse():\n    allcfs, timeHelper = setUp()\n    cf = allcfs.crazyflies[0]\n\n    traj = uav_trajectory.Trajectory()\n    traj.loadcsv(\"figure8.csv\")\n    trajId = 100\n    cf.uploadTrajectory(trajectoryId=trajId, pieceOffset=0, trajectory=traj)\n\n    cf.startTrajectory(trajId)\n    positions = _collectRelativePositions(timeHelper, cf, traj.duration)\n\n    cf.startTrajectory(trajId, reverse=True)\n    positionsReverse = _collectRelativePositions(timeHelper, cf, traj.duration)\n    positions2 = np.flipud(positionsReverse)\n\n    # The distance threshold must be large because the trajectory is not\n    # symmetrical, not because time/reversing is super sloppy.\n    dists = np.linalg.norm(positions - positions2, axis=1)\n    assert not np.any(dists > 0.2)\n\ndef test_uploadTrajectory_broadcast():\n    allcfs, timeHelper = setUp()\n    cf0, cf1 = allcfs.crazyflies\n\n    relativeInitial = cf1.initialPosition - cf0.initialPosition\n\n    traj = uav_trajectory.Trajectory()\n    traj.loadcsv(\"figure8.csv\")\n    trajId = 100\n    for cf in (cf0, cf1):\n        cf.uploadTrajectory(trajectoryId=trajId, pieceOffset=0, trajectory=traj)\n\n    allcfs.startTrajectory(trajId)\n    t0 = timeHelper.time()\n    while timeHelper.time() - t0 < traj.duration:\n        relative = cf1.position() - cf0.position()\n        assert np.all(np.isclose(relativeInitial, relative))\n        timeHelper.sleep(timeHelper.dt + 1e-6)\n\ndef test_setGroupMask():\n    allcfs, timeHelper = setUp()\n    cf0, cf1 = allcfs.crazyflies\n    cf0.setGroupMask(1)\n    cf1.setGroupMask(2)\n    allcfs.takeoff(targetHeight=Z, duration=1.0 + Z, groupMask = 1)\n    timeHelper.sleep(1.5+Z)\n    \n    pos0 = cf0.initialPosition + np.array([0, 0, Z])\n    assert np.all(np.isclose(cf0.position(), pos0, atol=0.0001)) \n    assert np.all(np.isclose(cf1.position(), cf1.initialPosition, atol=0.0001)) \n\n    allcfs.takeoff(targetHeight=Z, duration=1.0 + Z, groupMask = 2)\n    timeHelper.sleep(1.5+Z)\n\n    pos1 = cf1.initialPosition + np.array([0, 0, Z])\n    assert np.all(np.isclose(cf0.position(), pos0, atol=0.0001)) \n    assert np.all(np.isclose(cf1.position(), pos1, atol=0.0001)) "
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_lowLevel.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\nfrom pycrazyswarm import *\n\nZ = 1.0\n\ndef setUp(extra_args=\"\"):\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - channel: 100\n      id: 1\n      initialPosition: [1.0, 0.0, 0.0]\n    \"\"\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=\"--sim --vis null \" + extra_args)\n    timeHelper = swarm.timeHelper\n    return swarm.allcfs, timeHelper\n\ndef test_cmdFullState_zeroVel():\n    allcfs, timeHelper = setUp()\n    cf = allcfs.crazyflies[0]\n\n    pos = np.array(cf.initialPosition) + np.array([1, 1, Z])\n    cf.cmdFullState(pos, np.zeros(3), np.zeros(3), 0, np.zeros(3))\n    timeHelper.sleep(1.0)\n\n    assert np.all(np.isclose(cf.position(), pos))\n\ndef test_cmdPosition():\n    allcfs, timeHelper = setUp()\n    cf = allcfs.crazyflies[0]\n\n    pos = np.array(cf.initialPosition) + np.array([1, 1, Z])\n    cf.cmdPosition(pos,yaw=0.0)\n    timeHelper.sleep(1.0)\n\n    assert np.all(np.isclose(cf.position(), pos))\n\ndef test_cmdVelocityWorld_checkVelocity():\n    allcfs, timeHelper = setUp()\n    \n    cf = allcfs.crazyflies[0]\n    vel = np.ones(3)\n    cf.cmdVelocityWorld(vel, yawRate=0)\n    timeHelper.sleep(1.0)\n\n    assert np.all(np.isclose(cf.velocity(), vel))\n    \ndef test_cmdVelocityWorld_checkIntegrate():\n    allcfs, timeHelper = setUp()\n\n    cf = allcfs.crazyflies[0]\n    vel = np.ones(3)\n    cf.cmdVelocityWorld(vel, yawRate=0)\n    timeHelper.sleep(1.0)\n\n    pos = cf.initialPosition + vel\n    assert np.all(np.isclose(cf.position(), pos))\n\ndef test_cmdVelocityWorld_disturbance():\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - channel: 100\n      id: 1\n      initialPosition: [1.0, 0.0, 0.0]\n    \"\"\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=\"--sim --vis null --disturbance 1.0\")\n    timeHelper = swarm.timeHelper\n\n    cf = swarm.allcfs.crazyflies[0]\n\n    vel = np.ones(3)\n    cf.cmdVelocityWorld(vel, yawRate=0)\n    timeHelper.sleep(1.0)\n\n    pos = cf.initialPosition + vel\n    assert not np.any(np.isclose(cf.position(), pos))\n\ndef test_sleepResidual():\n    \"\"\"Verify TimeHelper's time() is consistent with its integration steps.\"\"\"\n    np.random.seed(0)\n    TRIALS = 100\n    for _ in range(TRIALS):\n        dtTick = 10 ** np.random.uniform(-2, 0)\n        dtSleep = 10 ** np.random.uniform(-2, 0)\n        allcfs, timeHelper = setUp(\"--dt {}\".format(dtTick))\n\n        cf = allcfs.crazyflies[0]\n        vel = np.ones(3)\n        cf.cmdVelocityWorld(vel, yawRate=0)\n        time = 0.0\n        while timeHelper.time() < 1.0:\n            timeHelper.sleep(dtSleep)\n            time += dtSleep\n\n        assert time >= timeHelper.time()\n\n        # We don't expect them to be exactly the same because timeHelper.time()\n        # will always be an integer multiple of dtTick. However, we should not\n        # be off by more than a tick.\n        assert time - timeHelper.time() < dtTick\n\n        pos = cf.initialPosition + timeHelper.time() * vel\n        assert np.all(np.isclose(cf.position(), pos))\n\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_ros.py",
    "content": "import pytest\n\n\n@pytest.mark.ros\ndef test_ros_import():\n    from pycrazyswarm.crazyflie import TimeHelper, CrazyflieServer\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_simOnly.py",
    "content": "#!/usr/bin/env python\n\n\"\"\"Tests for simulation-only functionality.\"\"\"\n\nimport numpy as np\n\nfrom pycrazyswarm import *\n\n\ndef setUp():\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - channel: 100\n      id: 1\n      initialPosition: [1.0, 0.0, 0.0]\n    \"\"\"\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=\"--sim --vis null\")\n    timeHelper = swarm.timeHelper\n    return swarm.allcfs, timeHelper\n\n\ndef test_attitudeRPY():\n    \"\"\"Checks differential flatness and roll/pitch/yaw calculations.\"\"\"\n\n    end = 0.99 * np.pi  # Not trying to deal with wrapping here.\n    yaws = np.linspace(-end, end, 11)\n\n    for yaw in yaws:\n        allcfs, timeHelper = setUp()\n        cf = allcfs.crazyflies[0]\n        Z = 1.0\n\n        cf.takeoff(targetHeight=Z, duration=1.0+Z)\n        timeHelper.sleep(1.5+Z)\n        cf.goTo(np.zeros(3), yaw=yaw, duration=1.0, relative=True)\n        timeHelper.sleep(1.5)\n\n        c = np.cos(yaw)\n        s = np.sin(yaw)\n        Ryaw = np.array([\n            [c, -s, 0],\n            [s,  c, 0],\n            [0,  0, 1],\n        ])\n        forward, left, up = Ryaw.T\n\n        dirAngleSigns = [\n            ( forward, 1,  1),\n            (-forward, 1, -1),\n            (    left, 0, -1),\n            (   -left, 0,  1),\n        ]\n\n        for direction, angleIdx, sign in dirAngleSigns:\n            cf.goTo(direction, yaw=0.0, duration=1.0, relative=True)\n            timeHelper.sleep(0.25)\n            rpy = cf.rpy()\n            assert rpy[angleIdx] * sign > np.radians(20)\n            assert np.abs(rpy[1 ^ angleIdx]) < np.radians(0.001)\n            assert np.abs(rpy[2] - yaw) < np.radians(0.001)\n            timeHelper.sleep(1.0)\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_videoOutput.py",
    "content": "\"\"\"Test video output in simulation.\n\nThis test is a bit strange: due to the following conditions\n\n- Video capture runs until the script process stops,\n- Video capture uses a child ffmpeg process to do compression,\n- We register an `atexit` function to ensure that the pipe is flushed and\n  ffmpeg process is closed cleanly,\n\nwe must run the video-generating script in a separate process.\n\nUsing `multiprocessing` would be easier, but `multiprocessing` processes don't\nrun `atexit` handlers when they exit. This design is controversial [1, 2].\nTherefore, we must do a full `system()`-style process spawn witn `subprocess`\ninstead. To avoid adding another script just to support this test, this script\nwill behave as the video generator process when run as `__main__()`, and behave\nas the test process when run via pytest.\n\n[1] https://stackoverflow.com/questions/2546276/python-process-wont-call-atexit\n[2] https://stackoverflow.com/questions/34506638/how-to-register-atexit-function-in-pythons-multiprocessing-subprocess\n\"\"\"\n\nimport os\nimport subprocess\nimport sys\n\nimport numpy as np\nimport pytest\n\nfrom pycrazyswarm import *\n\ncrazyflies_yaml = \"\"\"\ncrazyflies:\n- id: 1\n  channel: 110\n  initialPosition: [0.0, 0.0, 0.0]\n\"\"\"\n\nZ = 1.0\nFPS = 12\nDT = 1.0 / FPS\nTOTAL_TIME = 4.0\n\n\ndef videoWriterProcess(path):\n    args = \"--sim --vis vispy --dt {} --video {}\".format(DT, path)\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=args)\n    timeHelper = swarm.timeHelper\n    cf = swarm.allcfs.crazyflies[0]\n\n    cf.takeoff(targetHeight=Z, duration=TOTAL_TIME / 2)\n    timeHelper.sleep(TOTAL_TIME / 2)\n\n    cf.goTo(cf.initialPosition + np.array([0.0, 1.0, Z]), yaw=0.0, duration=TOTAL_TIME / 2)\n    timeHelper.sleep(TOTAL_TIME / 2)\n\n\n@pytest.mark.skipif(\"TRAVIS\" in os.environ or \"CI\" in os.environ,\n                    reason=\"CI usually cannot create OpenGL context.\")\ndef test_videoOutput(tmp_path):\n    # tmp_path is supplied by pytest - a directory where we can write that will\n    # eventually be deleted.\n    path = str(tmp_path / \"crazyswarm_test_video.mp4\")\n    subprocess.call([os.environ[\"CSW_PYTHON\"], __file__, path])\n\n    import ffmpeg\n    properties = ffmpeg.probe(path)\n    stream = properties[\"streams\"][0]\n    file_duration = float(stream[\"duration\"])\n    file_fps = int(stream[\"avg_frame_rate\"].split(\"/\")[0])\n    assert file_fps == FPS\n    assert abs(file_duration - TOTAL_TIME) <= DT\n\n\nif __name__ == \"__main__\":\n    videoWriterProcess(sys.argv[1])\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/test_yamlString.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\nfrom pycrazyswarm import *\n\ndef test_yaml_string_load():\n\n    crazyflies_yaml = \"\"\"\n    crazyflies:\n    - channel: 100\n      id: 1\n      initialPosition: [1.0, 0.0, 0.0]\n    - channel: 100\n      id: 10\n      initialPosition: [0.0, -1.0, 0.0]\n    \"\"\"\n\n    swarm = Crazyswarm(crazyflies_yaml=crazyflies_yaml, args=\"--sim --vis null\")\n    timeHelper = swarm.timeHelper\n    cfs = swarm.allcfs.crazyflies\n    byId = swarm.allcfs.crazyfliesById\n\n    assert len(cfs) == 2\n    cf1 = byId[1]\n    assert np.all(cf1.initialPosition == [1.0, 0.0, 0.0])\n\n    cf10 = byId[10]\n    assert np.all(cf10.initialPosition == [0.0, -1.0, 0.0])\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/udp_multicast.py",
    "content": "#!/usr/bin/env python\n\nimport socket\nimport struct\n\n# see https://stackoverflow.com/questions/603852/multicast-in-python\nclass UdpMulticastSender:\n  def __init__(self, MCAST_GRP = '224.1.1.1', MCAST_PORT = 5007):\n    self.MCAST_GRP = MCAST_GRP\n    self.MCAST_PORT = MCAST_PORT\n    self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP)\n    self.sock.setsockopt(socket.IPPROTO_IP, socket.IP_MULTICAST_TTL, 2)\n    \n  def send(self, msg):\n    self.sock.sendto(msg, (self.MCAST_GRP, self.MCAST_PORT))\n\n\nclass UdpMulticastReceiver:\n  def __init__(self, MCAST_GRP = '224.1.1.1', MCAST_PORT = 5007):\n    self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP)\n    self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)\n    self.sock.bind(('', MCAST_PORT))  # use MCAST_GRP instead of '' to listen only\n                                 # to MCAST_GRP, not all groups on MCAST_PORT\n    mreq = struct.pack(\"4sl\", socket.inet_aton(MCAST_GRP), socket.INADDR_ANY)\n    self.sock.setsockopt(socket.IPPROTO_IP, socket.IP_ADD_MEMBERSHIP, mreq)\n\n  def recv(self, bufsize=4096):\n    return self.sock.recv(bufsize)\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/waypoints.csv",
    "content": "id,x[m],y[m],z[m],t[s]\n1,0,0,1,0\n1,0,1,1,2\n1,0,0,2,4\n2,1,0,1,0\n2,1,1,2,4\n3,1,1,1,0\n3,1,1,3,2\n3,1,2,2,4\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/waypoints.py",
    "content": "#!/usr/bin/env python\n\nimport numpy as np\nfrom pycrazyswarm import *\n\nclass Waypoint:\n    def __init__(self, agent, x, y, z, arrival, duration):\n        self.agent = agent\n        self.x = x\n        self.y = y\n        self.z = z\n        self.arrival = arrival\n        self.duration = duration\n\n    def __lt__(self, other):\n        return self.arrival < other.arrival\n\n    def __repr__(self):\n        return \"Ag {} at {} s. [{}, {}, {}]\".format(self.agent, self.arrival, self.x, self.y, self.z)\n\n\nif __name__ == \"__main__\":\n\n    # load csv file\n    data = np.loadtxt(\"waypoints.csv\", skiprows=1, delimiter=',')\n\n    # sort by agents\n    data[data[:,0].argsort()]\n\n    # convert to internal data structure\n    waypoints = []\n    lastAgent = None\n    for row in data:\n        if lastAgent is None or lastAgent != row[0]:\n            lastTime = 0.0\n        waypoints.append(Waypoint(\n            int(row[0]),\n            row[1],\n            row[2],\n            row[3],\n            row[4],\n            row[4] - lastTime))\n        lastTime = row[4]\n        lastAgent = int(row[0])\n\n    # sort waypoints by arrival time\n    waypoints.sort()\n\n    # print waypoints\n    print(waypoints)\n\n    # execute waypoints\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    allcfs = swarm.allcfs\n\n    allcfs.takeoff(targetHeight=1.0, duration=2.0)\n    timeHelper.sleep(2.0)\n    lastTime = 0.0\n    for waypoint in waypoints:\n        if waypoint.arrival == 0:\n            pos = [waypoint.x, waypoint.y, waypoint.z]\n            # print(waypoint.agent, pos, 2.0)\n            cf = allcfs.crazyfliesById[waypoint.agent]\n            cf.goTo(pos, 0, 2.0)\n        elif waypoint.duration > 0:\n            timeHelper.sleep(waypoint.arrival - lastTime)\n            lastTime = waypoint.arrival\n            pos = [waypoint.x, waypoint.y, waypoint.z]\n            # print(waypoint.agent, pos, waypoint.duration)\n            cf = allcfs.crazyfliesById[waypoint.agent]\n            cf.goTo(pos, 0, waypoint.duration)\n\n    # land\n    allcfs.land(targetHeight=0.02, duration=2.0)\n    timeHelper.sleep(2.0)\n"
  },
  {
    "path": "ros_ws/src/crazyswarm/scripts/waypoints_simple.py",
    "content": "\"\"\"Single CF: takeoff, follow absolute-coords waypoints, land.\"\"\"\n\nimport numpy as np\n\nfrom pycrazyswarm import Crazyswarm\n\n\nZ = 1.0\nTAKEOFF_DURATION = 2.5\nGOTO_DURATION = 3.0\nWAYPOINTS = np.array([\n    (1.0, 0.0, Z),\n    (1.0, 1.0, Z),\n    (0.0, 1.0, Z),\n    (0.0, 0.0, Z),\n])\n\n\ndef main():\n    swarm = Crazyswarm()\n    timeHelper = swarm.timeHelper\n    cf = swarm.allcfs.crazyflies[0]\n\n    cf.takeoff(targetHeight=Z, duration=TAKEOFF_DURATION)\n    timeHelper.sleep(TAKEOFF_DURATION + 1.0)\n\n    for p in WAYPOINTS:\n        cf.goTo(cf.initialPosition + p, yaw=0.0, duration=GOTO_DURATION)\n        timeHelper.sleep(GOTO_DURATION + 1.0)\n\n    cf.land(targetHeight=0.05, duration=TAKEOFF_DURATION)\n    timeHelper.sleep(TAKEOFF_DURATION + 1.0)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "rosinstall",
    "content": "repositories:\n  motion_capture_tracking:\n    type: git\n    url: https://github.com/IMRCLab/motion_capture_tracking.git\n    version: ros2"
  },
  {
    "path": "systemtests/SDplotting/cfusdlog.py",
    "content": "# -*- coding: utf-8 -*-\n\"\"\"\nHelper to decode binary logged sensor data from crazyflie2 with uSD-Card-Deck.\n\nSource: https://github.com/IMRCLab/crazyflie-firmware/blob/master/tools/usdlog/cfusdlog.py\n\nMIT License\n\nCopyright (c) 2021 Intelligent Multi-Robot Coordination Lab @ TU Berlin, Germany\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\n\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\n\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n\"\"\"\nimport argparse\nfrom zlib import crc32\nimport struct\nimport numpy as np\n\n# extract null-terminated string\ndef _get_name(data, idx):\n    endIdx = idx\n    while data[endIdx] != 0:\n        endIdx = endIdx + 1\n    return data[idx:endIdx].decode(\"utf-8\"), endIdx + 1\n\ndef decode(filename):\n    # read file as binary\n    with open(filename, 'rb') as f:\n        data = f.read()\n\n    # check magic header\n    if data[0] != 0xBC:\n        print(\"Unsupported format!\")\n        return\n\n    # check CRC\n    crc = crc32(data[0:-4])\n    expected_crc, = struct.unpack('I', data[-4:])\n    if crc != expected_crc:\n        print(\"WARNING: CRC does not match!\")\n\n    # check version\n    version, num_event_types = struct.unpack('HH', data[1:5])\n    if version != 1 and version != 2:\n        print(\"Unsupported version!\", version)\n        return\n\n    result = dict()\n    event_by_id = dict()\n\n    # read header with data types\n    idx = 5\n    for _ in range(num_event_types):\n        event_id, = struct.unpack('H', data[idx:idx+2])\n        idx += 2\n        event_name, idx = _get_name(data, idx)\n        result[event_name] = dict()\n        result[event_name][\"timestamp\"] = []\n        num_variables, = struct.unpack('H', data[idx:idx+2])\n        idx += 2\n        fmtStr = \"<\"\n        variables = []\n        for _ in range(num_variables):\n            var_name_and_type, idx = _get_name(data, idx)\n            var_name = var_name_and_type[0:-3]\n            var_type = var_name_and_type[-2]\n            result[event_name][var_name] = []\n            fmtStr += var_type\n            variables.append(var_name)\n        event_by_id[event_id] = {\n            'name': event_name,\n            'fmtStr': fmtStr,\n            'numBytes': struct.calcsize(fmtStr),\n            'variables': variables,\n            }\n\n    while idx < len(data) - 4:\n        if version == 1:\n            event_id, timestamp, = struct.unpack('<HI', data[idx:idx+6])\n            idx += 6\n        elif version == 2:\n            event_id, timestamp, = struct.unpack('<HQ', data[idx:idx+10])\n            timestamp = timestamp / 1000.0\n            idx += 10\n        event = event_by_id[event_id]\n        fmtStr = event['fmtStr']\n        eventData = struct.unpack(fmtStr, data[idx:idx+event['numBytes']])\n        idx += event['numBytes']\n        for v,d in zip(event['variables'], eventData):\n            result[event['name']][v].append(d)\n        result[event['name']][\"timestamp\"].append(timestamp)\n\n    # remove keys that had no data\n    for event_name in list(result.keys()):\n        if len(result[event_name]['timestamp']) == 0:\n            del result[event_name]\n\n    # convert to numpy arrays\n    for event_name in result.keys():\n        for var_name in result[event_name]:\n            result[event_name][var_name] = np.array(result[event_name][var_name])\n\n    return result\n\n\nif __name__ == \"__main__\":\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"filename\")\n    args = parser.parse_args()\n    data = decode(args.filename)\n    print(data)\n"
  },
  {
    "path": "systemtests/SDplotting/data_helper.py",
    "content": "# -*- coding: utf-8 -*-\n\"\"\"\nTool for manipulating and adding data to the automatically generated reports.\n\"\"\"\nimport numpy as np\nfrom numpy.polynomial import polynomial as P\nfrom scipy.interpolate import CubicSpline, BSpline, splrep\n\n\n# from model_payload import ResidualsPayload\n\n\nclass DataHelper:\n    def __init__(self) -> None:\n        pass\n    \n    @staticmethod\n    def generate_data(data: dict[str, np.ndarray], \n                      event: str, \n                      info: dict[str, str | int | float]) -> dict[str, np.ndarray]:\n        source = data[event].get(info.get(\"source\", None), None)\n        t = data[event][\"timestamp\"]\n        t_fit = data[event].get(\"fitTimestamp\", None)\n        \n        if info.get(\"derivative\", 0) < 0:\n            raise ValueError(\"Derivative must be greater than or equal to 0\")\n\n        if info[\"type\"] == \"linspace\":\n            data_new = DataHelper.generate_data_linspace(source, info[\"step\"])\n        elif info[\"type\"] == \"poly\":\n            data_new = DataHelper.generate_data_poly(t, source, t_fit, info)\n        elif info[\"type\"] == \"cs\":\n            data_new = DataHelper.generate_data_cs(t, source, t_fit, info)\n        elif info[\"type\"] == \"bs\":\n            data_new = DataHelper.generate_data_bs(t, source, t_fit, info)\n        elif info[\"type\"] == \"custom\":\n            data_new = DataHelper.generate_data_custom(data[event], info[\"target\"])\n        else:\n            raise NotImplementedError\n\n        # exit 1: add each vector of the custom data list iteratively to the data dictionary and return\n        if isinstance(info[\"target\"], list):\n            dict_new = {}\n            for i, target in enumerate(info[\"target\"]):\n                dict_new[target] = data_new[i]\n            \n            return dict_new\n\n        # exit 2: add single vector to dictionary and return\n        return {info[\"target\"]: data_new}\n\n    @staticmethod\n    def generate_data_linspace(x: np.ndarray, step: int) -> np.ndarray:\n        return np.arange(x[0], x[-1], step)\n\n    @staticmethod\n    def generate_data_poly(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray:\n        p = P.Polynomial.fit(x, y,  info[\"degree\"])\n        p = p.deriv(info[\"derivative\"])\n\n        if not info.get(\"original_length\", False):\n            return p(x_fit)\n\n        return p(x)\n    \n    @staticmethod\n    def generate_data_cs(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray:\n        cs = CubicSpline(x, y)\n\n        if not info.get(\"original_length\", False):\n            return cs(x_fit, info[\"derivative\"])\n        \n        return cs(x, info[\"derivative\"])\n    \n    @staticmethod\n    def generate_data_bs(x: np.ndarray, y: np.ndarray, x_fit: np.ndarray, info: dict[str, str | int | float]) -> np.ndarray:\n        tck = splrep(x, y, s=info[\"smoothing\"])\n        bs = BSpline(*tck)\n\n        if not info.get(\"original_length\", False):\n            return bs(x_fit, info[\"derivative\"])\n        \n        return bs(x, info[\"derivative\"])  \n    \n    @staticmethod\n    def generate_data_custom(data: dict[str, np.ndarray], target_list: list[str]) -> list[np.ndarray]:\n        pass\n        # init objects for computing custom data (residuals, state errors, etc.)\n        # res_payload = ResidualsPayload(data)\n\n        # check and generate target for custom data\n        # custom_data = []\n        # for target in target_list:\n        #     if target == \"error.px\":\n        #         custom_data.append(res_payload.get_error_payload_position_x())\n        #     elif target == \"error.py\":\n        #         custom_data.append(res_payload.get_error_payload_position_y())\n        #     elif target == \"error.pz\":\n        #         custom_data.append(res_payload.get_error_payload_position_z())\n        #     elif target == \"error.pvx\":\n        #         custom_data.append(res_payload.get_error_payload_velocity_x())\n        #     elif target == \"error.pvy\":\n        #         custom_data.append(res_payload.get_error_payload_velocity_x())\n        #     elif target == \"error.pvz\":\n        #         custom_data.append(res_payload.get_error_payload_velocity_x())\n        #     elif target == \"error.cpx\":\n        #         custom_data.append(res_payload.get_error_cable_unit_vector_x())\n        #     elif target == \"error.cpy\":\n        #         custom_data.append(res_payload.get_error_cable_unit_vector_y())\n        #     elif target == \"error.cpz\":\n        #         custom_data.append(res_payload.get_error_cable_unit_vector_z())\n        #     elif target == \"error.pwx\":\n        #         custom_data.append(res_payload.get_error_payload_angular_velocity_x())\n        #     elif target == \"error.pwy\": \n        #         custom_data.append(res_payload.get_error_payload_angular_velocity_y())\n        #     elif target == \"error.pwz\":\n        #         custom_data.append(res_payload.get_error_payload_angular_velocity_z())\n        #     elif target == \"error.rpyx\":\n        #         custom_data.append(res_payload.get_error_uav_orientation_x())\n        #     elif target == \"error.rpyy\":\n        #         custom_data.append(res_payload.get_error_uav_orientation_y())\n        #     elif target == \"error.rpyz\":\n        #         custom_data.append(res_payload.get_error_uav_orientation_z())\n        #     elif target == \"error.wx\":\n        #         custom_data.append(res_payload.get_error_uav_angular_velocity_x())\n        #     elif target == \"error.wy\":\n        #         custom_data.append(res_payload.get_error_uav_angular_velocity_y())\n        #     elif target == \"error.wz\":\n        #         custom_data.append(res_payload.get_error_uav_angular_velocity_z())\n        #     elif target == \"residual.f\":\n        #         custom_data.append(res_payload.get_residual_force())\n        #     elif target == \"residual.tx\":\n        #         custom_data.append(res_payload.get_residual_torque_x())\n        #     elif target == \"residual.ty\":\n        #         custom_data.append(res_payload.get_residual_torque_y())\n        #     elif target == \"residual.tz\":\n        #         custom_data.append(res_payload.get_residual_torque_z())\n\n        # return custom_data\n    \n    \nif __name__ == \"__main__\":\n    pass\n    # small test\n    # data = {\"event\": {\n    #         \"timestamp\": np.array([1, 2, 3, 4, 5, 6, 7, 8, 9, 10]),\n    #         \"source\": np.array([10, 20, 15, 30, 15, 10, 5, 10, 15, 20])}}\n\n    # info = {\"type\": \"poly\",\n    #         \"degree\": 100,\n    #         \"derivative\": 1,\n    #         \"source\": \"source\",\n    #         \"target\": \"target\"}\n\n    # target, generated_data = DataHelper.generate_data(data, \"event\", info)\n    # plt.plot(data[\"event\"][\"timestamp\"], data[\"event\"][\"source\"], label=\"source\")\n    # plt.plot(data[\"event\"][\"timestamp\"], generated_data, label=\"generated\")\n    # plt.legend()\n    # plt.show()\n\n    # another small test\n    # x = np.arange(10)\n    # y = np.sin(x)\n    # cs = CubicSpline(x, y)\n    # xs = np.arange(-0.5, 9.6, 0.1)\n    # fig, ax = plt.subplots(figsize=(6.5, 4))\n    # ax.plot(x, y, 'o', label='data')\n    # ax.plot(xs, np.sin(xs), label='true')\n    # ax.plot(xs, cs(xs), label=\"S\")\n    # ax.plot(xs, cs.derivative(1), label=\"S'\")\n    # ax.plot(xs, cs.derivative(2), label=\"S''\")\n    # ax.plot(xs, cs.derivative(3), label=\"S'''\")\n    # ax.set_xlim(-0.5, 9.5)\n    # ax.legend(loc='lower left', ncol=2)\n    # plt.show()\n\n    # print(cs.c.shape)\n    # csder = cs.derivative(1)\n    # print(csder.c.shape)"
  },
  {
    "path": "systemtests/SDplotting/plot.py",
    "content": "# -*- coding: utf-8 -*-\n\"\"\"\nTool for yaml-based automatic report generation from logged data of the crazyflie.\n\"\"\"\n\n# attidtue best: 22\n\nimport SDplotting.cfusdlog\nimport matplotlib.pyplot as plt\nimport os\nimport sys\nimport yaml\nfrom matplotlib.backends.backend_pdf import PdfPages\nimport numpy as np\n\n\nimport SDplotting.data_helper\n\n\ndef file_guard(pdf_path):\n    msg = None\n    if os.path.exists(pdf_path):\n        msg = input(\"file already exists, overwrite? [y/n]: \")\n        if msg == \"n\":\n            print(\"exiting...\")\n            sys.exit(0)\n        elif msg == \"y\":\n            print(\"overwriting...\")\n            os.remove(pdf_path)\n        else:\n            print(\"invalid msg...\")\n            file_guard(pdf_path)\n\n    return\n\n\ndef process_data(data, settings):\n    print(\"...processing data\")\n    # convert units\n    event = settings[\"event_name\"]\n    \n    \n    # if we have a list of events we need to iterate over each individually\n    if type(event) == list :        \n        for one_event in event:\n            if settings[\"convert_units\"]:\n                for key, value in settings[\"convert_units\"].items():\n                    if key in data[one_event].keys():\n                        data[one_event][key] = data[one_event][key] * value                       \n            # shift time vector to start at 0\n            data[one_event][\"timestamp\"] = (data[one_event][\"timestamp\"] - data[one_event]['timestamp'][0])\n            \n   \n\n            # crop data\n            start_time = settings[\"start_time\"]\n            end_time = settings[\"end_time\"]\n            \n            t = data[one_event][\"timestamp\"]\n            if start_time is not None:\n                for key, value in data[one_event].items():\n                    data[one_event][key] = value[t >= start_time]\n\n            t = data[one_event][\"timestamp\"]\n            if end_time is not None:\n                for key, value in data[one_event].items():\n                    data[one_event][key] = value[t <= end_time]\n\n            # add additional data to the data dictionary\n            # add_data(data, settings)\n\n            # print(data[one_event].keys())\n            # print(data[one_event].items())\n    \n    \n     # else:   #if only one event\n    #     if settings[\"convert_units\"]:\n    #         for key, value in settings[\"convert_units\"].items():\n    #             data[event][key] = data[event][key] * value\n    #    # shift time vector to start at 0\n    #     data[event][\"timestamp\"] = (data[event][\"timestamp\"] - data[event]['timestamp'][0])\n        \n    #     # crop data\n    #     start_time = settings[\"start_time\"]\n    #     end_time = settings[\"end_time\"]\n        \n    #     t = data[event][\"timestamp\"]\n    #     if start_time is not None:\n    #         for key, value in data[event].items():\n    #             data[event][key] = value[t >= start_time]\n\n    #     t = data[event][\"timestamp\"]\n    #     if end_time is not None:\n    #         for key, value in data[event].items():\n    #             data[event][key] = value[t <= end_time]\n\n        # add additional data to the data dictionary\n        # add_data(data, settings)\n\n        # print(data[event].keys())\n        # print(data[event].items())\n\n    return data\n\n\ndef add_data(data, settings):\n    event = settings[\"event_name\"]\n    print(\"...adding data\")\n    \n    for info in settings[\"additional_data\"]:\n        # print(f\"found target: {info['target']}\")\n        dict_new = data_helper.DataHelper.generate_data(data, event, info)\n        data[event].update(dict_new)\n        print(f\">>> added data: {info['type']} -> {list(dict_new.keys())}\")\n        # print(f\">>> data shape: {data_new.shape}\")\n\n    print(\"...done adding data\")\n\n\ndef create_figures(data_usd, settings, logfile=None, out=None, ros2_ws=None, experiment=None):\n    debug_all = False\n    debug = False\n    debug_figure_number = 20 # Residual Torques\n    # debug_figure_number = 4 # UAV angles\n    # debug_figure_number = 13 # payload position error\n    # debug_figure_number = 6 # payload positions\n    # debug_figure_number = 7 # payload velocities\n\n    if logfile != None :\n        log_path = logfile\n    else:   #choose default log file path given in settings.yaml if no specific path given\n        log_path = os.path.join(settings[\"data_dir\"], settings['data_file'])\n    \n    print(\"log file: {}\".format(log_path))\n\n    data_processed = process_data(data_usd, settings)\n\n    # create a PDF to save the figures\n    if out!= None:\n        pdf_path = out\n    else:   #choose default pdf path in settings.yaml if no specifif one given\n        pdf_path =  os.path.join(settings[\"output_dir\"], settings['data_file']) + \".pdf\"\n    print(\"output path: {}\".format(pdf_path))\n\n    # check if user wants to overwrite the report file\n    file_guard(pdf_path)\n\n    pdf_pages = PdfPages(pdf_path)\n\n    # create the title page\n    title_text_settings = f\"Settings:\\n\"\n    for setting in settings[\"title_settings\"]:\n        title_text_settings += f\"    {setting}: {settings[setting]}\\n\"\n\n    # read the parameters from the info file\n    info_path = os.path.join(settings['info_dir'], settings[\"info_file\"])\n    if ros2_ws != None and experiment != None:\n        info_path = str(ros2_ws) + f\"/src/crazyswarm2/systemtests/SDplotting/info/info_{experiment}.yaml\"\n    print(\"... reading info file: {}\".format(info_path))\n\n    try:\n        with open(info_path, \"r\") as f:\n            info = yaml.safe_load(f)\n    except FileNotFoundError:\n        print(f\"(plot.py) File not found: {info_path}\")\n        exit(1)\n\n    title_text_parameters = f\"Parameters:\\n\"\n    for key, value in info.items():\n        title_text_parameters += f\"    {key}: {value}\\n\"\n\n    text = f\"%% Report %%\\n\"\n    title_text = text + \"\\n\" + title_text_settings + \"\\n\" + title_text_parameters + \"\\n\" # + title_text_results\n    fig = plt.figure(figsize=(5, 8))\n    fig.text(0.1, 0.1, title_text, size=11)\n    pdf_pages.savefig(fig)\n\n    # create data plots for each event\n    figures_max = settings.get(\"figures_max\", None)  # set to None to plot all figures\n    figure_count = 0\n    for k, (event, data) in enumerate(data_processed.items()):\n        if event in settings[\"event_name\"]:\n            print(\"processing event: {} ({})\".format(event, k))\n\n            # create a title text for each event\n            t = f\"%% Event {k}: {event} %%\\n\"\n            fig = plt.figure(figsize=(5, 5))\n            fig.text(0.1, 0.1, title_text, size=11)\n            pdf_pages.savefig(fig)\n\n            # create a new figure for each value in the data dictionary\n            figures_key = f\"figures_{event}\"\n            for figure_info in settings[figures_key]:\n                if figures_max is not None and figure_count >= figures_max:\n                    break\n\n                title = figure_info[\"title\"]\n                figure_type = figure_info[\"type\"]\n                x_label = figure_info.get(\"x_label\", None)\n                y_label = figure_info.get(\"y_label\", None)\n                z_label = figure_info.get(\"z_label\", None)\n                structure = figure_info[\"structure\"]\n                structure_length = len(structure)\n                \n                if figure_type == \"2d subplots\":\n                    fig, ax = plt.subplots(structure_length, 1)\n\n                    if structure_length == 1:\n                        ax = [ax]\n                    \n                    # iterate over every subplot in the figure\n                    for i, obj in enumerate(structure):\n                        n_x = len(obj[\"x_axis\"])\n                        n_y = len(obj[\"y_axis\"])\n                        n_leg = len(obj[\"legend\"])\n\n                        if n_x != n_y != n_leg:\n                            raise ValueError(\"Please specify the same number of x and y signals and legends\")\n                        \n                        # iterate over every plot in the respective subplot\n                        for j in range(n_x):\n                            x = obj[\"x_axis\"][j]\n                            y = obj[\"y_axis\"][j]\n                            \n                            # print(obj[\"legend\"][j], bool(obj[\"legend\"][j]))\n                            if figure_info[\"marker\"] == \"line\":\n                                ax[i].plot(data[x], data[y], label=obj[\"legend\"][j], **figure_info[\"marker_kwargs\"])\n                            elif figure_info[\"marker\"] == \"scatter\":\n                                ax[i].scatter(data[x], data[y], label=obj[\"legend\"][j], **figure_info[\"marker_kwargs\"])\n                            else:\n                                raise ValueError(\"Invalid marker\")\n\n                            ax[i].set_xlabel(obj[\"x_label\"])\n                            ax[i].set_ylabel(obj[\"y_label\"])\n                            if obj[\"legend\"][j]:\n                                ax[i].legend(loc=\"lower left\", fontsize=5)\n                            ax[i].grid(True)\n\n                # DEPRECATED\n                # if figure_type == \"2d single\":\n                #     fig, ax = plt.subplots()\n                    \n                #     # iterate over every subplot\n                #     for obj in structure:\n                #         ax.plot(data[obj[\"x_axis\"]], \n                #             data[obj[\"y_axis\"]], \n                #             label=obj[\"legend\"], \n                #             linewidth=0.5)\n                #         ax.set_xlabel(obj[\"x_label\"])\n                #         ax.set_ylabel(obj[\"y_label\"])\n                #         ax.legend(loc=\"lower left\", fontsize=5)\n                #         ax.grid(True)\n\n                if figure_type == \"3d\":\n                    fig = plt.figure()\n                    ax = fig.add_subplot(projection='3d')\n\n                    y_label = figure_info[\"y_label\"]\n                    \n                    # iterate over every subplot\n                    for i, obj in enumerate(structure):\n                        ax.plot(data[obj[0]],\n                                data[obj[1]],\n                                data[obj[2]], \n                                label=obj[3], \n                                linewidth=0.5)\n                        \n                        ax.set_xlim(min(data[obj[0]])-0.1*min(data[obj[0]]), \n                                    max(data[obj[0]])+0.1*max(data[obj[0]]))\n                        ax.set_ylim(min(data[obj[1]])-0.1*min(data[obj[1]]),\n                                    max(data[obj[1]])+0.1*max(data[obj[1]]))\n                        ax.set_zlim(min(data[obj[2]])-0.1*min(data[obj[2]]),\n                                    max(data[obj[2]])+0.1*max(data[obj[2]]))\n\n                    ax.set_xlabel(x_label)\n                    ax.set_ylabel(y_label)\n                    ax.set_zlabel(z_label)\n                    ax.legend(loc=\"lower left\", fontsize=5)\n                    ax.grid(True)\n\n                # show plot for debugging\n                if debug and figure_count == debug_figure_number-1 or debug_all:\n                    plt.show()\n\n                fig.suptitle(title, fontsize=16)\n                plt.tight_layout()\n                \n                # save the figure as a page in the PDF\n                pdf_pages.savefig(fig)\n                plt.close(fig)\n\n                figure_count += 1\n                status_text = \">>> created figure {}: {}\".format(figure_count, title)\n                print(status_text)\n\n    pdf_pages.close()\n\n\ndef plot_SD_data(logfile=None, output = None, experiment=None, ros2_ws = None):\n\n    # change the current working directory to the directory of this file\n    os.chdir(os.path.dirname(os.path.abspath(__file__)))\n\n    # load the plot settings\n    settings_file = \"settings.yaml\"\n    with open(settings_file, 'r') as f:\n        settings = yaml.load(f, Loader=yaml.FullLoader)\n    \n    if experiment != None:\n        settings[\"data_file\"] = experiment\n        settings[\"info_file\"] = \"info_\" + experiment + \".csv\"\n\n    # decode binary log data\n    if logfile != None :\n        path = logfile\n    else:   #choose default path given in settings.yaml\n        path = os.path.join(settings[\"data_dir\"], settings['data_file'])\n    print(f\"Processing {path}...\")\n    data_usd = SDplotting.cfusdlog.decode(path)\n\n    # create the figures\n    print(\"...creating figures\")\n    create_figures(data_usd, settings, out=output, ros2_ws=ros2_ws, experiment=experiment)\n    print(\"...done creating figures\")\n\n    \nif __name__ == \"__main__\":\n    plot_SD_data()"
  },
  {
    "path": "systemtests/SDplotting/save.py",
    "content": "# -*- coding: utf-8 -*-\n\"\"\"\nTool for saving parameters from the crazyflie.yaml before every experiment.\n\"\"\"\nimport os\nimport yaml\n\n\ndef write_info(experiment=None, ros2_ws_path=None):\n    # Dictionary to store extracted information\n    info = {}\n\n    # Prompt the user for the experiment number\n    # experiment_number = int(input(\"Enter the experiment number: \"))\n\n    # File paths\n    crazyflies_config_path = \"../crazyflie/config/crazyflies.yaml\"\n    if ros2_ws_path != None:\n        crazyflies_config_path = str(ros2_ws_path) + \"/src/crazyswarm2/crazyflie/config/crazyflies.yaml\"\n        info_file_prepath = str(ros2_ws_path) + \"/src/crazyswarm2/systemtests\"\n        \n\n    # Read information from crazyflies.yaml\n    try:\n        with open(crazyflies_config_path, \"r\") as config_file:\n            config_data = yaml.safe_load(config_file)\n            # extract the trajectory and timescale\n            obj = config_data[\"all\"][\"firmware_params\"]\n            if \"ctrlLeeInfo\" in obj:\n                for key, value in obj[\"ctrlLeeInfo\"].items():\n                    info[key] = value\n            # extract the ctrlLee parameters\n            if \"ctrlLee\" in obj:\n                for key, value in obj[\"ctrlLee\"].items():\n                    info[key] = value\n    except FileNotFoundError:\n        print(f\"(save.py) File not found: {crazyflies_config_path}\")\n        exit(1)\n\n\n    if experiment != None:\n        info[\"experiment\"] = experiment\n        info[\"trajectory\"] = str(experiment) + \".csv\"\n        \n    experiment_name = info[\"experiment\"]\n    info_file_path = info_file_prepath + f\"/SDplotting/info/info_{experiment_name}.yaml\"\n    # info_file_path = str(ros2_ws_path) + f\"systemtests/SDplotting/info/info{experiment_name}.yaml\"\n    \n    # file guard\n    if os.path.exists(info_file_path):\n        print(f\"File already exists: {info_file_path}  It will be replaced\")\n        # ans = input(\"Overwrite? [y/n]: \")\n        # if ans == \"n\":\n        #     print(\"Exiting...\")\n        #     exit(1)\n\n    print(\"========================================\")\n\n    try:\n        with open(info_file_path, \"w\") as info_file:\n            print(f\"Writing experiment info to {info_file_path}\")\n            for key in info:\n                print(f\">>> {key}: {info[key]}\")\n                yaml.dump({key: info[key]}, info_file, default_flow_style=False, sort_keys=False)\n        print(f\"Experiment info written to {info_file_path}\")\n    except Exception as e:\n        print(f\"Error writing to {info_file_path}: {str(e)}\")\n\n    print(\"========================================\")\n\nif __name__ == \"__main__\":\n    write_info(\"multi_trajectory\", \"/home/jthevenoz/ros2_ws\")"
  },
  {
    "path": "systemtests/SDplotting/settings.yaml",
    "content": "---\n# general settings\ndata_dir: logs\ndata_file: figure8\n# data_file: log129\ninfo_dir: info\ninfo_file: infofigure8.yaml\nevent_name: \n- fixedFrequency\n- estPosition\nstart_time:    # s (w.r.t log start time)\nend_time:     # s (w.r.t log start time)\noutput_dir: reports\nfigures_max:\nskip_data:\n- timestamp\n\n# title settings\ntitle_settings:\n- data_dir\n- data_file\n- info_dir\n- info_file\n- event_name\n- output_dir\n- start_time\n- end_time\n\n# figure settings for event fixedFrequency\nfigures_fixedFrequency:\n- title: UAV Positions \n  type: 2d subplots\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  structure:\n  - x_axis: [timestamp]\n    y_axis: [stateEstimate.x]\n    legend: [ekf]\n    x_label: \"$t [s]$\"\n    y_label: \"$x [m]$\"\n  - x_axis: [timestamp]\n    y_axis: [stateEstimate.y]\n    legend: [ekf]\n    x_label: \"$t [s]$\"\n    y_label: \"$y [m]$\"\n  - x_axis: [timestamp]\n    y_axis: [stateEstimate.z]\n    legend: [ekf]\n    x_label: \"$t [s]$\"\n    y_label: \"$z [m]$\"\n- title: 3D Trajectory\n  type: 3d\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  x_label: $x [m]$\n  y_label: $y [m]$\n  z_label: $z [m]$\n  structure:\n  - - stateEstimate.x\n    - stateEstimate.y\n    - stateEstimate.z\n    - ekf\n- title: 2D Trajectory\n  type: 2d subplots\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  structure:\n  - x_axis: [stateEstimate.x]\n    y_axis: [stateEstimate.y]\n    legend: [ekf]\n    x_label: \"$x [m]$\"\n    y_label: \"$y [m]$\"\n\n# figure settings for event estPosition\nfigures_estPosition:\n- title: UAV Positions \n  type: 2d subplots\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  structure:\n  - x_axis: [timestamp]\n    y_axis: [locSrv.x]\n    legend: [mocap]\n    x_label: \"$t [s]$\"\n    y_label: \"$x [m]$\"\n  - x_axis: [timestamp]\n    y_axis: [locSrv.y]\n    legend: [mocap]\n    x_label: \"$t [s]$\"\n    y_label: \"$y [m]$\"\n  - x_axis: [timestamp]\n    y_axis: [locSrv.z]\n    legend: [mocap]\n    x_label: \"$t [s]$\"\n    y_label: \"$z [m]$\"\n- title: 3D Trajectory\n  type: 3d\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  x_label: $x [m]$\n  y_label: $y [m]$\n  z_label: $z [m]$\n  structure:\n  - - locSrv.x\n    - locSrv.y\n    - locSrv.z\n    - mocap\n- title: 2D Trajectory\n  type: 2d subplots\n  marker: line\n  marker_kwargs:\n    linewidth: 0.5\n  structure:\n  - x_axis: [locSrv.x]\n    y_axis: [locSrv.y]\n    legend: [mocap]\n    x_label: \"$x [m]$\"\n    y_label: \"$y [m]$\"\n\n\n# unit settings\nconvert_units:\n  timestamp: 0.001\n  stateEstimate.x: 0.001\n  stateEstimate.y: 0.001\n  stateEstimate.z: 0.001\n  # stateEstimateZ.x: 0.001\n  # stateEstimateZ.y: 0.001\n  # stateEstimateZ.z: 0.001\n  # stateEstimateZ.vx: 0.001\n  # stateEstimateZ.vy: 0.001\n  # stateEstimateZ.vz: 0.001\n  # ctrltargetZ.x: 0.001\n  # ctrltargetZ.y: 0.001\n  # ctrltargetZ.z: 0.001\n  # ctrltargetZ.vx: 0.001\n  # ctrltargetZ.vy: 0.001\n  # ctrltargetZ.vz: 0.001\n  # ctrlLee.rpyx: 57.2957795131\n  # ctrlLee.rpydx: 57.2957795131\n  # ctrlLee.rpyy: 57.2957795131\n  # ctrlLee.rpydy: 57.2957795131\n  # ctrlLee.rpyz: 57.2957795131\n  # ctrlLee.rpydz: 57.2957795131\n  # ctrlLee.omegax: 57.2957795131\n  # ctrlLee.omegarx: 57.2957795131\n  # ctrlLee.omegay: 57.2957795131\n  # ctrlLee.omegary: 57.2957795131\n  # ctrlLee.omegaz: 57.2957795131\n  # ctrlLee.omegarz: 57.2957795131\n  # acc.x: 1.0\n  # acc.y: 1.0\n  # acc.z: 1.0\n  # stateEstimateZ.px: 0.001\n  # stateEstimateZ.py: 0.001\n  # stateEstimateZ.pz: 0.001\n  # stateEstimateZ.pvx: 0.001\n  # stateEstimateZ.pvy: 0.001\n  # stateEstimateZ.pvz: 0.001 \n  locSrv.x: 1.0\n  locSrv.y: 1.0\n  locSrv.z: 1.0\n  # locSrv.qx: 1.0\n  # locSrv.qy: 1.0\n  # locSrv.qz: 1.0\n  # locSrv.qw: 1.0\n \n# units for the report:\n#   timestamp: s\n#   stateEstimateZ.x: m\n#   stateEstimateZ.y: m\n#   stateEstimateZ.z: m\n#   stateEstimateZ.vx: m/s\n#   stateEstimateZ.vy: m/s\n#   stateEstimateZ.vz: m/s\n#   ctrltargetZ.x: m\n#   ctrltargetZ.y: m\n#   ctrltargetZ.z: m\n#   ctrltargetZ.vx: m/s\n#   ctrltargetZ.vy: m/s\n#   ctrltargetZ.vz: m/s\n#   ctrlLee.rpyx: °\n#   ctrlLee.rpyy: °\n#   ctrlLee.rpyz: °\n#   ctrlLee.rpydx: °\n#   ctrlLee.rpydy: °\n#   ctrlLee.rpydz: °\n#   ctrlLee.omegax: °/s\n#   ctrlLee.omegay: °/s\n#   ctrlLee.omegaz: °/s\n#   ctrlLee.omegarx: °/s\n#   ctrlLee.omegary: °/s\n#   ctrlLee.omegarz: °/s\n#   ctrlLee.thrustSI: N\n#   ctrlLee.torquex: Nm\n#   ctrlLee.torquey: Nm\n#   ctrlLee.torquez: Nm\n#   acc.x: m/s^2\n#   acc.y: m/s^2\n#   acc.z: m/s^2\n#   stateEstimate.px: m\n#   stateEstimate.py: m\n#   stateEstimate.pz: m\n#   stateEstimate.pvx: m/s\n#   stateEstimate.pvy: m/s\n#   stateEstimate.pvz: m/s\n#   locSrv.x: m\n#   locSrv.y: m\n#   locSrv.z: m\n#   locSrv.qw: \n#   locSrv.qx: \n#   locSrv.qy: \n#   locSrv.qz: \n\n# info for adding additional data (fmi: data_helper.py)\n# (1) type: linspace  -> takes data and returns data with more points in between (needs step)\n# (2) type: poly      -> takes data and returns data of a fitted polynomial, or its derivative (needs derivative, degree)\n# (3) type: cs        -> takes data and returns data of a cubic spline, or its derivative (needs derivative)\n# (4) type: bs        -> takes data and returns data of a b-spline, or its derivative (needs derivative, smoothing)\n# (5) type: custom    -> processes data to compute and return new custom data vectors (based on target string list)\n# additional_data:\n#   # ==================================================\n#   # fitting: new time vector\n#   # ==================================================\n#   - source: timestamp\n#     target: fitTimestamp\n#     type: linspace\n#     step: 0.0001\n#   # ==================================================\n#   # fitting with new length\n#   # ==================================================\n#   - source: stateEstimateZ.px\n#     target: fitZ.px\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#   - source: stateEstimateZ.py\n#     target: fitZ.py\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#   - source: stateEstimateZ.pz\n#     target: fitZ.pz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#   - source: stateEstimateZ.px\n#     target: fitZ.pvx\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#   - source: stateEstimateZ.py\n#     target: fitZ.pvy\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#   - source: stateEstimateZ.pz\n#     target: fitZ.pvz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#   - source: stateEstimateZ.px\n#     target: fitZ.pax\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#   - source: stateEstimateZ.py\n#     target: fitZ.pay\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#   - source: stateEstimateZ.pz\n#     target: fitZ.paz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#   # ==================================================\n#   # fitting with original length\n#   # ==================================================\n#   - source: ctrlLee.rpyx\n#     target: fitZOriginalLength.rpyx\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: ctrlLee.rpyy\n#     target: fitZOriginalLength.rpyy\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: ctrlLee.rpyz\n#     target: fitZOriginalLength.rpyz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: ctrlLee.rpyx\n#     target: fitZOriginalLength.omegax\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: ctrlLee.rpyy\n#     target: fitZOriginalLength.omegay\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: ctrlLee.rpyz\n#     target: fitZOriginalLength.omegaz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: ctrlLee.rpyx\n#     target: fitZOriginalLength.alphax\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   - source: ctrlLee.rpyy\n#     target: fitZOriginalLength.alphay\n#     type: bs\n#     smoothing: 10\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   - source: ctrlLee.rpyz\n#     target: fitZOriginalLength.alphaz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   - source: stateEstimateZ.px\n#     target: fitZOriginalLength.px\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: stateEstimateZ.py\n#     target: fitZOriginalLength.py\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: stateEstimateZ.pz\n#     target: fitZOriginalLength.pz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 0\n#     original_length: True\n#   - source: stateEstimateZ.px\n#     target: fitZOriginalLength.pvx\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: stateEstimateZ.py\n#     target: fitZOriginalLength.pvy\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: stateEstimateZ.pz\n#     target: fitZOriginalLength.pvz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 1\n#     original_length: True\n#   - source: stateEstimateZ.px\n#     target: fitZOriginalLength.pax\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   - source: stateEstimateZ.py\n#     target: fitZOriginalLength.pay\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   - source: stateEstimateZ.pz\n#     target: fitZOriginalLength.paz\n#     type: bs\n#     smoothing: 1\n#     # degree:\n#     derivative: 2\n#     original_length: True\n#   # ==================================================\n#   # custom data with original length respectively\n#   # ==================================================\n#   - type: custom\n#     target: \n#     - error.px\n#     - error.py\n#     - error.pz\n#     - error.pvx\n#     - error.pvy\n#     - error.pvz\n#     - error.cpx\n#     - error.cpy\n#     - error.cpz\n#     - error.pwx\n#     - error.pwy\n#     - error.pwz\n#     - error.rpyx\n#     - error.rpyy\n#     - error.rpyz\n#     - error.wx\n#     - error.wy\n#     - error.wz\n#     - residual.f\n#     - residual.tx\n#     - residual.ty\n#     - residual.tz\n#   # =================================================="
  },
  {
    "path": "systemtests/figure8_ideal_traj.csv",
    "content": "duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7,\n\n#### wait on the ground\n0.6,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n\n####takeoff\n2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000001,0.000000,0.000000,0.232052,0.184839,0.030911,-0.176192,0.050572,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n####hover\n3.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n####figure8\n1.050000,0.000000,-0.000000,0.000000,-0.000000,0.830443,-0.276140,-0.384219,0.180493,-0.000000,0.000000,-0.000000,0.000000,-1.356107,0.688430,0.587426,-0.329106,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,0.396058,0.918033,0.128965,-0.773546,0.339704,0.034310,-0.026417,-0.030049,-0.445604,-0.684403,0.888433,1.493630,-1.361618,-0.139316,0.158875,0.095799,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,0.922409,0.405715,-0.582968,-0.092188,-0.114670,0.101046,0.075834,-0.037926,-0.291165,0.967514,0.421451,-1.086348,0.545211,0.030109,-0.050046,-0.068177,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,0.923174,-0.431533,-0.682975,0.177173,0.319468,-0.043852,-0.111269,0.023166,0.289869,0.724722,-0.512011,-0.209623,-0.218710,0.108797,0.128756,-0.055461,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.405364,-0.834716,0.158939,0.288175,-0.373738,-0.054995,0.036090,0.078627,0.450742,-0.385534,-0.954089,0.128288,0.442620,0.055630,-0.060142,-0.076163,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.560000,0.001062,-0.646270,-0.012560,-0.324065,0.125327,0.119738,0.034567,-0.063130,0.001593,-1.031457,0.015159,0.820816,-0.152665,-0.130729,-0.045679,0.080444,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.700000,-0.402804,-0.820508,-0.132914,0.236278,0.235164,-0.053551,-0.088687,0.031253,-0.449354,-0.411507,0.902946,0.185335,-0.239125,-0.041696,0.016857,0.016709,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.620000,-0.921641,-0.464596,0.661875,0.286582,-0.228921,-0.051987,0.004669,0.038463,-0.292459,0.777682,0.565788,-0.432472,-0.060568,-0.082048,-0.009439,0.041158,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n0.710000,-0.923935,0.447832,0.627381,-0.259808,-0.042325,-0.032258,0.001420,0.005294,0.288570,0.873350,-0.515586,-0.730207,-0.026023,0.288755,0.215678,-0.148061,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n1.053185,-0.398611,0.850510,-0.144007,-0.485368,-0.079781,0.176330,0.234482,-0.153567,0.447039,-0.532729,-0.855023,0.878509,0.775168,-0.391051,-0.713519,0.391628,1.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,\n####hover\n1.7,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n####landing\n2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000001,0.000000,0.000000,-0.232049,-0.184841,-0.030916,0.176196,-0.050573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n"
  },
  {
    "path": "systemtests/mcap_handler.py",
    "content": "from pathlib import Path\nfrom rclpy.serialization import deserialize_message\nfrom rosidl_runtime_py.utilities import get_message\nfrom std_msgs.msg import String\nimport rosbag2_py\nimport csv\n\nclass McapHandler:\n    def __init__(self):\n        self.takeoff_time = None\n\n    def read_messages(self, input_bag: str):\n        reader = rosbag2_py.SequentialReader()\n        reader.open(\n            rosbag2_py.StorageOptions(uri=input_bag, storage_id=\"mcap\"),\n            rosbag2_py.ConverterOptions(\n                input_serialization_format=\"cdr\", output_serialization_format=\"cdr\"\n            ),\n        )\n        topic_types = reader.get_all_topics_and_types()\n\n        def typename(topic_name):\n            for topic_type in topic_types:\n                if topic_type.name == topic_name:\n                    return topic_type.type\n            raise ValueError(f\"topic {topic_name} not in bag\")\n\n        while reader.has_next():\n            topic, data, timestamp = reader.read_next()\n            msg_type = get_message(typename(topic))\n            msg = deserialize_message(data, msg_type)\n            yield topic, msg, timestamp\n        del reader\n    \n    def write_mcap_to_csv(self, inputbag:str, outputfile:str):\n        '''A method which translates an .mcap rosbag file format to a .csv file. \n        Also modifies the timestamp to start at 0.0 instead of the wall time.\n        Only written to translate the /tf topic but could easily be extended to other topics'''\n        t_start_bag = None #this is the timestamp of the first message we read in the bag (doesn't mean it's exactly the start time of the bag but close enough ?)\n        try:\n            print(\"Translating .mcap to .csv\")\n            f = open(outputfile, 'w+')\n            writer = csv.writer(f)\n            writer.writerow([\"# t\",\" x\",\" y\",\" z\"])\n            for topic, msg, timestamp in self.read_messages(inputbag):\n                if topic ==\"/tf\":\n                    if t_start_bag == None:\n                        t_start_bag = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) \n                    t = msg.transforms[0].header.stamp.sec + msg.transforms[0].header.stamp.nanosec *10**(-9) -t_start_bag\n                    writer.writerow([t, msg.transforms[0].transform.translation.x, msg.transforms[0].transform.translation.y, msg.transforms[0].transform.translation.z])\n                if topic == \"/rosout\":  #and t_start_bag != None :\n                    if msg.name == \"crazyflie_server\" and msg.function == \"takeoff\":\n                        t = msg.stamp.sec + msg.stamp.nanosec *10**(-9) - t_start_bag\n                        self.takeoff_time = t\n                    #the takeoff message in simulation has a sligthly different name than IRL, so we need this to record the sim takeoff time\n                    #BUT for some unknown reason the sim tests seem to work perfectly without even recording takeoff and adjusting the offset\n                    #so I will leave this commented here just in case the sim tests have to be worked on\n                    # if msg.name == \"crazyflie_server\" and msg.function == \"_takeoff_callback\":\n                    #     t = msg.stamp.sec + msg.stamp.nanosec *10**(-9)\n                    #     self.takeoff_time = t\n                    #     print(f\"takeoff at {self.takeoff_time}\")\n\n            #write the \"takeoff command\" time as a comment on the last line\n            writer.writerow([f\"### takeoff time : {self.takeoff_time}\"])\n            f.close()\n        except FileNotFoundError:\n            print(f\"McapHandler : file {outputfile} not found\")\n            exit(1)\n\n\n\n\nif __name__ == \"__main__\":\n\n    #command line utility \n\n    from argparse import ArgumentParser, Namespace\n    parser = ArgumentParser(description=\"Translates the /tf topic of an .mcap rosbag file format to a .csv file\")\n    parser.add_argument(\"inputbag\", type=str, help=\"The .mcap rosbag file to be translated\")\n    parser.add_argument(\"outputfile\", type=str, help=\"Output csv file that has to be created/overwritten\")\n    args:Namespace = parser.parse_args()\n\n    translator =  McapHandler()\n    translator.write_mcap_to_csv(args.inputbag,args.outputfile)"
  },
  {
    "path": "systemtests/multi_trajectory_ideal_traj0.csv",
    "content": "Duration,x^0,x^1,x^2,x^3,x^4,x^5,x^6,x^7,y^0,y^1,y^2,y^3,y^4,y^5,y^6,y^7,z^0,z^1,z^2,z^3,z^4,z^5,z^6,z^7,yaw^0,yaw^1,yaw^2,yaw^3,yaw^4,yaw^5,yaw^6,yaw^7\n\n#wait before takeoff\n0.5,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n\n\n####takeoff\n2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000001,0.000000,0.000000,0.232052,0.184839,0.030911,-0.176192,0.050572,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n\n####hover\n3.5,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n\n####flying around\n0.960464,0.0,0,0,0,-2.11233,4.6768,-3.73784,1.04989,0.0,0,0,0,3.30457,-7.9007,6.65669,-1.94082,1.0,0,0,0,-0.297773,0.623628,-0.493335,0.138654,0,0,0,0,0,0,0,0\n1.57331,0.176622,-0.147985,0.0532986,0.0623229,0.343746,-0.500924,0.241338,-0.0403025,0.289553,0.0742267,-0.0522539,-0.0351683,-0.975361,1.50407,-0.788135,0.141456,1.043558,-0.0592408,-0.0401473,-0.00342225,-1.05145,1.64557,-0.878344,0.159958,0,0,0,0,0,0,0,0\n1.68226,0.294342,0.17123,-0.0334701,-0.0192207,-0.0992382,0.118149,-0.0472082,0.00658999,0.084993,-0.0345305,0.0714366,0.00548031,0.800464,-1.18606,0.592827,-0.10086,0.753768,0.00212717,0.0685892,0.0024846,1.23285,-1.76366,0.869779,-0.147011,0,0,0,0,0,0,0,0\n1.92896,0.374489,-0.0338637,0.00252255,0.00888171,0.0111398,-0.0108929,0.00298726,-0.000251823,0.276975,-0.0784884,-0.0934159,0.000645144,-1.04135,1.33809,-0.584077,0.0868443,1.183524,0.0937667,-0.0541849,-0.00524925,-0.318377,0.393297,-0.166638,0.0242508,0,0,0,0,0,0,0,0\n2.03711,0.374489,0.0286391,-6.1852e-05,-0.00368623,0.00253097,-0.0050055,0.00272644,-0.000441277,-0.358361,0.0262046,0.110055,-0.00620508,0.544041,-0.672761,0.279349,-0.0393627,1.0461,-0.0452504,0.0303272,0.00292994,0.0964916,-0.116635,0.047237,-0.00652766,0,0,0,0,0,0,0,0\n1.08507,0.4,-0.00978883,-0.00352811,0.00421159,-0.147076,0.385891,-0.320935,0.0884478,0.1,-0.0261795,-0.0932209,0.0135473,-3.39392,7.64989,-5.90562,1.55714,1.1,0.0120733,-0.0160302,0.00109914,-0.170679,0.405338,-0.316775,0.0837347,0,0,0,0,0,0,0,0\n1.46341,0.4,0.0345966,0.0216228,0.00040938,0.113468,-0.193811,0.109932,-0.021215,-0.1,-0.00953811,0.0938259,0.00686414,1.78784,-3.00192,1.71647,-0.335021,1.1,0.0162005,0.0183118,0.001431,0.543281,-0.905734,0.51742,-0.101032,0,0,0,0,0,0,0,0\n2.19353,0.492638,0.0469231,-0.0199807,-0.000892996,-0.0338512,0.0362701,-0.0130911,0.00162474,0.203839,-0.0288206,-0.11848,-0.00554452,-0.630569,0.72139,-0.276928,0.0361384,1.209968,0.00986131,-0.0243065,-0.00119445,-0.0998581,0.115095,-0.0441976,0.00576199,0,0,0,0,0,0,0,0\n2.40126,0.48694,-0.00615544,0.0115191,0.000423929,0.00796213,-0.00925373,0.00321793,-0.000373305,-0.469909,0.0557579,0.149918,-0.00106415,0.538482,-0.564538,0.198219,-0.0236403,1.119622,0.0192151,0.028845,-0.000113746,0.115626,-0.12072,0.0423492,-0.00505007,0,0,0,0,0,0,0,0\n2.46094,0.515442,-0.000365976,-0.0122673,2.25527e-05,4.3861e-06,0.00181356,-0.000737567,8.47618e-05,0.463845,-0.0412104,-0.17329,0.000264977,-0.593703,0.60121,-0.20494,0.023781,1.330891,0.000348253,-0.0330759,0.000313802,-0.0979748,0.0999974,-0.0342066,0.00397451,0,0,0,0,0,0,0,0\n2.68427,0.48694,0.00486563,0.0132321,-0.00114426,0.0129524,-0.0144619,0.00482814,-0.000528691,-0.71593,-0.0408684,0.184692,0.00619732,0.442694,-0.405637,0.125531,-0.0132641,1.142929,-0.00451953,0.0270264,-0.00218942,0.0121858,-0.0179685,0.00647746,-0.000732907,0,0,0,0,0,0,0,0\n1.92558,0.505486,-0.0481952,-0.0204291,0.00284946,-0.0470553,0.0773259,-0.0377233,0.00598077,0.718761,0.267399,-0.141554,-0.0117975,-0.800345,0.963882,-0.403221,0.0582575,1.098904,-0.131338,-0.0396354,0.00782912,-0.4965,0.661823,-0.295209,0.0445271,0,0,0,0,0,0,0,0\n2.0699,0.421491,0.0186218,0.0156054,-0.00129697,0.07458,-0.0953844,0.0399616,-0.00562765,0.302142,-0.266958,0.0381168,0.0177516,-0.0552536,0.0911841,-0.0450511,0.00702141,0.771628,0.115857,0.0879918,-0.00554767,0.814447,-0.973674,0.396022,-0.0548837,0,0,0,0,0,0,0,0\n1.9596,0.48694,-0.0304046,-0.0213345,0.00170875,-0.231304,0.295149,-0.127553,0.0187408,0.120541,0.123032,0.0122544,-0.012462,0.149347,-0.218046,0.101473,-0.0155924,1.505486,0.00192474,-0.107286,0.000790515,-1.01863,1.26183,-0.536142,0.0779269,0,0,0,0,0,0,0,0\n1.70183,0.333009,0.0183142,0.028215,-0.00185434,0.43896,-0.63547,0.3139,-0.0528803,0.232223,-0.140993,-0.0449547,0.00936592,-1.12957,1.6455,-0.81818,0.138527,0.832615,-0.101997,0.0790866,0.00096767,0.497639,-0.719611,0.351991,-0.0587304,0,0,0,0,0,0,0,0\n1.34472,0.48694,-0.00625689,-0.0317257,0.000382684,-1.03393,1.83762,-1.13117,0.238966,-0.226478,0.0101228,0.0610516,-0.00764983,1.25229,-2.30188,1.44081,-0.307367,0.917626,-0.033286,-0.0550669,0.00313228,-1.52482,2.7969,-1.74891,0.372958,0,0,0,0,0,0,0,0\n2.1222,0.333009,-0.0545061,0.0199991,0.00480515,0.107972,-0.116334,0.0436145,-0.00566624,-0.072397,-0.0307885,-0.0689067,-0.00236443,-0.48434,0.57055,-0.226496,0.0305878,0.717497,0.028035,0.0816772,0.00612047,0.73381,-0.837942,0.327938,-0.0439369,0,0,0,0,0,0,0,0\n2.22722,0.421491,0.0660872,-0.00287208,-0.00340824,0.062709,-0.0713995,0.0277343,-0.00364623,-0.495874,0.0534612,0.0981472,0.00118253,0.675836,-0.73877,0.276221,-0.03532,1.457563,0.131649,-0.0799577,-0.00792167,-0.366161,0.385528,-0.140404,0.0176255,0,0,0,0,0,0,0,0\n1.85734,0.540865,-0.00634081,-0.00724899,0.00147892,-0.0808568,0.10675,-0.0483186,0.00746342,0.379252,0.132248,-0.0957692,-0.00873243,-1.07307,1.34465,-0.588112,0.0887744,1.038957,-0.200084,0.0246642,0.00970083,-0.25658,0.36452,-0.173423,0.0277121,0,0,0,0,0,0,0,0\n1.69138,0.496281,-0.00160133,0.00618968,0.000136705,0.124512,-0.174729,0.0851269,-0.0142547,-0.1853,-0.289684,0.024136,0.0175717,-0.384504,0.663858,-0.362455,0.0651215,0.81169,0.0702784,0.0295687,-0.00247486,1.21881,-1.70715,0.833757,-0.139995,0,0,0,0,0,0,0,0\n2.19933,0.540865,0.0144117,-0.00391837,-0.00119932,-0.0275664,0.0268387,-0.00940817,0.0011576,-0.385893,0.235345,0.0702187,-0.0148152,0.588274,-0.67496,0.261551,-0.0343838,1.323729,0.185085,-0.00841054,-0.00925475,0.039381,-0.0748132,0.0351087,-0.00510156,0,0,0,0,0,0,0,0\n2.68201,0.500322,-0.0412104,-0.00763103,0.000713901,-0.0520821,0.0470691,-0.0146416,0.00155911,0.387882,-0.0842107,-0.121138,0.00454433,-0.324702,0.302031,-0.0946549,0.0100916,1.366876,-0.264264,-0.0765883,0.0107036,-0.298247,0.281606,-0.0893991,0.00961875,0,0,0,0,0,0,0,0\n2.21932,0.292621,-0.0377479,0.0107761,0.00185615,0.0523879,-0.0498758,0.0171324,-0.002072,-0.664787,-0.0756608,0.114634,0.000204595,0.482644,-0.530616,0.198653,-0.0254146,0.289226,0.0179677,0.111474,-0.00732309,0.507412,-0.56779,0.21534,-0.0277882,0,0,0,0,0,0,0,0\n0.826943,0.365479,0.0796986,0.011073,-0.00345361,6.10559,-17.7498,17.8943,-6.18313,-0.128196,0.0924843,-0.0686475,0.000538459,-0.967377,2.3937,-2.12002,0.661123,0.899606,0.03983,-0.0650002,0.0145722,-1.19604,3.65303,-3.72378,1.2885,0,0,0,0,0,0,0,0\n1.70943,0.515442,0.0778242,-0.0130839,-0.00452718,-0.0331128,0.0135171,0.00336571,-0.00165812,-0.128196,-0.0503162,-0.00225906,0.0131073,0.046757,-0.0481522,0.016617,-0.00196654,0.899606,0.0424298,0.0647269,0.0125499,1.45743,-2.08038,1.01596,-0.169609,0,0,0,0,0,0,0,0\n2.0764,0.515442,-0.0859543,-0.0188315,0.00474201,-0.258721,0.311102,-0.127276,0.0176996,-0.128196,0.0471026,0.00501662,-0.00187713,0.203127,-0.228639,0.0905749,-0.0123697,1.418091,0.0269611,-0.0986299,-0.00460336,-0.709972,0.831305,-0.332664,0.0455369,0,0,0,0,0,0,0,0\n1.34033,0.241704,0.00169625,0.0267376,-0.0040746,0.496448,-0.922,0.581167,-0.124661,0.125962,0.103337,0.00817997,-0.00308402,1.45034,-2.64983,1.66366,-0.356691,0.813306,-0.0951879,0.0808931,0.00400333,1.56751,-2.73421,1.6614,-0.348002,0,0,0,0,0,0,0,0\n1.27955,0.296893,-0.0207413,-0.0288722,0.000206756,-1.45292,2.73635,-1.78001,0.396694,0.363893,0.0205828,-0.0396241,-0.00426978,-2.18054,3.96089,-2.52441,0.555328,1.000432,0.116162,-0.0271769,-0.0121203,-0.0967398,0.0511672,0.0231312,-0.0137364,0,0,0,0,0,0,0,0\n1.25924,0.129979,-0.0386626,0.0254433,0.00229348,0.314605,-0.568015,0.359101,-0.0786867,0.096373,-0.177655,-0.00188175,0.0162637,-1.43193,2.92354,-2.00733,0.465729,1.019741,-0.0837562,-0.0114419,0.0108961,-0.89746,1.80018,-1.22397,0.282268,0,0,0,0,0,0,0,0\n1.35118,0.155486,0.0338914,-0.00270101,-0.0039661,0.202739,-0.374799,0.237823,-0.0512712,-0.106737,0.0769914,0.0704076,-0.0152089,1.54198,-2.90366,1.8396,-0.394692,0.898222,0.0286494,0.0412961,-0.00329222,1.31264,-2.35215,1.45212,-0.306802,0,0,0,0,0,0,0,0\n1.14424,0.2,0.0015442,-0.00224162,0.00123466,-0.00661606,0.0134679,-0.00982511,0.00245085,0.0,-0.0953098,-0.0830381,0.0218392,-2.55729,5.66335,-4.2252,1.06822,1.1,0.0445589,-0.0317429,-0.000623191,-0.213517,0.427027,-0.293881,0.0698972,0,0,0,0,0,0,0,0\n1.06974,0.0,-7.36408e-05,0.000107209,-5.42089e-05,0.000468972,-0.00106323,0.000841569,-0.000226684,0.0,0.0736875,0.104178,-0.0410587,3.38468,-7.9737,6.38949,-1.73737,1.1,-0.0104492,0.00871066,0.00133714,0.089598,-0.209747,0.164384,-0.043835,0,0,0,0,0,0,0,0\n\n####hover\n2.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.0,0.000000,0.000000,0.0,0.0,0.0,0.0,0.0,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n\n\n####landing\n2.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000001,0.000000,0.000000,-0.232049,-0.184841,-0.030916,0.176196,-0.050573,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,0.000000\n"
  },
  {
    "path": "systemtests/plotter_class.py",
    "content": "import matplotlib.pyplot as plt\nimport os\nimport sys \nfrom matplotlib.backends.backend_pdf import PdfPages\nfrom matplotlib.patches import Rectangle\nimport numpy as np\nfrom crazyflie_py.uav_trajectory import Trajectory\nfrom pathlib import Path\n\n\nclass Plotter:\n\n    def __init__(self, sim_backend = False):\n        self.params = {'experiment':'1','trajectory':'','motors':'standard motors(CF)', 'propellers':'standard propellers(CF)'}\n        self.bag_times = np.empty([0])\n        self.bag_x = np.empty([0])\n        self.bag_y = np.empty([0])\n        self.bag_z = np.empty([0])\n        self.ideal_traj_x = np.empty([0])\n        self.ideal_traj_y = np.empty([0])\n        self.ideal_traj_z = np.empty([0])\n        self.euclidian_dist = np.empty([0])\n        self.deviation = [] #list of all indexes where euclidian_distance(ideal - recorded) > EPSILON\n        self.test_name = None\n\n        self.SIM = sim_backend      #indicates if we are plotting data from real life test or from a simulated test. Default is false (real life test)\n        self.EPSILON = 0.15 # euclidian distance in [m] between ideal and recorded trajectory under which the drone has to stay to pass the test (NB : epsilon is doubled for multi_trajectory test)\n        self.ideal_takeoff = 0.6\n        self.ideal_traj_start = 5.6\n        self.ALLOWED_DEV_POINTS = 0.05  #allowed percentage of datapoints whose deviation > EPSILON while still passing test (currently % for fig8 and 10% for mt)\n        # if self.SIM :                #It allows to temporally adjust the ideal and real trajectories on the graph. Could this be implemented in a better (not hardcoded) way ?\n        #     self.DELAY_CONST_FIG8 = 0#-0.45  #for an unknown reason, the delay constants with the sim_backend is different\n        #     self.DELAY_CONST_MT = 0#-0.3\n        self.ALTITUDE_CONST_FIG8 = 1 #this is the altitude given for the takeoff in figure8.py. I should find a better solution than a symbolic constant ?\n    \n    def file_guard(self, pdf_path):\n        msg = None\n        if os.path.exists(pdf_path):\n            msg = input(\"file already exists, overwrite? [y/n]: \")\n            if msg == \"n\":\n                print(\"exiting...\")\n                sys.exit(0)\n            elif msg == \"y\":\n                print(\"overwriting...\")\n                os.remove(pdf_path)\n            else:\n                print(\"invalid msg...\")\n                self.file_guard(pdf_path)\n        return\n    \n\n\n    def read_csv_and_set_arrays(self, ideal_csvfile, rosbag_csvfile):\n        '''Method that reads the csv data of the ideal test trajectory and of the actual recorded trajectory and initializes the attribute arrays'''\n\n        \n        #get ideal trajectory data\n        self.ideal_traj_csv = Trajectory()\n        try:\n            path_to_ideal_csv = os.path.join(os.path.dirname(os.path.abspath(__file__)),ideal_csvfile)\n            self.ideal_traj_csv.loadcsv(path_to_ideal_csv)\n        except FileNotFoundError:\n            print(\"Plotter : File not found \" + path_to_ideal_csv)\n            exit(1)\n\n\n        #get rosbag data\n        rosbag_data = np.loadtxt(rosbag_csvfile, delimiter=\",\")\n        \n        self.bag_times = np.array(rosbag_data[:,0])\n        self.bag_x = np.array(rosbag_data[:,1])\n        self.bag_y = np.array(rosbag_data[:,2])\n        self.bag_z = np.array(rosbag_data[:,3])\n    \n        self.adjust_arrays()\n        bag_arrays_size = len(self.bag_times)\n        print(\"number of datapoints in self.bag_*: \",bag_arrays_size)\n        \n\n        #since the rosbag doesn't start at a reliable time, we need to adjust the ideal time array and the real one so that they aren't offset. For this we compare the time where the \"takeoff\" command was\n        # given to the crazyflie with the time of takeoff in the desired trajectory. With this we have the time-delay which we need to correct the offset (NB : empirically modified by 0.15 seconds this \n        #time-delay because that seems to be the delay between receiving the takeoff command and actually flying off)\n        with open(rosbag_csvfile) as f:\n                lines = f.readlines()\n                lastline = lines[-1] #get last line of csv file, where the takeoff time is written as comment\n                try:\n                    self.takeoff_time = float(lastline[lastline.find(\":\") + 1 :])  #get the \"takeoff\" time from last line of csv\n                except ValueError: #if no takeoff was issued, there will be a \"None\" in the lastline which will produce value error when converting to float\n                    print(\"Warning : No takeoff written in the lastline of the rosbag csv file : offset cannot be corrected.\")\n                    self.takeoff_time = 0\n        offset1 = (self.ideal_takeoff - self.takeoff_time) - 0.15\n\n\n        #####calculate ideal trajectory points corresponding to the times of recorded points \n\n        self.ideal_traj_x = np.empty([bag_arrays_size])\n        self.ideal_traj_y = np.empty([bag_arrays_size])\n        self.ideal_traj_z = np.empty([bag_arrays_size])\n        self.euclidian_dist = np.empty([bag_arrays_size])\n\n        no_match_in_idealcsv=[]\n\n        delay = offset1\n        # if self.test_name == \"fig8\" and self.SIM:\n        #     delay = self.DELAY_CONST_FIG8\n        # elif self.test_name == \"mt\" and self.SIM:\n        #     delay = self.DELAY_CONST_MT\n        \n        for i in range(bag_arrays_size):  \n            try:\n                pos = self.ideal_traj_csv.eval(self.bag_times[i] + delay).pos\n            except AssertionError: \n                no_match_in_idealcsv.append(i)\n                pos = [0,0,0]  #for all recorded datapoints who cannot be matched to a corresponding ideal position we assume the drone is on its ground start position (ie those datapoints are before takeoff or after landing)\n               \n            self.ideal_traj_x[i], self.ideal_traj_y[i], self.ideal_traj_z[i]= pos[0], pos[1], pos[2]\n\n            self.euclidian_dist[i] = np.linalg.norm([self.ideal_traj_x[i]-self.bag_x[i], \n                                                self.ideal_traj_y[i]-self.bag_y[i], self.ideal_traj_z[i]-self.bag_z[i]])\n            if self.euclidian_dist[i] > self.EPSILON:\n                self.deviation.append(i)\n            \n        self.no_match_warning(no_match_in_idealcsv)\n\n\n    def no_match_warning(self, unmatched_values:list):\n        ''' A method which prints a warning saying how many (if any) recorded datapoints could not be matched to an ideal datapoint'''\n\n        no_match_arr = np.array(unmatched_values)\n\n        if no_match_arr.size == 0:\n            return\n        \n        split_index_arr = []\n\n        for i in range(no_match_arr.size - 1):                    #find indexes which are not consecutive\n            if(no_match_arr[i+1] != no_match_arr[i]+1):\n                split_index_arr.append(i+1)\n\n        banana_split = np.split(no_match_arr, split_index_arr)     #split array into sub-array of consecutive indexes -> each sub-array is a timerange for which ideal positions weren't able to calculated\n        print(f\"{len(no_match_arr)} recorded positions weren't able to be matched with a specified ideal position and were given the default (0,0,0) ideal position instead.\")\n        print(\"Probable reason : their timestamp is before the start of the ideal trajectory or after its end.\")\n        if len(banana_split)==2:\n            timerange1_start = self.bag_times[banana_split[0][0]]\n            timerange1_end= self.bag_times[banana_split[0][1]]\n            timerange2_start = self.bag_times[banana_split[1][0]]\n            timerange2_end = self.bag_times[banana_split[1][1]]\n            print(f\"These datapoints correspond to the time ranges [{timerange1_start} , {timerange1_end}] and [{timerange2_start} , {timerange2_end}]\")\n\n\n\n    def adjust_arrays(self):\n        ''' Method that adjusts the self.bag_* attributes to get rid of the datapoints whose timestamp don't make sense'''\n\n        print(f\"rosbag initial length {(self.bag_times[-1]-self.bag_times[0]) }s\")\n\n\n        #recurring problem : some messages recorded from /tf arrive way later (2-4 seconds) than when they were emitted, which makes a mess in the timestamps\n        #zB we have timestamps (in s) : 5.1, 5.2, 5.3, !!!3.7, 3.9, 4.5, 4.9!!!, 5.4, 5.5, 5.6, 5.7 etc. This bug almost always occurs in the first seconds of the recording & generally only happens once per recording\n        #and only concerns a very small percentage of datapoints (10-40 over about 1800 total), so it is not a big deal. We do not know if this bug stems from the Rosbag recording, from how /tf behaves or from the radio\n\n        #Since we use a lineplot, we need to get rid of these datapoints that are in an order that doesn't make sense so that the plot can be readable\n        self.nonsensical = [] #list of indexes of datapoints who arrived too late, meaning their timestamp doesn't follow the ones before\n        time = -1\n        for index,t in enumerate(self.bag_times):\n            if t > time:\n                time = t\n            else:\n                self.nonsensical.append(index)\n\n\n        if self.nonsensical: #if self.nonsensical is not empty\n            self.bag_times = np.delete(self.bag_times, self.nonsensical)\n            self.bag_x = np.delete(self.bag_x, self.nonsensical)\n            self.bag_y = np.delete(self.bag_y, self.nonsensical)\n            self.bag_z = np.delete(self.bag_z, self.nonsensical)\n            print(f\"{len(self.nonsensical)} datapoints were ignored because because their timestamp wasn't in the good order (delayed message problem). They go from index {self.nonsensical[0]} to {self.nonsensical[-1]}\")\n\n        assert len(self.bag_times) == len(self.bag_x) == len(self.bag_y) == len(self.bag_z), \"Plotter : self.bag_* aren't the same size after adjusting arrays\"\n\n        print(f\"trimmed bag_times starts: {self.bag_times[0]}s and ends: {self.bag_times[-1]}, size: {len(self.bag_times)}\")\n\n\n\n    def create_figures(self, ideal_csvfile:str, rosbag_csvfile:str, pdfname:str, overwrite=False):\n        '''Method that creates the pdf with the plots'''\n\n        #check which test we are plotting : figure8 or multi_trajectory or another one\n        if(\"figure8\" in rosbag_csvfile):\n            self.test_name = \"fig8\"\n            self.params[\"trajectory\"] = \"figure8\"\n            print(\"Plotting fig8 test data\")\n        elif \"multi_trajectory\" in rosbag_csvfile:\n            self.test_name = \"mt\"\n            self.params[\"trajectory\"] = \"multi_trajectory\"\n            self.EPSILON *= 2  #multi_trajectory test has way more difficulties\n            self.ALLOWED_DEV_POINTS *= 2\n            print(\"Plotting multi_trajectory test data\")\n        else:\n            self.test_name = \"undefined\"\n            self.params[\"trajectory\"] = \"undefined\"\n            print(\"Plotting unspecified test data\")\n\n\n        self.read_csv_and_set_arrays(ideal_csvfile,rosbag_csvfile)\n        \n        test_result=\"failed\"\n        passed, percentage = self.test_passed()\n        if passed:\n            test_result = \"passed\"\n        \n        #create PDF to save figures\n        if(pdfname[-4:] != \".pdf\"):\n            pdfname= pdfname + '.pdf'\n\n        #check if user wants to overwrite the report file\n        if not overwrite :\n            self.file_guard(pdfname)\n        pdf_pages = PdfPages(pdfname)\n\n        #create title page\n        if \"figure8\" in ideal_csvfile:\n            name = \"Figure8\"\n        elif \"multi_trajectory\" in ideal_csvfile:\n            name = \"Multi_trajectory\"\n        else:\n            name = \"Unnamed test\"\n            print(\"Plotter : test name not defined\")\n\n        title = f'{name} trajectory test'\n        if self.SIM:  \n            title += \"(SIMULATION)\"\n        title_text_settings = f'Settings:\\n'\n        title_text_parameters = f'Parameters:\\n'\n        for key, value in self.params.items():\n            title_text_parameters += f\"    {key}: {value}\\n\"\n        title_text_results = f'Results: test {test_result}\\n' + f\"acceptable deviation EPSILON: {self.EPSILON}[m]\\n\"\n        title_text_results += f\"percentage of points > EPSILON : {percentage:.4f}%\\n\" + f\"average error : {np.mean(self.euclidian_dist):.6f} [m]\\n\"\n        title_text_results += f\"median error : {np.median(self.euclidian_dist):.6f} [m]\\n\" + f\"max error : {np.max(self.euclidian_dist):.6f} [m]\\n\"\n\n\n        title_text = title + \"\\n\" + title_text_settings + \"\\n\" + title_text_parameters + \"\\n\" + title_text_results\n        fig = plt.figure(figsize=(5,8))\n        fig.text(0.1, 0.1, title_text, size=11)\n    \n\n        pdf_pages.savefig(fig)\n    \n   \n        #create plots\n        fig, ax = plt.subplots()\n        ax.plot(self.bag_times, self.ideal_traj_x, label='Ideal trajectory', linestyle=\"--\", linewidth=1, zorder=10)\n        ax.plot(self.bag_times, self.bag_x, label='Recorded trajectory')\n        ax.set_xlabel('time [s]')\n        ax.set_ylabel('x position [m]')  \n        ax.set_title(\"Trajectory x\")   \n        ax.grid(which='major', color='#DDDDDD', linewidth=0.8)\n        ax.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5)\n        ax.minorticks_on()\n        fig.tight_layout(pad = 4)\n        fig.legend()       \n        pdf_pages.savefig(fig) \n          \n        fig2, ax2 = plt.subplots()\n        ax2.plot(self.bag_times, self.ideal_traj_y, label='Ideal trajectory', linestyle=\"--\", linewidth=1, zorder=10)\n        ax2.plot(self.bag_times, self.bag_y, label='Recorded trajectory')\n        ax2.set_xlabel('time [s]')\n        ax2.set_ylabel('y position [m]')  \n        ax2.set_title(\"trajectory y\")\n        ax2.grid(which='major', color='#DDDDDD', linewidth=0.8)\n        ax2.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5)\n        ax2.minorticks_on()\n        fig2.tight_layout(pad = 4) \n        fig2.legend()\n        pdf_pages.savefig(fig2) \n          \n\n        fig3, ax3 = plt.subplots()\n        ax3.plot(self.bag_times, self.ideal_traj_z, label='Ideal trajectory', linestyle=\"--\", linewidth=1, zorder=10)\n        ax3.plot(self.bag_times, self.bag_z, label='Recorded trajectory')\n        ax3.set_xlabel('time [s]')\n        ax3.set_ylabel('z position [m]')   \n        ax3.set_title(\"Trajectory z\")\n        ax3.grid(which='major', color='#DDDDDD', linewidth=0.8)\n        ax3.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5)\n        ax3.minorticks_on()\n        fig3.tight_layout(pad = 4)\n        fig3.legend()\n        pdf_pages.savefig(fig3) \n \n        fig4, ax4 = plt.subplots()\n        ax4.plot(self.bag_times, self.euclidian_dist)\n        ax4.set_xlabel('time [s]')\n        ax4.set_ylabel('Euclidean distance [m]')\n        ax4.set_title('Deviation between ideal and recorded trajectories')\n        fig4.tight_layout(pad=4)\n        ax4.grid(which='major', color='#DDDDDD', linewidth=0.8)\n        ax4.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5)\n        ax4.minorticks_on()\n        pdf_pages.savefig(fig4)\n\n\n        fig5,ax5 = plt.subplots()\n        ax5.plot(self.ideal_traj_x, self.ideal_traj_y, label='Ideal trajectory', linestyle=\"--\", linewidth=1, zorder=10)\n        ax5.plot(self.bag_x, self.bag_y, label='Recorded trajectory')\n        ax5.set_xlabel('x [m]')\n        ax5.set_ylabel('y [m]')\n        ax5.set_title('2D visualization')\n        fig5.tight_layout(pad=4)\n        ax5.grid(which='major', color='#DDDDDD', linewidth=0.8)\n        ax5.grid(which='minor', color='#EEEEEE', linestyle=':', linewidth=0.5)\n        ax5.minorticks_on()\n        pdf_pages.savefig(fig5)\n\n\n        fig6 = plt.figure()\n        ax6 = fig6.add_subplot(projection=\"3d\")\n        ax6.plot3D(self.ideal_traj_x,self.ideal_traj_y,self.ALTITUDE_CONST_FIG8, label='Ideal trajectory', linestyle=\"--\", linewidth=1, zorder=10)\n        ax6.plot3D(self.bag_x,self.bag_y,self.bag_z, label='Recorded trajectory', linewidth=1)\n        ax6.grid(True)\n        ax6.set_title('3D visualization')\n        ax6.set_xlabel('x [m]')\n        ax6.set_ylabel('y [m]')\n        ax6.set_zlabel('z [m]')\n        plt.close(fig6)\n        plt.tight_layout(pad=4)\n        pdf_pages.savefig(fig6)\n\n        pdf_pages.close()\n\n        print(\"Results saved in \" + pdfname)\n\n    def test_passed(self) -> tuple :\n        '''Returns a tuple containing (bool:passed, float:percentage). If the deviation between recorded and ideal trajectories of the drone didn't exceed \n        EPSILON for more than ALLOWED_DEV_POINTS % of datapoints, the boolean passed is True. Otherwise it is false. float:percentage is the percentage\n        of points which whose deviation is less than EPSILON'''\n\n        nb_dev_points = len(self.deviation)\n        threshold = self.ALLOWED_DEV_POINTS * len(self.bag_times)\n        percentage = (len(self.deviation) / len(self.bag_times)) * 100 \n\n        if nb_dev_points < threshold:\n            print(f\"Test {self.test_name} passed : {percentage:.4f}% of datapoints had deviation larger than {self.EPSILON}m ({self.ALLOWED_DEV_POINTS * 100}% max for pass)\")\n            return (True, percentage)\n        else:\n            print(f\"Test {self.test_name} failed : The deviation between ideal and recorded trajectories is greater than {self.EPSILON}m for {percentage:8.4f}% of  datapoints\")\n            return (False, percentage)\n        \n\n\nif __name__==\"__main__\":\n    \n    # command line utility \n\n    from argparse import ArgumentParser, Namespace\n    parser = ArgumentParser(description=\"Creates a pdf plotting the recorded trajectory of a drone against its desired trajectory\")\n    parser.add_argument(\"desired_trajectory\", type=str, help=\".csv file containing (time,x,y,z) of the ideal/desired drone trajectory\")\n    parser.add_argument(\"recorded_trajectory\", type=str, help=\".csv file containing (time,x,y,z) of the recorded drone trajectory\")\n    parser.add_argument(\"pdf\", type=str, help=\"name of the pdf file you want to create/overwrite\")\n    parser.add_argument(\"--open\", help=\"Open the pdf directly after it is created\", action=\"store_true\")\n    parser.add_argument(\"--overwrite\", action=\"store_true\", help=\"If the given pdf already exists, overwrites it without asking\")\n    args : Namespace = parser.parse_args()\n\n    plotter = Plotter()\n    plotter.create_figures(args.desired_trajectory, args.recorded_trajectory, args.pdf, overwrite=args.overwrite)\n    if args.open:\n        import subprocess\n        subprocess.call([\"xdg-open\", args.pdf])"
  },
  {
    "path": "systemtests/test_flights.py",
    "content": "import unittest\n\nfrom pathlib import Path\nimport shutil\nimport os\nfrom plotter_class import Plotter\nfrom mcap_handler import McapHandler\nfrom subprocess import Popen, PIPE, TimeoutExpired\nimport time\nimport signal\nimport atexit\nfrom argparse import ArgumentParser, Namespace\nfrom SDplotting import save, plot\n\n\ndef setUpModule():\n\n    path = Path(__file__)           #Path(__file__) in this case \"/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/src/crazyswarm2/systemtests/test_flights.py\" ; path.parents[0]=.../systemstests\n    \n    #delete results, logs and bags of previous experiments if they exist\n    if(Path(path.parents[3] / \"results\").exists()):\n        shutil.rmtree(path.parents[3] / \"results\")  \n\n    os.makedirs(path.parents[3] / \"results\")  # /home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws/results\n\ndef tearDownModule():\n    pass\n\n\ndef clean_process(process:Popen) -> int :\n    '''Kills process and its children on exit if they aren't already terminated (called with atexit). Returns 0 on termination, 1 if SIGKILL was needed''' \n    if process.poll() == None:\n        group_id = os.getpgid(process.pid)\n        #print(f\"cleaning process {group_id}\")\n        os.killpg(group_id, signal.SIGTERM)\n        time.sleep(0.01) #necessary delay before first poll\n        i=0\n        while i < 10 and process.poll() == None:  #in case the process termination is lazy and takes some time, we wait up to 0.5 sec per process\n            if process.poll() != None:\n                return 0  #if we have a returncode-> it terminated\n            time.sleep(0.05) #if not wait a bit longer\n        if(i == 9):\n            os.killpg(group_id, signal.SIGKILL)\n            return 1  #after 0.5s we stop waiting, consider it did not terminate correctly and kill it\n        return 0\n    else:\n        return 0 #process already terminated\n    \ndef print_PIPE(process : Popen, process_name, always=False):\n    '''If process creates some error, prints the stderr and stdout PIPE of the process. NB : stderr and stdout must = PIPE in the Popen constructor'''\n    if process.returncode != 0 or always:\n        out, err = process.communicate()\n        print(f\"{process_name} returncode = {process.returncode}\")\n        print(f\"{process_name} stderr : {err} \\n\")\n        print(f\"{process_name} stdout : {out} \\n\")\n        print(\"\\n\")\n    else:\n        print(f\"{process_name} completed sucessfully\")\n\n\n\nclass TestFlights(unittest.TestCase):\n    SIM = False\n\n    def __init__(self, methodName: str = \"runTest\") -> None:\n        super().__init__(methodName)\n        self.test_file = None\n        self.launch_crazyswarm : Popen = None \n        self.ros2_ws = Path(__file__).parents[3] #/home/github/actions-runner/_work/crazyswarm2/crazyswarm2/ros2_ws\n        self.src = f\"source {str(self.ros2_ws)}/install/setup.bash\"\n\n    def idFolderName(self):\n        return self.id().split(\".\")[-1] #returns the name of the test_function currently being run, for example \"test_figure8\"\n\n    # runs once per test_ function\n    def setUp(self):\n\n        if(Path(Path.home() / \".ros/log\").exists()): #delete log files of the previous test\n            shutil.rmtree(Path.home() / \".ros/log\")\n        self.test_file = None\n\n        # launch server\n        command = f\"{self.src} && ros2 launch crazyflie launch.py\"\n        if TestFlights.SIM :                               \n            command += \" backend:=sim\"    #launch crazyswarm from simulation backend \n            current_env = os.environ.copy()\n        self.launch_crazyswarm = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, text=True,\n                                start_new_session=True, executable=\"/bin/bash\")\n        atexit.register(clean_process, self.launch_crazyswarm)  #atexit helps us to make sure processes are cleaned even if script exits unexpectedly\n        time.sleep(5)\n\n    # runs once per test_ function\n    def tearDown(self) -> None:\n        clean_process(self.launch_crazyswarm)   #kill crazyswarm_server and all of its child processes\n        # print_PIPE(self.launch_crazyswarm, \"launch_crazyswarm\")  #this will always print all of the STDOUT and STDERR since we killed it beforehand. Not smart ?\n        time.sleep(3)  #give some time for crazyflie_server to shut down completely before starting the USD download\n        # copy .ros/log files to results folder\n        if Path(Path.home() / \".ros/log\").exists():\n            shutil.copytree(Path.home() / \".ros/log\", Path(__file__).parents[3] / f\"results/{self.idFolderName()}/roslogs\")\n\n        if self.SIM:                    #if in simulation, we skip the downloading SD data part\n            return super().tearDown()\n\n        command = f\"{self.src} && ros2 run crazyflie downloadUSDLogfile --output SDlogfile\" #if CF doesn't use default URI, add --uri custom_uri (e.g --uri radio://0/80/2M/E7E7E7E70B)\n        try:\n            downloadSD= Popen(command, shell=True, stderr=False, stdout=False, text=True,         #download the log file in ....../ros2_ws/results/test_xxxxxxx/\n                                cwd= self.ros2_ws / f\"results/{self.idFolderName()}\" ,start_new_session=True, executable=\"/bin/bash\") \n            atexit.register(clean_process, downloadSD)\n            ####testing purposes\n            print(\"waiting\")\n            time_start = time.time()\n            #######\n            downloadSD.wait(timeout=300) #wait 5min for download to finish and raise TimeoutExpired if not finished\n            print(f\"download lasted {time.time()-time_start}s\")\n        except TimeoutExpired:\n            clean_process(downloadSD)\n            print(\"Downloading SD card data was killed for taking too long\")\n            return super().tearDown()\n        \n          \n            ####try to plot the SD log\n        SDlogfile_path = str(self.ros2_ws / f\"results/{self.idFolderName()}/SDlogfile\")\n        # pdf_path = str(self.ros2_ws / f\"results/{self.idFolderName()}/SDreport.pdf\")\n        test_name = self.test_file[:self.test_file.rfind(\"_ideal_traj\")]  #strip the end of the test_file string to just keep the name\n        save.write_info(experiment=test_name, ros2_ws_path=str(self.ros2_ws))\n        \n        if Path(SDlogfile_path).stat().st_size == 0: \n            print(\"SDlogfile has size 0. Maybe the CF failed at writing the log on its SD card, or the downloading through radio failed. SDreport PDF cannot be generated\")\n            return super().tearDown()\n\n        plot.plot_SD_data(output = str(self.ros2_ws / f\"results/{self.idFolderName()}/SDreport.pdf\"), \n                        logfile = SDlogfile_path, experiment = test_name, ros2_ws = self.ros2_ws)\n\n        return super().tearDown()\n        \n\n    def record_start_and_clean(self, testname:str, max_wait:int):\n        '''Starts recording the /tf topic in a rosbag, starts the test, waits, closes the rosbag and terminate all processes. max_wait is the max amount of time you want to wait \n            before forcefully terminating the test flight script (in case it never finishes correctly).\n            NB the testname must be the name of the crayzflie_examples executable (ie the CLI grammar \"ros2 run crazyflie_examples testname\" must be valid)'''\n        \n        # src = f\"source {str(self.ros2_ws)}/install/setup.bash\"\n        try:\n            command = f\"{self.src} && ros2 bag record -s mcap -o test_{testname} /tf /rosout\"   \n            record_bag =  Popen(command, shell=True, stderr=PIPE, stdout=True, text=True,\n                                cwd= self.ros2_ws / \"results/\", start_new_session=True, executable=\"/bin/bash\") \n            atexit.register(clean_process, record_bag)\n\n            command = f\"{self.src} && ros2 run crazyflie_examples {testname}\"\n            if TestFlights.SIM:\n                command += \" --ros-args -p use_sim_time:=True\" #necessary args to start the test in simulation\n            start_flight_test = Popen(command, shell=True, stderr=PIPE, stdout=PIPE, \n                                    start_new_session=True, text=True, executable=\"/bin/bash\")\n            atexit.register(clean_process, start_flight_test)\n\n            if TestFlights.SIM :\n                start_flight_test.wait(timeout=max_wait*5)  #simulation can be super slow \n            else : \n                start_flight_test.wait(timeout=max_wait)  #raise Timeoutexpired after max_wait seconds if start_flight_test didn't finish by itself\n\n            clean_process(start_flight_test)          \n            clean_process(record_bag)\n            print(\"finished the test\")\n\n        except TimeoutExpired:      #if max_wait is exceeded\n            clean_process(start_flight_test)          \n            clean_process(record_bag)\n\n        except KeyboardInterrupt:   #if drone crashes, user can ^C to skip the waiting\n            clean_process(start_flight_test)          \n            clean_process(record_bag)\n        \n        #if something went wrong with the bash command lines in Popen, print the error\n        print_PIPE(record_bag, f\"record_bag for {self.idFolderName()}\")\n        print_PIPE(start_flight_test, f\"start_flight_test for {self.idFolderName()}\", always=True)\n\n        \n    def translate_plot_and_check(self, testname:str) -> bool :\n        '''Translates rosbag .mcap format to .csv, then uses that csv to plot a pdf. Checks the deviation between ideal and real trajectories, i.e if the drone \n            successfully followed its given trajectory. Returns True if deviation < epsilon(defined in plotter_class.py) at every timestep, false if not.  '''\n  \n        # NB : the mcap filename is almost the same as the folder name but has _0 at the end\n        inputbag = f\"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.mcap\"\n        output_csv = f\"{str(self.ros2_ws)}/results/test_{testname}/test_{testname}_0.csv\"\n\n        writer = McapHandler()\n        writer.write_mcap_to_csv(inputbag, output_csv)  #translate bag from mcap to csv\n        output_pdf = f\"{str(self.ros2_ws)}/results/test_{testname}/results_{testname}.pdf\"\n        rosbag_csv = output_csv\n\n        plotter = Plotter(sim_backend=TestFlights.SIM)\n        plotter.create_figures(self.test_file, rosbag_csv, output_pdf) #plot the data\n        return plotter.test_passed()\n    \n\n\n    def test_figure8(self):\n        self.test_file = \"figure8_ideal_traj.csv\"\n        # run test\n        self.record_start_and_clean(\"figure8\", 20)\n        #create the plot etc\n        test_passed = self.translate_plot_and_check(\"figure8\")\n        assert test_passed, \"figure8 test failed : deviation larger than epsilon\"\n\n    # def test_multi_trajectory(self):\n    #     self.test_file = \"multi_trajectory_traj0_ideal.csv\"\n    #     self.record_start_and_clean(\"multi_trajectory\", 80)\n    #     test_passed = self.translate_plot_and_check(\"multi_trajectory\")\n    #     assert test_passed, \"multitrajectory test failed : deviation larger than epsilon\"\n\n\n\nif __name__ == '__main__':\n    from argparse import ArgumentParser\n    import sys\n    parser = ArgumentParser(description=\"Runs (real or simulated) flight tests with pytest framework\")\n    parser.add_argument(\"--sim\", action=\"store_true\", help=\"Runs the test from the simulation backend\")\n    args, other_args = parser.parse_known_args()\n    if args.sim :\n        TestFlights.SIM = True\n\n    unittest.main(argv=[sys.argv[0]] + other_args)\n\n"
  }
]